Skip to content

Commit

Permalink
published nand gps seqnum/time when recieved
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Jan 9, 2025
1 parent 5d2eadb commit 9ab7370
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion rb_ws/src/buggy/buggy/serial/ros_to_bnyahaj.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import rclpy
from rclpy import Node

from std_msgs.msg import Float64, Int8, Int32, UInt8, Bool
from std_msgs.msg import Float64, Int8, Int32, UInt8, Bool, UInt64
from host_comm import *
from nav_msgs.msg import Odometry

Expand Down Expand Up @@ -101,6 +101,12 @@ def __init__(self, teensy_name):
self.nand_gps_acc_publisher = self.create_publisher(
Float64, "NAND/debug/gps_accuracy", 1
)
self.nand_gps_seqnum_publisher = self.create_publisher(
Int32, "NAND/debug/gps_seqnum", 1
)
self.nand_gps_time_publisher = self.create_publisher(
UInt64, "NAND/debug/gps_time", 1
)

# SC SENSOR PUBLISHERS
self.sc_velocity_publisher = self.create_publisher(
Expand Down Expand Up @@ -204,6 +210,8 @@ def reader_thread(self):
self.nand_gps_odom_publisher.publish(odom)
self.nand_gps_fix_publisher.publish(packet.gps_fix)
self.nand_gps_acc_publisher.publish(packet.accuracy)
self.nand_gps_seqnum_publisher.publish(packet.gps_seqnum)
self.nand_gps_time_publisher.publish(packet.gps_time)

elif isinstance(packet, Radio):

Expand Down

0 comments on commit 9ab7370

Please sign in to comment.