From c94cfd1bc6b0978fab2c9a7e1a1efb7b379df589 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 13 Nov 2024 14:15:33 +0900 Subject: [PATCH] fix: access invalid field Signed-off-by: Hayato Mizushima --- .../scripts/perception_evaluator_node.py | 20 ++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/driving_log_replayer_v2/scripts/perception_evaluator_node.py b/driving_log_replayer_v2/scripts/perception_evaluator_node.py index 55c1f341..dfa3621b 100755 --- a/driving_log_replayer_v2/scripts/perception_evaluator_node.py +++ b/driving_log_replayer_v2/scripts/perception_evaluator_node.py @@ -210,10 +210,14 @@ def list_dynamic_object_from_ros_msg( unix_time=unix_time, frame_id=self.__frame_id, position=eval_conversions.position_from_ros_msg( - perception_object.kinematics.pose_with_covariance.pose.position, + perception_object.kinematics.pose_with_covariance.pose.position + if isinstance(perception_object, DetectedObject | TrackedObject) + else perception_object.kinematics.initial_pose_with_covariance.pose.position ), orientation=eval_conversions.orientation_from_ros_msg( - perception_object.kinematics.pose_with_covariance.pose.orientation, + perception_object.kinematics.pose_with_covariance.pose.orientation + if isinstance(perception_object, DetectedObject | TrackedObject) + else perception_object.kinematics.initial_pose_with_covariance.pose.orientation ), shape=Shape( shape_type=shape_type, @@ -226,10 +230,16 @@ def list_dynamic_object_from_ros_msg( ), ), velocity=eval_conversions.velocity_from_ros_msg( - perception_object.kinematics.twist_with_covariance.twist.linear, + perception_object.kinematics.twist_with_covariance.twist.linear + if isinstance(perception_object, DetectedObject | TrackedObject) + else perception_object.kinematics.initial_twist_with_covariance.twist.linear ), - pose_covariance=perception_object.kinematics.pose_with_covariance.covariance, - twist_covariance=perception_object.kinematics.twist_with_covariance.covariance, + pose_covariance=perception_object.kinematics.pose_with_covariance.covariance + if isinstance(perception_object, DetectedObject | TrackedObject) + else perception_object.kinematics.initial_pose_with_covariance.covariance, + twist_covariance=perception_object.kinematics.twist_with_covariance.covariance + if isinstance(perception_object, DetectedObject | TrackedObject) + else perception_object.kinematics.initial_twist_with_covariance.covariance, semantic_score=most_probable_classification.probability, semantic_label=label, uuid=uuid,