diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
index 326964eefdeae..fb2be1dd610ba 100644
--- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
+++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
@@ -6,6 +6,7 @@
+
@@ -14,6 +15,7 @@
+
diff --git a/perception/lidar_centerpoint/lib/ros_utils.cpp b/perception/lidar_centerpoint/lib/ros_utils.cpp
index 57237609139e5..8bc5f955efab4 100644
--- a/perception/lidar_centerpoint/lib/ros_utils.cpp
+++ b/perception/lidar_centerpoint/lib/ros_utils.cpp
@@ -71,13 +71,15 @@ void box3DToDetectedObject(
tier4_autoware_utils::createTranslation(box3d.length, box3d.width, box3d.height);
// twist
- float vel_x = box3d.vel_x;
- float vel_y = box3d.vel_y;
- geometry_msgs::msg::Twist twist;
- twist.linear.x = std::sqrt(std::pow(vel_x, 2) + std::pow(vel_y, 2));
- twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw);
- obj.kinematics.twist_with_covariance.twist = twist;
- obj.kinematics.has_twist = has_twist;
+ if (has_twist) {
+ float vel_x = box3d.vel_x;
+ float vel_y = box3d.vel_y;
+ geometry_msgs::msg::Twist twist;
+ twist.linear.x = std::sqrt(std::pow(vel_x, 2) + std::pow(vel_y, 2));
+ twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw);
+ obj.kinematics.twist_with_covariance.twist = twist;
+ obj.kinematics.has_twist = has_twist;
+ }
}
uint8_t getSemanticType(const std::string & class_name)