Skip to content

Commit 8f50806

Browse files
committed
Remove camera_info_topic and image_raw_topic ROS parameters - these should be static and changes handled through ROS topic remapping instead.
1 parent d6667cb commit 8f50806

File tree

7 files changed

+17
-60
lines changed

7 files changed

+17
-60
lines changed

config/test_typhoon_h480__ksql_airport.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,6 @@ mock_gps_node:
1212
request_timeout: 10
1313
misc:
1414
autopilot: 'gisnav.autopilots.px4_micrortps.PX4microRTPS'
15-
image_topic: '/camera/image_raw'
16-
camera_info_topic: '/camera/camera_info'
1715
mock_gps_selection: 1
1816
attitude_deviation_threshold: 10
1917
#max_pitch: 30

config/typhoon_h480__ksql_airport.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@ mock_gps_node:
1111
request_timeout: 10
1212
misc:
1313
autopilot: 'gisnav.autopilots.px4_micrortps.PX4microRTPS'
14-
image_topic: '/camera/image_raw'
15-
camera_info_topic: '/camera/camera_info'
1614
attitude_deviation_threshold: 10 # degrees
1715
max_pitch: 30 # 30 # Used by _should_match
1816
min_match_altitude: 50

config/typhoon_h480__ksql_airport_ardupilot.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@ mock_gps_node:
1111
request_timeout: 10
1212
misc:
1313
autopilot: 'gisnav.autopilots.ardupilot_mavros.ArduPilotMAVROS'
14-
image_topic: '/camera/image_raw'
15-
camera_info_topic: '/camera/camera_info'
1614
attitude_deviation_threshold: 10 # degrees
1715
max_pitch: 50 # 30 # Make bigger with static_camera: True # Used by _should_match
1816
min_match_altitude: 50

gisnav/autopilots/ardupilot_mavros.py

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -41,16 +41,13 @@ class ArduPilotMAVROS(Autopilot):
4141
}
4242
"""ROS topics to subscribe"""
4343

44-
def __init__(self, node: rclpy.node.Node, camera_info_topic: str, image_topic: str,
45-
image_callback: Callable[[Image], None]) -> None:
44+
def __init__(self, node: rclpy.node.Node, image_callback: Callable[[Image], None]) -> None:
4645
"""Initialize class
4746
4847
:param node: Parent node that handles the ROS subscriptions
49-
:param camera_info_topic: ROS camera info topic to subscribe to
50-
:param image_topic: ROS camera image (raw) topic to subscribe to
5148
:param image_callback: Callback function for camera image
5249
"""
53-
super().__init__(node, camera_info_topic, image_topic, image_callback)
50+
super().__init__(node, image_callback)
5451

5552
# TODO: copy to shared folder and use relative path
5653
self._egm96 = GeoidPGM('/usr/share/GeographicLib/geoids/egm96-5.pgm', kind=-3)

gisnav/autopilots/autopilot.py

Lines changed: 12 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -24,27 +24,28 @@ class Autopilot(ABC):
2424
TELEMETRY_EXPIRATION_LIMIT = 1e6
2525
"""Expiration period in usec for vehicle state (if telemetry data is older than this it should not be used)"""
2626

27-
def __init__(self, node: rclpy.node.Node, camera_info_topic: str, image_topic: str,
28-
on_image_callback: Callable[[ImageData], None]) -> None:
27+
CAMERA_INFO_TOPIC = 'camera/camera_info'
28+
"""ROS camera info (:class:`.sensor_msgs.msg.CameraInfo`) topic to subscribe to"""
29+
30+
IMAGE_RAW_TOPIC = 'camera/image_raw'
31+
"""ROS image raw (:class:`.sensor_msgs.msg.Image`) topic to subscribe to"""
32+
33+
def __init__(self, node: rclpy.node.Node, on_image_callback: Callable[[ImageData], None]) -> None:
2934
"""Initializes autopilot adapter
3035
3136
:param node: Parent node that handles the ROS subscriptions
32-
:param camera_info_topic: ROS camera info topic to subscribe to
33-
:param image_topic: ROS topic for :class:`.sensor_msgs.msg.Image`
3437
:param on_image_callback: Callback function for camera image
3538
"""
3639
self._node = node
3740
self._topics = {}
3841

3942
# Subscribe to camera data topic
4043
self.camera_data = None
41-
self._camera_info_topic = camera_info_topic
42-
self._subscribe(self._camera_info_topic, CameraInfo, self._camera_info_callback,
44+
self._subscribe(self.CAMERA_INFO_TOPIC, CameraInfo, self._camera_info_callback,
4345
rclpy.qos.QoSPresetProfiles.SENSOR_DATA.value)
4446

4547
# Image topic callback gets access to base node through provided on_image_callback
46-
self._image_topic = image_topic
47-
self._subscribe(self._image_topic, Image, on_image_callback, rclpy.qos.QoSPresetProfiles.SENSOR_DATA.value)
48+
self._subscribe(self.IMAGE_RAW_TOPIC, Image, on_image_callback, rclpy.qos.QoSPresetProfiles.SENSOR_DATA.value)
4849

4950
@property
5051
def _node(self) -> rclpy.node.Node:
@@ -76,26 +77,6 @@ def camera_data(self, value: Optional[CameraData]) -> None:
7677
assert_type(value, get_args(Optional[CameraData]))
7778
self.__camera_data = value
7879

79-
@property
80-
def _camera_info_topic(self) -> str:
81-
"""CameraInfo ROS topic name."""
82-
return self.__camera_info_topic
83-
84-
@_camera_info_topic.setter
85-
def _camera_info_topic(self, value: str) -> None:
86-
assert_type(value, str)
87-
self.__camera_info_topic = value
88-
89-
@property
90-
def _image_topic(self) -> str:
91-
"""Image ROS topic name."""
92-
return self.__image_topic
93-
94-
@_image_topic.setter
95-
def _image_topic(self, value: str) -> None:
96-
assert_type(value, str)
97-
self.__image_topic = value
98-
9980
def _subscribe(self, topic_name: str, class_: type, callback: Callable, qos: rclpy.qos.QoSProfile) -> None:
10081
"""Subscribes to ROS topic
10182
@@ -137,10 +118,10 @@ def _camera_info_callback(self, msg: CameraInfo) -> None:
137118
return None
138119
else:
139120
self.camera_data = CameraData(k=msg.k.reshape((3, 3)), dim=Dim(msg.height, msg.width))
140-
camera_info_topic = self._topics.get(self._camera_info_topic, {}).get(self._TOPICS_SUBSCRIBER_KEY, None)
141-
if camera_info_topic is not None:
121+
camera_info_sub = self._topics.get(self.CAMERA_INFO_TOPIC, {}).get(self._TOPICS_SUBSCRIBER_KEY, None)
122+
if camera_info_sub is not None:
142123
# Assume camera info is static, destroy subscription
143-
camera_info_topic.destroy()
124+
camera_info_sub.destroy()
144125

145126
@property
146127
@abstractmethod

gisnav/autopilots/px4_micrortps.py

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -40,16 +40,13 @@ class PX4microRTPS(Autopilot):
4040
}
4141
"""ROS topics to subscribe"""
4242

43-
def __init__(self, node: rclpy.node.Node, camera_info_topic: str, image_topic: str,
44-
image_callback: Callable[[Image], None]) -> None:
43+
def __init__(self, node: rclpy.node.Node, image_callback: Callable[[Image], None]) -> None:
4544
"""Initialize class
4645
4746
:param node: Parent node that handles the ROS subscriptions
48-
:param camera_info_topic: ROS camera info topic to subscribe to
49-
:param image_topic: ROS camera image (raw) topic to subscribe to
5047
:param image_callback: Callback function for camera image
5148
"""
52-
super().__init__(node, camera_info_topic, image_topic, image_callback)
49+
super().__init__(node, image_callback)
5350

5451
self._setup_subscribers()
5552

gisnav/nodes/base_node.py

Lines changed: 1 addition & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -81,12 +81,6 @@ class BaseNode(Node, ABC):
8181
ROS_D_MISC_AUTOPILOT = 'gisnav.autopilots.px4_micrortps.PX4microRTPS'
8282
"""Default autopilot adapter"""
8383

84-
ROS_D_MISC_IMAGE_TOPIC = '/camera/image_raw'
85-
"""Default ROS image topic name"""
86-
87-
ROS_D_MISC_CAMERA_INFO_TOPIC = '/camera/camera_info'
88-
"""Default ROS camera info topic name"""
89-
9084
ROS_D_STATIC_CAMERA = False
9185
"""Default value for static camera flag (true for static camera facing down from vehicle body)"""
9286

@@ -183,8 +177,6 @@ class BaseNode(Node, ABC):
183177
('wms.srs', ROS_D_WMS_SRS),
184178
('wms.request_timeout', ROS_D_WMS_REQUEST_TIMEOUT),
185179
('misc.autopilot', ROS_D_MISC_AUTOPILOT, read_only),
186-
('misc.camera_info_topic', ROS_D_MISC_CAMERA_INFO_TOPIC, read_only),
187-
('misc.image_topic', ROS_D_MISC_IMAGE_TOPIC, read_only),
188180
('misc.static_camera', ROS_D_STATIC_CAMERA, read_only),
189181
('misc.attitude_deviation_threshold', ROS_D_MISC_ATTITUDE_DEVIATION_THRESHOLD),
190182
('misc.max_pitch', ROS_D_MISC_MAX_PITCH),
@@ -234,12 +226,8 @@ def __init__(self, name: str, package_share_dir: str) -> None:
234226
# Autopilot bridge
235227
ap = self.get_parameter('misc.autopilot').get_parameter_value().string_value or self.ROS_D_MISC_AUTOPILOT
236228
ap: Autopilot = self._load_autopilot(ap)
237-
image_topic = self.get_parameter('misc.image_topic').get_parameter_value().string_value \
238-
or self.ROS_D_MISC_IMAGE_TOPIC
239-
camera_info_topic = self.get_parameter('misc.camera_info_topic').get_parameter_value().string_value \
240-
or self.ROS_D_MISC_CAMERA_INFO_TOPIC
241229
# TODO: implement passing init args, kwargs
242-
self._bridge = ap(self, camera_info_topic, image_topic, self._image_raw_callback)
230+
self._bridge = ap(self, self._image_raw_callback)
243231

244232
# Converts image_raw to cv2 compatible image
245233
self._cv_bridge = CvBridge()

0 commit comments

Comments
 (0)