Skip to content

Commit ef7a0d8

Browse files
committed
align TopicMetadata interface
Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>
1 parent 0bd9b23 commit ef7a0d8

4 files changed

Lines changed: 42 additions & 35 deletions

File tree

driving_log_replayer_v2/driving_log_replayer_v2/ground_segmentation/runner.py

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020

2121
import numpy as np
2222
import ros2_numpy
23-
from rosbag2_py import TopicMetadata
2423
from std_msgs.msg import String
2524

2625
from driving_log_replayer_v2.ground_segmentation.evaluation_manager import (
@@ -29,11 +28,13 @@
2928
from driving_log_replayer_v2.ground_segmentation.models import GroundSegmentationResult
3029
from driving_log_replayer_v2.ground_segmentation.models import GroundSegmentationScenario
3130
import driving_log_replayer_v2.perception_eval_conversions as eval_conversions
31+
from driving_log_replayer_v2.post_process.ros2_utils import get_topic_metadata
3232
from driving_log_replayer_v2.post_process.runner import ConvertedData
3333
from driving_log_replayer_v2.post_process.runner import Runner
3434
from driving_log_replayer_v2.post_process.runner import UseCaseInfo
3535

3636
if TYPE_CHECKING:
37+
from rosbag2_py import TopicMetadata
3738
from sensor_msgs.msg import PointCloud2
3839
from std_msgs.msg import Header
3940

@@ -105,11 +106,9 @@ def _get_use_case_info_list(
105106

106107
def _get_external_record_topics(self) -> list[TopicMetadata]:
107108
return [
108-
TopicMetadata(
109-
id=0,
109+
get_topic_metadata(
110110
name="/driving_log_replayer_v2/ground_segmentation/results",
111-
type="std_msgs/msg/String",
112-
serialization_format="cdr",
111+
topic_type="std_msgs/msg/String",
113112
),
114113
]
115114

driving_log_replayer_v2/driving_log_replayer_v2/perception/runner.py

Lines changed: 10 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
from autoware_perception_msgs.msg import DetectedObjects
2525
from autoware_perception_msgs.msg import PredictedObjects
2626
from autoware_perception_msgs.msg import TrackedObjects
27-
from rosbag2_py import TopicMetadata
2827
from std_msgs.msg import Header
2928
from std_msgs.msg import String
3029

@@ -40,6 +39,7 @@
4039
from driving_log_replayer_v2.perception.topics import load_evaluation_topics
4140
import driving_log_replayer_v2.perception_eval_conversions as eval_conversions
4241
from driving_log_replayer_v2.planning_control import PlanningFactorResult
42+
from driving_log_replayer_v2.post_process.ros2_utils import get_topic_metadata
4343
from driving_log_replayer_v2.post_process.ros2_utils import lookup_transform
4444
from driving_log_replayer_v2.post_process.runner import ConvertedData
4545
from driving_log_replayer_v2.post_process.runner import Runner
@@ -51,6 +51,7 @@
5151
from perception_eval.config import PerceptionEvaluationConfig
5252
from perception_eval.evaluation.result.perception_frame_result import PerceptionFrameResult
5353
from perception_eval.tool import PerceptionAnalyzer3D
54+
from rosbag2_py import TopicMetadata
5455
from visualization_msgs.msg import MarkerArray
5556

5657
from driving_log_replayer_v2.post_process.evaluator import FrameResult
@@ -187,29 +188,21 @@ def _get_use_case_info_list(
187188

188189
def _get_external_record_topics(self) -> list[TopicMetadata]:
189190
return [
190-
TopicMetadata(
191-
id=0,
191+
get_topic_metadata(
192192
name="/driving_log_replayer_v2/marker/ground_truth",
193-
type="visualization_msgs/msg/MarkerArray",
194-
serialization_format="cdr",
193+
topic_type="visualization_msgs/msg/MarkerArray",
195194
),
196-
TopicMetadata(
197-
id=0,
195+
get_topic_metadata(
198196
name="/driving_log_replayer_v2/marker/results",
199-
type="visualization_msgs/msg/MarkerArray",
200-
serialization_format="cdr",
197+
topic_type="visualization_msgs/msg/MarkerArray",
201198
),
202-
TopicMetadata(
203-
id=0,
199+
get_topic_metadata(
204200
name="/driving_log_replayer_v2/perception/results",
205-
type="std_msgs/String",
206-
serialization_format="cdr",
201+
topic_type="std_msgs/String",
207202
),
208-
TopicMetadata(
209-
id=0,
203+
get_topic_metadata(
210204
name="/driving_log_replayer_v2/planning_factor/results",
211-
type="std_msgs/String",
212-
serialization_format="cdr",
205+
topic_type="std_msgs/String",
213206
),
214207
]
215208

driving_log_replayer_v2/driving_log_replayer_v2/perception_fp/runner.py

Lines changed: 9 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,6 @@
3131
from perception_eval.common.object import DynamicObject
3232
from perception_eval.config import PerceptionEvaluationConfig
3333
from rclpy.time import Duration
34-
from rosbag2_py import TopicMetadata
3534
from sensor_msgs.msg import PointCloud2
3635
from std_msgs.msg import ColorRGBA
3736
from std_msgs.msg import Header
@@ -48,12 +47,15 @@
4847
from driving_log_replayer_v2.perception_fp.models import PerceptionFPScenario
4948
from driving_log_replayer_v2.perception_fp.models import Polygon3D
5049
from driving_log_replayer_v2.post_process.ros2_utils import convert_to_homogeneous_matrix
50+
from driving_log_replayer_v2.post_process.ros2_utils import get_topic_metadata
5151
from driving_log_replayer_v2.post_process.ros2_utils import lookup_transform
5252
from driving_log_replayer_v2.post_process.runner import ConvertedData
5353
from driving_log_replayer_v2.post_process.runner import Runner
5454
from driving_log_replayer_v2.post_process.runner import UseCaseInfo
5555

5656
if TYPE_CHECKING:
57+
from rosbag2_py import TopicMetadata
58+
5759
from driving_log_replayer_v2.post_process.evaluator import FrameResult
5860
from driving_log_replayer_v2.result import ResultWriter
5961

@@ -299,23 +301,17 @@ def _get_use_case_info_list(
299301

300302
def _get_external_record_topics(self) -> list[TopicMetadata]:
301303
return [
302-
TopicMetadata(
303-
id=0,
304+
get_topic_metadata(
304305
name="/driving_log_replayer_v2/perception_fp/results",
305-
type="std_msgs/msg/String",
306-
serialization_format="cdr",
306+
topic_type="std_msgs/msg/String",
307307
),
308-
TopicMetadata(
309-
id=0,
308+
get_topic_metadata(
310309
name="/driving_log_replayer_v2/perception_fp/non_detection_area",
311-
type="visualization_msgs/msg/MarkerArray",
312-
serialization_format="cdr",
310+
topic_type="visualization_msgs/msg/MarkerArray",
313311
),
314-
TopicMetadata(
315-
id=0,
312+
get_topic_metadata(
316313
name="/driving_log_replayer_v2/perception_fp/fp_objects",
317-
type="visualization_msgs/msg/MarkerArray",
318-
serialization_format="cdr",
314+
topic_type="visualization_msgs/msg/MarkerArray",
319315
),
320316
]
321317

driving_log_replayer_v2/driving_log_replayer_v2/post_process/ros2_utils.py

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -357,3 +357,22 @@ def convert_to_homogeneous_matrix(transform: TransformStamped) -> np.ndarray:
357357
matrix[0:3, 3] = [translation.x, translation.y, translation.z]
358358
matrix[0:3, 0:3] = quaternion.rotation_matrix
359359
return matrix
360+
361+
362+
# TODO: remove this function after ROS Jazzy is supported
363+
def get_topic_metadata(name: str, topic_type: str) -> TopicMetadata:
364+
# for humble
365+
try:
366+
return TopicMetadata(
367+
name=name,
368+
type=topic_type,
369+
serialization_format="cdr",
370+
)
371+
# for jazzy
372+
except TypeError:
373+
return TopicMetadata(
374+
id=0,
375+
name=name,
376+
type=topic_type,
377+
serialization_format="cdr",
378+
)

0 commit comments

Comments
 (0)