Skip to content

Commit

Permalink
feat: add line_width property to object display (tier4#1206)
Browse files Browse the repository at this point in the history
* feat: add line_width property to object display

Signed-off-by: tomoya.kimura <[email protected]>

* remove default value

Signed-off-by: tomoya.kimura <[email protected]>

* add the description of parameter

Signed-off-by: tomoya.kimura <[email protected]>
  • Loading branch information
tkimura4 authored and boyali committed Oct 3, 2022
1 parent 753e74a commit ecd76b1
Show file tree
Hide file tree
Showing 6 changed files with 18 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -75,12 +75,13 @@ const std::map<
/// \param centroid Centroid position of the shape in Object.header.frame_id frame
/// \param orientation Orientation of the shape in Object.header.frame_id frame
/// \param color_rgba Color and alpha values to use for the marker
/// \param line_width Line thickness around the object
/// \return Marker ptr. Id and header will have to be set by the caller
AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr
get_shape_marker_ptr(
const autoware_auto_perception_msgs::msg::Shape & shape_msg,
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
const std_msgs::msg::ColorRGBA & color_rgba);
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width);

/// \brief Convert the given polygon into a marker representing the shape in 3d
/// \param centroid Centroid position of the shape in Object.header.frame_id frame
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
m_display_path_confidence_property{
"Display Predicted Path Confidence", true, "Enable/disable predicted paths visualization",
this},
m_line_width_property{"Line Width", 0.03, "Line width of object-shape", this},
m_default_topic{default_topic}
{
// iterate over default values to create and initialize the properties.
Expand Down Expand Up @@ -133,17 +134,18 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
/// \param centroid Centroid position of the shape in Object.header.frame_id frame
/// \param orientation Orientation of the shape in Object.header.frame_id frame
/// \param labels List of ObjectClassificationMsg objects
/// \param line_width Line thickness around the object
/// \return Marker ptr. Id and header will have to be set by the caller
template <typename ClassificationContainerT>
std::optional<Marker::SharedPtr> get_shape_marker_ptr(
const autoware_auto_perception_msgs::msg::Shape & shape_msg,
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
const ClassificationContainerT & labels) const
const ClassificationContainerT & labels, const double & line_width) const
{
const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels);

if (m_display_3d_property.getBool()) {
return detail::get_shape_marker_ptr(shape_msg, centroid, orientation, color_rgba);
return detail::get_shape_marker_ptr(shape_msg, centroid, orientation, color_rgba, line_width);
} else {
return std::nullopt;
}
Expand Down Expand Up @@ -335,6 +337,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
colors.push_back(sample_color); // spring green
}

double get_line_width() { return m_line_width_property.getFloat(); }

private:
// All rviz plugins should have this. Should be initialized with pointer to this class
MarkerCommon m_marker_common;
Expand All @@ -358,6 +362,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
rviz_common::properties::BoolProperty m_display_predicted_paths_property;
// Property to enable/disable predicted path confidence visualization
rviz_common::properties::BoolProperty m_display_path_confidence_property;
// Property to decide line width of object shape
rviz_common::properties::FloatProperty m_line_width_property;
// Default topic name to be visualized
std::string m_default_topic;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg)
// Get marker for shape
auto shape_marker = get_shape_marker_ptr(
object.shape, object.kinematics.pose_with_covariance.pose.position,
object.kinematics.pose_with_covariance.pose.orientation, object.classification);
object.kinematics.pose_with_covariance.pose.orientation, object.classification,
get_line_width());
if (shape_marker) {
auto shape_marker_ptr = shape_marker.value();
shape_marker_ptr->header = msg->header;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ visualization_msgs::msg::Marker::SharedPtr get_label_marker_ptr(
visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
const autoware_auto_perception_msgs::msg::Shape & shape_msg,
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
const std_msgs::msg::ColorRGBA & color_rgba)
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width)
{
auto marker_ptr = std::make_shared<Marker>();
marker_ptr->ns = std::string("shape");
Expand All @@ -235,7 +235,7 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.2);
marker_ptr->scale.x = 0.03;
marker_ptr->scale.x = line_width;
marker_ptr->color = color_rgba;

return marker_ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms
// Get marker for shape
auto shape_marker = get_shape_marker_ptr(
object.shape, object.kinematics.initial_pose_with_covariance.pose.position,
object.kinematics.initial_pose_with_covariance.pose.orientation, object.classification);
object.kinematics.initial_pose_with_covariance.pose.orientation, object.classification,
get_line_width());
if (shape_marker) {
auto shape_marker_ptr = shape_marker.value();
shape_marker_ptr->header = msg->header;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg)
// Get marker for shape
auto shape_marker = get_shape_marker_ptr(
object.shape, object.kinematics.pose_with_covariance.pose.position,
object.kinematics.pose_with_covariance.pose.orientation, object.classification);
object.kinematics.pose_with_covariance.pose.orientation, object.classification,
get_line_width());
if (shape_marker) {
auto shape_marker_ptr = shape_marker.value();
shape_marker_ptr->header = msg->header;
Expand Down

0 comments on commit ecd76b1

Please sign in to comment.