diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index 1122bf7b4b18e..d8b5599cc1ca7 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -244,6 +244,11 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() std::atan2(compensated_velocity.y, compensated_velocity.x)); geometry_msgs::msg::PoseStamped transformed_pose_stamped{}; + if (transform_ == nullptr) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 5000, "getTransform failed. radar output will be empty."); + return tracked_objects; + } tf2::doTransform(radar_pose_stamped, transformed_pose_stamped, *transform_); kinematics.pose_with_covariance.pose = transformed_pose_stamped.pose; kinematics.pose_with_covariance.pose.orientation =