Skip to content

Commit

Permalink
pass style checks
Browse files Browse the repository at this point in the history
  • Loading branch information
pearlastrid committed Jan 24, 2025
1 parent 0c57e60 commit 9688cb1
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 26 deletions.
10 changes: 1 addition & 9 deletions launch/localization.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@

def generate_launch_description():


rover_gps_driver_node = Node(
package="mrover",
executable="rover_gps_driver",
Expand All @@ -34,11 +33,4 @@ def generate_launch_description():
parameters=[os.path.join(get_package_share_directory("mrover"), "config", "zed.yaml")],
)


return LaunchDescription(
[
rover_gps_driver_node,
gps_linearization_node,
zed_node
]
)
return LaunchDescription([rover_gps_driver_node, gps_linearization_node, zed_node])
2 changes: 0 additions & 2 deletions launch/localization_basestation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,13 @@

def generate_launch_description():


basestation_gps_driver_node = Node(
package="mrover",
executable="basestation_gps_driver.py",
name="basestation_gps_driver",
parameters=[os.path.join(get_package_share_directory("mrover"), "config", "localization.yaml")],
)


return LaunchDescription(
[
basestation_gps_driver_node,
Expand Down
12 changes: 6 additions & 6 deletions localization/basestation_gps_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,17 +65,17 @@ def spin(self) -> None:
for i in range(msg.numSvs):
gnssId = getattr(msg, f"gnssId_{i+1:02d}")
cno = getattr(msg, f"cno_{i+1:02d}")
if (gnssId == 0):
if gnssId == 0:
self.get_logger().info(f"GPS signal strength: {cno}")
elif (gnssId == 1):
elif gnssId == 1:
self.get_logger().info(f"SBAS signal strength: {cno}")
elif (gnssId == 2):
elif gnssId == 2:
self.get_logger().info(f"Galileo signal strength: {cno}")
elif (gnssId == 3):
elif gnssId == 3:
self.get_logger().info(f"BeiDou signal strength: {cno}")
elif (gnssId == 5):
elif gnssId == 5:
self.get_logger().info(f"QZSS signal strength: {cno}")
elif (gnssId == 6):
elif gnssId == 6:
self.get_logger().info(f"GLONASS signal strength: {cno}")

rclpy.spin_once(self, timeout_sec=0)
Expand Down
17 changes: 8 additions & 9 deletions localization/gps_linearization.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
import message_filters
from lie.conversions import to_tf_tree, SE3


class GPSLinearization(Node):

def __init__(self) -> None:
Expand Down Expand Up @@ -54,25 +55,23 @@ def __init__(self) -> None:
self.sync = message_filters.ApproximateTimeSynchronizer([self.gps_sub, self.orientation_sub], 10, 1)
self.sync.registerCallback(self.synced_gps_imu_callback)


def synced_gps_imu_callback(self, gps_msg: NavSatFix, imu_msg: Imu):

if np.isnan([gps_msg.latitude, gps_msg.longitude, gps_msg.altitude]).any():
self.get_logger().warn("Received NaN GPS data, ignoring")
return

quaternion = np.array([imu_msg.orientation.x, imu_msg.orientation.y, imu_msg.orientation.z, imu_msg.orientation.w])
quaternion = np.array(
[imu_msg.orientation.x, imu_msg.orientation.y, imu_msg.orientation.z, imu_msg.orientation.w]
)
quaternion = quaternion / np.linalg.norm(quaternion)

x, y, z = geodetic2enu(gps_msg.latitude, gps_msg.longitude, gps_msg.altitude, self.ref_lat, self.ref_lon, self.ref_alt, deg=True)
x, y, z = geodetic2enu(
gps_msg.latitude, gps_msg.longitude, gps_msg.altitude, self.ref_lat, self.ref_lon, self.ref_alt, deg=True
)
pose = SE3(position=np.array([x, y, z]), quaternion=quaternion)

to_tf_tree(
tf_broadcaster=self.tf_broadcaster,
se3=pose,
child_frame="base_link",
parent_frame=self.world_frame
)
to_tf_tree(tf_broadcaster=self.tf_broadcaster, se3=pose, child_frame="base_link", parent_frame=self.world_frame)

self.get_logger().info(f"Published to TF Tree: Position({x}, {y}, {z}), Orientation({imu_msg.orientation})")

Expand Down

0 comments on commit 9688cb1

Please sign in to comment.