Skip to content

Commit

Permalink
published nand gps seqnum
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Jan 9, 2025
1 parent d736ce9 commit 94a1139
Showing 1 changed file with 8 additions and 4 deletions.
12 changes: 8 additions & 4 deletions rb_ws/src/buggy/buggy/serial/ros_to_bnyahaj.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,9 @@ def __init__(self, teensy_name):
self.rc_uplink_qual_publisher = self.create_publisher(
UInt8, "/debug/rc_uplink_quality", 1
)
self.nand_gps_seqnum_publisher = self.create_publisher(
Int32, "/debug/NAND_gps_seqnum", 1
)

# SERIAL DEBUG PUBLISHERS
self.roundtrip_time_publisher = self.create_publisher(
Expand All @@ -105,14 +108,13 @@ def __init__(self, teensy_name):
self.nand_gps_acc_publisher = self.create_publisher(
Float64, "/debug/gps_accuracy", 1
)
self.nand_gps_seqnum_publisher = self.create_publisher(
Int32, "/debug/gps_seqnum", 1
)

self.nand_gps_time_publisher = self.create_publisher(
UInt64, "/debug/gps_time", 1
)

if self.self_name == "SC":

# SC SENSOR PUBLISHERS
self.sc_velocity_publisher = self.create_publisher(
Float64, "/sensors/velocity", 1
Expand All @@ -121,6 +123,7 @@ def __init__(self, teensy_name):
Float64, "/sensors/steering_angle", 1
)

# RADIO DATA PUBLISHER
self.observed_nand_odom_publisher = self.create_publisher(
Odometry, "/NAND_raw_state", 1
)
Expand Down Expand Up @@ -224,7 +227,8 @@ def reader_thread(self):
odom.pose.pose.position.x = packet.nand_east_gps
odom.pose.pose.position.y = packet.nand_north_gps
self.observed_nand_odom_publisher.publish(odom)
self.get_logger().debug(f'Radio Received NAND GPS Seqnum: {packet.gps_seqnum}')
self.nand_gps_seqnum_publisher.publish(packet.gps_seqnum)




Expand Down

0 comments on commit 94a1139

Please sign in to comment.