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

feat: add twist information for detected object on rviz #1014

Closed
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 @@ -52,6 +52,28 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg)
label_marker_ptr->id = id++;
add_marker(label_marker_ptr);
}

// Get marker for velocity text
geometry_msgs::msg::Point vel_vis_position;
vel_vis_position.x = object.kinematics.pose_with_covariance.pose.position.x;
vel_vis_position.y = object.kinematics.pose_with_covariance.pose.position.y - 1.0;
vel_vis_position.z = object.kinematics.pose_with_covariance.pose.position.z - 1.0;
auto velocity_text_marker = get_velocity_text_marker_ptr(
object.kinematics.twist_with_covariance.twist, vel_vis_position, object.classification);
if (velocity_text_marker) {
auto velocity_text_marker_ptr = velocity_text_marker.value();
velocity_text_marker_ptr->header = msg->header;
add_marker(velocity_text_marker_ptr);
}

// Get marker for twist
auto twist_marker = get_twist_marker_ptr(
object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance);
if (twist_marker) {
auto twist_marker_ptr = twist_marker.value();
twist_marker_ptr->header = msg->header;
add_marker(twist_marker_ptr);
}
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms

// Get marker for id
geometry_msgs::msg::Point uuid_vis_position;
uuid_vis_position.x = object.kinematics.initial_pose_with_covariance.pose.position.x - 0.5;
uuid_vis_position.y = object.kinematics.initial_pose_with_covariance.pose.position.y;
uuid_vis_position.x = object.kinematics.initial_pose_with_covariance.pose.position.x;
uuid_vis_position.y = object.kinematics.initial_pose_with_covariance.pose.position.y - 0.5;
Comment on lines +57 to +58
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@scepter914 Can you share the image taken from view point of a third person?
I think it's good from BEV, but from view point of a third person it would be out of alignment.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It may be better to merge into one string and publish

uuid_vis_position.z = object.kinematics.initial_pose_with_covariance.pose.position.z - 0.5;

auto id_marker =
Expand All @@ -79,8 +79,8 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms

// Get marker for velocity text
geometry_msgs::msg::Point vel_vis_position;
vel_vis_position.x = uuid_vis_position.x - 0.5;
vel_vis_position.y = uuid_vis_position.y;
vel_vis_position.x = uuid_vis_position.x;
vel_vis_position.y = uuid_vis_position.y - 0.5;
vel_vis_position.z = uuid_vis_position.z - 0.5;
auto velocity_text_marker = get_velocity_text_marker_ptr(
object.kinematics.initial_twist_with_covariance.twist, vel_vis_position,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg)

// Get marker for id
geometry_msgs::msg::Point uuid_vis_position;
uuid_vis_position.x = object.kinematics.pose_with_covariance.pose.position.x - 0.5;
uuid_vis_position.y = object.kinematics.pose_with_covariance.pose.position.y;
uuid_vis_position.x = object.kinematics.pose_with_covariance.pose.position.x;
uuid_vis_position.y = object.kinematics.pose_with_covariance.pose.position.y - 0.5;
uuid_vis_position.z = object.kinematics.pose_with_covariance.pose.position.z - 0.5;

auto id_marker =
Expand All @@ -81,8 +81,8 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg)

// Get marker for velocity text
geometry_msgs::msg::Point vel_vis_position;
vel_vis_position.x = uuid_vis_position.x - 0.5;
vel_vis_position.y = uuid_vis_position.y;
vel_vis_position.x = uuid_vis_position.x;
vel_vis_position.y = uuid_vis_position.y - 0.5;
vel_vis_position.z = uuid_vis_position.z - 0.5;
auto velocity_text_marker = get_velocity_text_marker_ptr(
object.kinematics.twist_with_covariance.twist, vel_vis_position, object.classification);
Expand Down