37 #include <boost/algorithm/string.hpp> 
   38 #include <boost/algorithm/string/replace.hpp> 
   44 #include <rviz_default_plugins/robot/robot.hpp> 
   47 #include <rviz_common/display_context.hpp> 
   48 #include <rviz_common/properties/bool_property.hpp> 
   49 #include <rviz_common/properties/color_property.hpp> 
   50 #include <rviz_common/properties/editable_enum_property.hpp> 
   51 #include <rviz_common/properties/float_property.hpp> 
   52 #include <rviz_common/properties/int_property.hpp> 
   53 #include <rviz_common/properties/property.hpp> 
   54 #include <rviz_common/properties/ros_topic_property.hpp> 
   55 #include <rviz_common/properties/string_property.hpp> 
   56 #include <rviz_default_plugins/robot/robot_link.hpp> 
   57 #include <rviz_common/window_manager_interface.hpp> 
   59 #include <rclcpp/qos.hpp> 
   63 using namespace std::placeholders;
 
   67 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit_rviz_plugin_render_tools.trajectory_visualization");
 
   69 TrajectoryVisualization::TrajectoryVisualization(rviz_common::properties::Property* widget,
 
   70                                                  rviz_common::Display* display)
 
   71   : animating_path_(false)
 
   72   , drop_displaying_trajectory_(false)
 
   76   , trajectory_slider_panel_(nullptr)
 
   77   , trajectory_slider_dock_panel_(nullptr)
 
   80       "Trajectory Topic", 
"/display_planned_path",
 
   81       rosidl_generator_traits::data_type<moveit_msgs::msg::DisplayTrajectory>(),
 
   82       "The topic on which the moveit_msgs::msg::DisplayTrajectory messages are received", widget,
 
   83       SLOT(changedTrajectoryTopic()), 
this);
 
   86       new rviz_common::properties::BoolProperty(
"Show Robot Visual", 
true,
 
   87                                                 "Indicates whether the geometry of the robot as defined for " 
   88                                                 "visualisation purposes should be displayed",
 
   89                                                 widget, SLOT(changedDisplayPathVisualEnabled()), 
this);
 
   92       new rviz_common::properties::BoolProperty(
"Show Robot Collision", 
false,
 
   93                                                 "Indicates whether the geometry of the robot as defined " 
   94                                                 "for collision detection purposes should be displayed",
 
   95                                                 widget, SLOT(changedDisplayPathCollisionEnabled()), 
this);
 
   98       "Robot Alpha", 0.5f, 
"Specifies the alpha for the robot links", widget, SLOT(changedRobotPathAlpha()), 
this);
 
  103       new rviz_common::properties::EditableEnumProperty(
"State Display Time", 
"3x",
 
  104                                                         "Replay speed of trajectory. Either as factor of its time" 
  105                                                         "parameterization or as constant time (s) per waypoint.",
 
  106                                                         widget, SLOT(changedStateDisplayTime()), 
this);
 
  115       "Use Sim Time", 
false, 
"Indicates whether simulation time or wall-time is used for state display timing.", widget,
 
  119                                                                      "Indicates whether the last received path " 
  120                                                                      "is to be animated in a loop",
 
  121                                                                      widget, SLOT(changedLoopDisplay()), 
this);
 
  123   trail_display_property_ = 
new rviz_common::properties::BoolProperty(
"Show Trail", 
false, 
"Show a path trail", widget,
 
  124                                                                       SLOT(changedShowTrail()), 
this);
 
  127                                                                        "Specifies the step size of the samples " 
  128                                                                        "shown in the trajectory trail.",
 
  129                                                                        widget, SLOT(changedTrailStepSize()), 
this);
 
  133       "Interrupt Display", 
false,
 
  134       "Immediately show newly planned trajectory, interrupting the currently displayed one.", widget);
 
  137       "Robot Color", QColor(150, 50, 150), 
"The color of the animated robot", widget, SLOT(changedRobotColor()), 
this);
 
  140       "Color Enabled", 
false, 
"Specifies whether robot coloring is enabled", widget, SLOT(enabledRobotColor()), 
this);
 
  155                                            rviz_common::DisplayContext* context)
 
  162   auto ros_node_abstraction = 
context_->getRosNodeAbstraction().lock();
 
  163   if (!ros_node_abstraction)
 
  165     RVIZ_COMMON_LOG_WARNING(
"Unable to lock weak_ptr from DisplayContext in TrajectoryVisualization constructor");
 
  176   rviz_common::WindowManagerInterface* window_context = 
context_->getWindowManager();
 
  184             SLOT(trajectorySliderPanelVisibilityChange(
bool)));
 
  206     RCLCPP_ERROR_STREAM(LOGGER, 
"No robot model found");
 
  220     changedTrajectoryTopic();
 
  240 void TrajectoryVisualization::changedLoopDisplay()
 
  247 void TrajectoryVisualization::changedShowTrail()
 
  261   trajectory_trail_.resize(
static_cast<int>(std::ceil((t->getWayPointCount() + stepsize - 1) / (
float)stepsize)));
 
  264     int waypoint_i = std::min(i * stepsize, t->getWayPointCount() - 1);  
 
  266         std::make_unique<RobotStateVisualization>(
scene_node_, 
context_, 
"Trail Robot " + std::to_string(i), 
nullptr);
 
  280 void TrajectoryVisualization::changedTrailStepSize()
 
  286 void TrajectoryVisualization::changedRobotPathAlpha()
 
  293 void TrajectoryVisualization::changedTrajectoryTopic()
 
  300         [
this](
const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg) {
 
  306 void TrajectoryVisualization::changedDisplayPathVisualEnabled()
 
  317 void TrajectoryVisualization::changedStateDisplayTime()
 
  321 void TrajectoryVisualization::changedDisplayPathCollisionEnabled()
 
  334   changedRobotPathAlpha();  
 
  346   changedTrajectoryTopic();  
 
  353     r->setVisible(
false);
 
  371   constexpr 
char default_time_string[] = 
"3x";
 
  372   constexpr 
float default_time_value = -3.0f;
 
  379   if (tm.back() == 
'x')
 
  383   else if (tm.back() == 
's')
 
  390     return default_time_value;
 
  393   tm.resize(tm.size() - 1);
 
  394   boost::trim_right(tm);
 
  399     value = std::stof(tm);
 
  401   catch (
const std::invalid_argument& ex)
 
  404     return default_time_value;
 
  410     return default_time_value;
 
  494       const float rt_factor = -tm;  
 
  548     RCLCPP_ERROR_STREAM(LOGGER, 
"No robot state or robot model loaded");
 
  552   if (!msg->model_id.empty() && msg->model_id != 
robot_model_->getName())
 
  553     RCLCPP_WARN(LOGGER, 
"Received a trajectory to display for model '%s' but model '%s' was expected",
 
  554                 msg->model_id.c_str(), 
robot_model_->getName().c_str());
 
  558   auto t = std::make_shared<robot_trajectory::RobotTrajectory>(
robot_model_, 
"");
 
  561     for (std::size_t i = 0; i < msg->trajectory.size(); ++i)
 
  565         t->setRobotTrajectoryMsg(*
robot_state_, msg->trajectory_start, msg->trajectory[i]);
 
  574     display_->setStatus(rviz_common::properties::StatusProperty::Ok, 
"Trajectory", 
"");
 
  578     display_->setStatus(rviz_common::properties::StatusProperty::Error, 
"Trajectory", e.what());
 
  591 void TrajectoryVisualization::changedRobotColor()
 
  597 void TrajectoryVisualization::enabledRobotColor()
 
  607   for (
auto& link : 
robot->getLinks())
 
  608     link.second->unsetColor();
 
  629   for (
auto& link : 
robot->getLinks())
 
  630     robot->getLink(link.first)->setColor(color.redF(), color.greenF(), color.blueF());
 
  633 void TrajectoryVisualization::trajectorySliderPanelVisibilityChange(
bool enable)
 
This may be thrown if unrecoverable errors occur.
 
void onInitialize() override
 
void setSliderPosition(int position)
 
int getSliderPosition() const
 
void pauseButton(bool check)
 
void update(int way_point_count)
 
rviz_common::properties::BoolProperty * enable_robot_color_property_
 
void clearTrajectoryTrail()
 
void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr &msg)
ROS callback for an incoming path message.
 
Ogre::SceneNode * scene_node_
 
rviz_common::DisplayContext * context_
 
rviz_common::properties::BoolProperty * display_path_visual_enabled_property_
 
void setName(const QString &name)
 
rviz_common::properties::BoolProperty * interrupt_display_property_
 
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
 
robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_
 
std::mutex update_trajectory_message_
 
rviz_common::PanelDockWidget * trajectory_slider_dock_panel_
 
void onInitialize(const rclcpp::Node::SharedPtr &node, Ogre::SceneNode *scene_node, rviz_common::DisplayContext *context)
 
rviz_common::properties::BoolProperty * trail_display_property_
 
TrajectoryPanel * trajectory_slider_panel_
 
float current_state_time_
 
rviz_common::properties::BoolProperty * display_path_collision_enabled_property_
 
moveit::core::RobotStatePtr robot_state_
 
rviz_common::properties::RosTopicProperty * trajectory_topic_property_
 
moveit::core::RobotModelConstPtr robot_model_
 
rviz_common::properties::BoolProperty * use_sim_time_property_
 
std_msgs::msg::ColorRGBA default_attached_object_color_
 
rviz_common::properties::Property * widget_
 
rviz_common::properties::BoolProperty * loop_display_property_
 
rviz_common::properties::ColorProperty * robot_color_property_
 
void setRobotColor(rviz_default_plugins::robot::Robot *robot, const QColor &color)
 
float getStateDisplayTime()
get time to show each single robot state
 
rclcpp::Node::SharedPtr node_
 
rviz_common::properties::EditableEnumProperty * state_display_time_property_
 
void setDefaultAttachedObjectColor(const QColor &color)
 
rviz_common::properties::IntProperty * trail_step_size_property_
 
void interruptCurrentDisplay()
 
rviz_common::Display * display_
 
std::vector< RobotStateVisualizationUniquePtr > trajectory_trail_
 
void unsetRobotColor(rviz_default_plugins::robot::Robot *robot)
 
~TrajectoryVisualization() override
 
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr &robot_model)
 
virtual void update(float wall_dt, float sim_dt)
 
RobotStateVisualizationPtr display_path_robot_
 
rviz_common::properties::FloatProperty * robot_path_alpha_property_
 
bool drop_displaying_trajectory_
 
rclcpp::Subscription< moveit_msgs::msg::DisplayTrajectory >::SharedPtr trajectory_topic_sub_
 
Maintain a sequence of waypoints and the time durations between these waypoints.
 
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::msg::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
 
RobotTrajectory & append(const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max())
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_in...
 
const rclcpp::Logger LOGGER