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(tier4_planning_rviz_plugin): set path colors from rviz and add fade_out feature #8972

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <OgreSceneNode.h>

#include <deque>
#include <limits>
#include <memory>
#include <vector>

Expand All @@ -60,24 +61,29 @@
}

std::unique_ptr<Ogre::ColourValue> setColorDependsOnVelocity(
const double vel_max, const double cmd_vel)
const double vel_max, const double cmd_vel,
const rviz_common::properties::ColorProperty & color_min,
const rviz_common::properties::ColorProperty & color_mid,
const rviz_common::properties::ColorProperty & color_max)
{
const double cmd_vel_abs = std::fabs(cmd_vel);
const double vel_min = 0.0;

std::unique_ptr<Ogre::ColourValue> color_ptr(new Ogre::ColourValue());
if (vel_min < cmd_vel_abs && cmd_vel_abs <= (vel_max / 2.0)) {
double ratio = (cmd_vel_abs - vel_min) / (vel_max / 2.0 - vel_min);
color_ptr = gradation(Qt::red, Qt::yellow, ratio);
double ratio = (cmd_vel_abs) / (vel_max / 2.0);
color_ptr = gradation(color_min.getColor(), color_mid.getColor(), ratio);

Check warning on line 75 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L74-L75

Added lines #L74 - L75 were not covered by tests
} else if ((vel_max / 2.0) < cmd_vel_abs && cmd_vel_abs <= vel_max) {
double ratio = (cmd_vel_abs - vel_max / 2.0) / (vel_max - vel_max / 2.0);
color_ptr = gradation(Qt::yellow, Qt::green, ratio);
double ratio = (cmd_vel_abs - vel_max / 2.0) / (vel_max / 2.0);

Check warning on line 77 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L77

Added line #L77 was not covered by tests

color_ptr = gradation(color_mid.getColor(), color_max.getColor(), ratio);

Check warning on line 79 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L79

Added line #L79 was not covered by tests
} else if (vel_max < cmd_vel_abs) {
*color_ptr = Ogre::ColourValue::Green;
// Use max color when velocity exceeds max
*color_ptr = rviz_common::properties::qtToOgre(color_max.getColor());

Check warning on line 82 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L82

Added line #L82 was not covered by tests
} else {
*color_ptr = Ogre::ColourValue::Red;
// Use min color when velocity is below min
*color_ptr = rviz_common::properties::qtToOgre(color_min.getColor());

Check warning on line 85 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L85

Added line #L85 was not covered by tests
}

return color_ptr;
}

Expand Down Expand Up @@ -109,8 +115,10 @@
property_path_width_view_{"Constant Width", false, "", &property_path_view_},
property_path_width_{"Width", 2.0, "", &property_path_view_},
property_path_alpha_{"Alpha", 1.0, "", &property_path_view_},
property_path_color_view_{"Constant Color", false, "", &property_path_view_},
property_path_color_{"Color", Qt::black, "", &property_path_view_},
property_min_color_("Min Velocity Color", QColor("#3F2EE3"), "", &property_path_view_),
property_mid_color_("Mid Velocity Color", QColor("#208AAE"), "", &property_path_view_),
property_max_color_("Max Velocity Color", QColor("#00E678"), "", &property_path_view_),
property_fade_out_distance_{"Fade Out Distance", 0.0, "[m]", &property_path_view_},

Check warning on line 121 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L118-L121

Added lines #L118 - L121 were not covered by tests
property_vel_max_{"Color Border Vel Max", 3.0, "[m/s]", this},
// velocity
property_velocity_view_{"View Velocity", true, "", this},
Expand Down Expand Up @@ -356,6 +364,34 @@
const float right = property_path_width_view_.getBool() ? property_path_width_.getFloat() / 2.0
: info->width / 2.0;

// Initialize alphas with the default alpha value
std::vector<float> alphas(msg_ptr->points.size(), property_path_alpha_.getFloat());

Check warning on line 368 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L368

Added line #L368 was not covered by tests

// Backward iteration to adjust alpha values for the last x meters
if (property_fade_out_distance_.getFloat() > std::numeric_limits<float>::epsilon()) {
alphas.back() = 0.0f;

Check warning on line 372 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L372

Added line #L372 was not covered by tests
float cumulative_distance = 0.0f;
for (size_t point_idx = msg_ptr->points.size() - 1; point_idx > 0; point_idx--) {
const auto & curr_point = autoware::universe_utils::getPose(msg_ptr->points.at(point_idx));
const auto & prev_point =
autoware::universe_utils::getPose(msg_ptr->points.at(point_idx - 1));
float distance = std::sqrt(autoware::universe_utils::calcSquaredDistance2d(

Check warning on line 378 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L377-L378

Added lines #L377 - L378 were not covered by tests
prev_point.position, curr_point.position));
cumulative_distance += distance;

Check warning on line 380 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L380

Added line #L380 was not covered by tests

if (cumulative_distance <= property_fade_out_distance_.getFloat()) {
auto ratio =
static_cast<float>(cumulative_distance / property_fade_out_distance_.getFloat());
float alpha = property_path_alpha_.getFloat() * ratio;
alphas.at(point_idx - 1) = alpha;

Check warning on line 386 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L383-L386

Added lines #L383 - L386 were not covered by tests
} else {
// If the distance exceeds the fade out distance, break the loop
break;
}
}
}

// Forward iteration to visualize path
for (size_t point_idx = 0; point_idx < msg_ptr->points.size(); point_idx++) {
const auto & path_point = msg_ptr->points.at(point_idx);
const auto & pose = autoware::universe_utils::getPose(path_point);
Expand All @@ -364,15 +400,14 @@
// path
if (property_path_view_.getBool()) {
Ogre::ColourValue color;
if (property_path_color_view_.getBool()) {
color = rviz_common::properties::qtToOgre(property_path_color_.getColor());
} else {
// color change depending on velocity
std::unique_ptr<Ogre::ColourValue> dynamic_color_ptr =
setColorDependsOnVelocity(property_vel_max_.getFloat(), velocity);
color = *dynamic_color_ptr;
}
color.a = property_path_alpha_.getFloat();

// color change depending on velocity
std::unique_ptr<Ogre::ColourValue> dynamic_color_ptr = setColorDependsOnVelocity(
property_vel_max_.getFloat(), velocity, property_min_color_, property_mid_color_,
property_max_color_);
color = *dynamic_color_ptr;
color.a = alphas.at(point_idx);

Check warning on line 409 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L405-L409

Added lines #L405 - L409 were not covered by tests

Eigen::Vector3f vec_in;
Eigen::Vector3f vec_out;
Eigen::Quaternionf quat_yaw_reverse(0, 0, 0, 1);
Expand Down Expand Up @@ -413,8 +448,9 @@
color = rviz_common::properties::qtToOgre(property_velocity_color_.getColor());
} else {
/* color change depending on velocity */
std::unique_ptr<Ogre::ColourValue> dynamic_color_ptr =
setColorDependsOnVelocity(property_vel_max_.getFloat(), velocity);
std::unique_ptr<Ogre::ColourValue> dynamic_color_ptr = setColorDependsOnVelocity(
property_vel_max_.getFloat(), velocity, property_min_color_, property_mid_color_,
property_max_color_);

Check warning on line 453 in common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

View check run for this annotation

Codecov / codecov/patch

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp#L451-L453

Added lines #L451 - L453 were not covered by tests
color = *dynamic_color_ptr;
}
color.a = property_velocity_alpha_.getFloat();
Expand Down Expand Up @@ -616,8 +652,13 @@
rviz_common::properties::BoolProperty property_path_width_view_;
rviz_common::properties::FloatProperty property_path_width_;
rviz_common::properties::FloatProperty property_path_alpha_;
rviz_common::properties::BoolProperty property_path_color_view_;
rviz_common::properties::ColorProperty property_path_color_;
// Gradient points for velocity color
rviz_common::properties::ColorProperty property_min_color_;
rviz_common::properties::ColorProperty property_mid_color_;
rviz_common::properties::ColorProperty property_max_color_;
// Last x meters of the path will fade out to transparent
rviz_common::properties::FloatProperty property_fade_out_distance_;

rviz_common::properties::FloatProperty property_vel_max_;
rviz_common::properties::BoolProperty property_velocity_view_;
rviz_common::properties::FloatProperty property_velocity_alpha_;
Expand Down
Loading