Skip to content

Commit

Permalink
Add additional type to accepted ROS2 messages
Browse files Browse the repository at this point in the history
  • Loading branch information
cfirthae committed May 9, 2024
1 parent 9e92a64 commit 4513e60
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions onair/data_handling/ros_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import rclpy
from rclpy.node import Node
from std_msgs.msg import Bool, String
from geometry_msgs.msg import PoseStamped

from onair.data_handling.on_air_data_source import OnAirDataSource
from onair.data_handling.tlm_json_parser import parseJson
Expand All @@ -31,6 +32,7 @@
ROS_MSG_TYPE_MAPPINGS = {
"Bool": Bool,
"String": String,
"PoseStamped": PoseStamped,
}


Expand Down Expand Up @@ -107,12 +109,12 @@ def get_next(self):
self.topic_active = True
header_string = self.sub_node.received_topic
index = low_level_data['headers'].index(header_string)
low_level_data['data'][index] = self.sub_node.received_msg.data
low_level_data['data'][index] = self.sub_node.received_msg
else:
rclpy.spin_once(self.sub_node)
header_string = self.sub_node.received_topic
index = low_level_data['headers'].index(header_string)
low_level_data['data'][index] = self.sub_node.received_msg.data
low_level_data['data'][index] = self.sub_node.received_msg

self.low_level_data[self.double_buffer_read_index] = low_level_data
return low_level_data['data']
Expand Down

0 comments on commit 4513e60

Please sign in to comment.