Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(lidar_centerpoint): fix has_twist condition #1753

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="model_path" default="$(find-pkg-share lidar_centerpoint)/data"/>
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
<arg name="score_threshold" default="0.45"/>
<arg name="has_twist" default="false"/>

<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
Expand All @@ -14,6 +15,7 @@
<param name="densification_world_frame_id" value="map"/>
<param name="densification_num_past_frames" value="1"/>
<param name="trt_precision" value="fp16"/>
<param name="has_twist" value="$(var has_twist)"/>
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
Expand Down
16 changes: 9 additions & 7 deletions perception/lidar_centerpoint/lib/ros_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down