moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_visualization.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman */
36 
37 #include <boost/algorithm/string.hpp>
38 #include <boost/algorithm/string/replace.hpp>
39 
41 
44 #include <rviz_default_plugins/robot/robot.hpp>
45 
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>
58 
59 #include <rclcpp/qos.hpp>
60 
61 #include <string>
62 
63 using namespace std::placeholders;
64 
65 namespace moveit_rviz_plugin
66 {
67 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_rviz_plugin_render_tools.trajectory_visualization");
68 
69 TrajectoryVisualization::TrajectoryVisualization(rviz_common::properties::Property* widget,
70  rviz_common::Display* display)
71  : animating_path_(false)
72  , drop_displaying_trajectory_(false)
73  , current_state_(-1)
74  , display_(display)
75  , widget_(widget)
76  , trajectory_slider_panel_(nullptr)
77  , trajectory_slider_dock_panel_(nullptr)
78 {
79  trajectory_topic_property_ = new rviz_common::properties::RosTopicProperty(
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);
84 
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);
90 
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);
96 
97  robot_path_alpha_property_ = new rviz_common::properties::FloatProperty(
98  "Robot Alpha", 0.5f, "Specifies the alpha for the robot links", widget, SLOT(changedRobotPathAlpha()), this);
99  robot_path_alpha_property_->setMin(0.0);
100  robot_path_alpha_property_->setMax(1.0);
101 
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);
107  state_display_time_property_->addOptionStd("3x");
108  state_display_time_property_->addOptionStd("1x");
109  state_display_time_property_->addOptionStd("0.5x");
110  state_display_time_property_->addOptionStd("0.05s");
111  state_display_time_property_->addOptionStd("0.1s");
112  state_display_time_property_->addOptionStd("0.5s");
113 
114  use_sim_time_property_ = new rviz_common::properties::BoolProperty(
115  "Use Sim Time", false, "Indicates whether simulation time or wall-time is used for state display timing.", widget,
116  nullptr, this);
117 
118  loop_display_property_ = new rviz_common::properties::BoolProperty("Loop Animation", false,
119  "Indicates whether the last received path "
120  "is to be animated in a loop",
121  widget, SLOT(changedLoopDisplay()), this);
122 
123  trail_display_property_ = new rviz_common::properties::BoolProperty("Show Trail", false, "Show a path trail", widget,
124  SLOT(changedShowTrail()), this);
125 
126  trail_step_size_property_ = new rviz_common::properties::IntProperty("Trail Step Size", 1,
127  "Specifies the step size of the samples "
128  "shown in the trajectory trail.",
129  widget, SLOT(changedTrailStepSize()), this);
130  trail_step_size_property_->setMin(1);
131 
132  interrupt_display_property_ = new rviz_common::properties::BoolProperty(
133  "Interrupt Display", false,
134  "Immediately show newly planned trajectory, interrupting the currently displayed one.", widget);
135 
136  robot_color_property_ = new rviz_common::properties::ColorProperty(
137  "Robot Color", QColor(150, 50, 150), "The color of the animated robot", widget, SLOT(changedRobotColor()), this);
138 
139  enable_robot_color_property_ = new rviz_common::properties::BoolProperty(
140  "Color Enabled", false, "Specifies whether robot coloring is enabled", widget, SLOT(enabledRobotColor()), this);
141 }
142 
144 {
148 
149  display_path_robot_.reset();
152 }
153 
154 void TrajectoryVisualization::onInitialize(const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
155  rviz_common::DisplayContext* context)
156 {
157  // Save pointers for later use
158  scene_node_ = scene_node;
159  context_ = context;
160  node_ = node;
161 
162  auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
163  if (!ros_node_abstraction)
164  {
165  RVIZ_COMMON_LOG_WARNING("Unable to lock weak_ptr from DisplayContext in TrajectoryVisualization constructor");
166  return;
167  }
168  trajectory_topic_property_->initialize(ros_node_abstraction);
169 
170  // Load trajectory robot
171  display_path_robot_ = std::make_shared<RobotStateVisualization>(scene_node_, context_, "Planned Path", widget_);
172  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
173  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
174  display_path_robot_->setVisible(false);
175 
176  rviz_common::WindowManagerInterface* window_context = context_->getWindowManager();
177  if (window_context)
178  {
179  trajectory_slider_panel_ = new TrajectoryPanel(window_context->getParentWindow());
181  window_context->addPane(display_->getName() + " - Trajectory Slider", trajectory_slider_panel_);
182  trajectory_slider_dock_panel_->setIcon(display_->getIcon());
183  connect(trajectory_slider_dock_panel_, SIGNAL(visibilityChanged(bool)), this,
184  SLOT(trajectorySliderPanelVisibilityChange(bool)));
186  }
187 
188  trajectory_topic_sub_ = node_->create_subscription<moveit_msgs::msg::DisplayTrajectory>(
189  trajectory_topic_property_->getStdString(), rclcpp::ServicesQoS(),
190  [this](const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg) { return incomingDisplayTrajectory(msg); });
191 }
192 
194 {
196  trajectory_slider_dock_panel_->setWindowTitle(name + " - Slider");
197 }
198 
199 void TrajectoryVisualization::onRobotModelLoaded(const moveit::core::RobotModelConstPtr& robot_model)
200 {
201  robot_model_ = robot_model;
202 
203  // Error check
204  if (!robot_model_)
205  {
206  RCLCPP_ERROR_STREAM(LOGGER, "No robot model found");
207  return;
208  }
209 
210  // Load robot state
211  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
212  robot_state_->setToDefaultValues();
213 
214  // Load rviz robot
215  display_path_robot_->load(*robot_model_->getURDF());
216  enabledRobotColor(); // force-refresh to account for saved display configuration
217  // perform post-poned subscription to trajectory topic
218  // Check if topic name is empty
219  if (trajectory_topic_sub_->get_topic_name())
220  changedTrajectoryTopic();
221 }
222 
224 {
228  animating_path_ = false;
229 
230  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
231  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
232  display_path_robot_->setVisible(false);
233 }
234 
236 {
237  trajectory_trail_.clear();
238 }
239 
240 void TrajectoryVisualization::changedLoopDisplay()
241 {
245 }
246 
247 void TrajectoryVisualization::changedShowTrail()
248 {
250 
251  if (!trail_display_property_->getBool())
252  return;
253  robot_trajectory::RobotTrajectoryPtr t = trajectory_message_to_display_;
254  if (!t)
256  if (!t)
257  return;
258 
259  int stepsize = trail_step_size_property_->getInt();
260  // always include last trajectory point
261  trajectory_trail_.resize(static_cast<int>(std::ceil((t->getWayPointCount() + stepsize - 1) / (float)stepsize)));
262  for (std::size_t i = 0; i < trajectory_trail_.size(); ++i)
263  {
264  int waypoint_i = std::min(i * stepsize, t->getWayPointCount() - 1); // limit to last trajectory point
265  auto r =
266  std::make_unique<RobotStateVisualization>(scene_node_, context_, "Trail Robot " + std::to_string(i), nullptr);
267  r->load(*robot_model_->getURDF());
268  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
269  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
270  r->setAlpha(robot_path_alpha_property_->getFloat());
271  r->update(t->getWayPointPtr(waypoint_i), default_attached_object_color_);
272  if (enable_robot_color_property_->getBool())
273  setRobotColor(&(r->getRobot()), robot_color_property_->getColor());
274  r->setVisible(display_->isEnabled() && (!animating_path_ || waypoint_i <= current_state_));
275  r->updateAttachedObjectColors(default_attached_object_color_);
276  trajectory_trail_[i] = std::move(r);
277  }
278 }
279 
280 void TrajectoryVisualization::changedTrailStepSize()
281 {
282  if (trail_display_property_->getBool())
283  changedShowTrail();
284 }
285 
286 void TrajectoryVisualization::changedRobotPathAlpha()
287 {
288  display_path_robot_->setAlpha(robot_path_alpha_property_->getFloat());
289  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
290  r->setAlpha(robot_path_alpha_property_->getFloat());
291 }
292 
293 void TrajectoryVisualization::changedTrajectoryTopic()
294 {
295  // post-pone subscription if robot_state_ is not yet defined, i.e. onRobotModelLoaded() not yet called
296  if (!trajectory_topic_property_->getStdString().empty() && robot_state_)
297  {
298  trajectory_topic_sub_ = node_->create_subscription<moveit_msgs::msg::DisplayTrajectory>(
299  trajectory_topic_property_->getStdString(), rclcpp::ServicesQoS(),
300  [this](const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg) {
301  return incomingDisplayTrajectory(msg);
302  });
303  }
304 }
305 
306 void TrajectoryVisualization::changedDisplayPathVisualEnabled()
307 {
308  if (display_->isEnabled())
309  {
310  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
312  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
313  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
314  }
315 }
316 
317 void TrajectoryVisualization::changedStateDisplayTime()
318 {
319 }
320 
321 void TrajectoryVisualization::changedDisplayPathCollisionEnabled()
322 {
323  if (display_->isEnabled())
324  {
325  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
327  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
328  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
329  }
330 }
331 
333 {
334  changedRobotPathAlpha(); // set alpha property
335 
336  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
337  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
339  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
340  {
341  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
342  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
343  r->setVisible(true);
344  }
345 
346  changedTrajectoryTopic(); // load topic at startup if default used
347 }
348 
350 {
351  display_path_robot_->setVisible(false);
352  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
353  r->setVisible(false);
355  animating_path_ = false;
358 }
359 
361 {
362  // update() starts a new trajectory as soon as it is available
363  // interrupting may cause the newly received trajectory to interrupt
364  // hence, only interrupt when current_state_ already advanced past first
365  if (current_state_ > 0)
366  animating_path_ = false;
367 }
368 
370 {
371  constexpr char default_time_string[] = "3x";
372  constexpr float default_time_value = -3.0f;
373 
374  std::string tm = state_display_time_property_->getStdString();
375  boost::trim(tm);
376 
377  float type;
378 
379  if (tm.back() == 'x')
380  {
381  type = -1.0f;
382  }
383  else if (tm.back() == 's')
384  {
385  type = 1.0f;
386  }
387  else
388  {
389  state_display_time_property_->setStdString(default_time_string);
390  return default_time_value;
391  }
392 
393  tm.resize(tm.size() - 1);
394  boost::trim_right(tm);
395 
396  float value;
397  try
398  {
399  value = std::stof(tm);
400  }
401  catch (const std::invalid_argument& ex)
402  {
403  state_display_time_property_->setStdString(default_time_string);
404  return default_time_value;
405  }
406 
407  if (value <= 0)
408  {
409  state_display_time_property_->setStdString(default_time_string);
410  return default_time_value;
411  }
412 
413  return type * value;
414 }
415 
417 {
419 }
420 
421 void TrajectoryVisualization::update(float wall_dt, float sim_dt)
422 {
424  {
425  animating_path_ = false;
429  }
430  if (!animating_path_)
431  { // finished last animation?
432  std::scoped_lock lock(update_trajectory_message_);
433 
434  // new trajectory available to display?
436  {
437  animating_path_ = true;
439  changedShowTrail();
442  }
444  {
445  if (loop_display_property_->getBool())
446  { // do loop? -> start over too
447  animating_path_ = true;
448  }
449  else if (trajectory_slider_panel_ && trajectory_slider_panel_->isVisible())
450  {
451  if (static_cast<unsigned int>(trajectory_slider_panel_->getSliderPosition()) >=
452  displaying_trajectory_message_->getWayPointCount() - 1)
453  return; // nothing more to do
454  else
455  animating_path_ = true;
456  }
457  }
459 
460  if (animating_path_)
461  {
462  // restart animation
463  current_state_ = -1;
464  }
465  }
466 
467  if (animating_path_)
468  {
469  int previous_state = current_state_;
470  int waypoint_count = displaying_trajectory_message_->getWayPointCount();
471  if (use_sim_time_property_->getBool())
472  {
473  current_state_time_ += sim_dt;
474  }
475  else
476  {
477  current_state_time_ += wall_dt;
478  }
479  float tm = getStateDisplayTime();
480 
482  {
484  current_state_time_ = displaying_trajectory_message_->getWayPointDurationFromPrevious(current_state_);
485  }
486  else if (current_state_ < 0)
487  { // special case indicating restart of animation
488  current_state_ = 0;
489  current_state_time_ = 0.0;
490  }
491  else if (tm < 0.0)
492  {
493  // using realtime factors: skip to next waypoint based on elapsed display time
494  const float rt_factor = -tm; // negative tm is the intended realtime factor
495  while (current_state_ < waypoint_count &&
496  (tm = displaying_trajectory_message_->getWayPointDurationFromPrevious(current_state_ + 1) / rt_factor) <
498  {
499  current_state_time_ -= tm;
500  // if we are stuck in the while loop we should move the robot along the path to keep up
501  if (tm < current_state_time_)
503  ++current_state_;
504  }
505  }
506  else if (current_state_time_ > tm)
507  { // fixed display time per state
508  current_state_time_ = 0.0;
509  ++current_state_;
510  }
511 
512  if (current_state_ == previous_state)
513  return;
514 
515  if (current_state_ < waypoint_count)
516  {
520  for (std::size_t i = 0; i < trajectory_trail_.size(); ++i)
521  trajectory_trail_[i]->setVisible(
522  std::min(waypoint_count - 1, static_cast<int>(i) * trail_step_size_property_->getInt()) <= current_state_);
523  }
524  else
525  {
526  animating_path_ = false; // animation finished
527  if (trajectory_slider_panel_) // make sure we move the slider to the end
528  // so the user can re-play
530  display_path_robot_->update(displaying_trajectory_message_->getWayPointPtr(waypoint_count - 1));
531  display_path_robot_->setVisible(loop_display_property_->getBool());
534  }
535  }
536  // set visibility
537  display_path_robot_->setVisible(display_->isEnabled() && displaying_trajectory_message_ &&
538  (animating_path_ || trail_display_property_->getBool() ||
540  display_path_robot_->updateAttachedObjectColors(default_attached_object_color_);
541 }
542 
543 void TrajectoryVisualization::incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg)
544 {
545  // Error check
546  if (!robot_state_ || !robot_model_)
547  {
548  RCLCPP_ERROR_STREAM(LOGGER, "No robot state or robot model loaded");
549  return;
550  }
551 
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());
555 
557 
558  auto t = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, "");
559  try
560  {
561  for (std::size_t i = 0; i < msg->trajectory.size(); ++i)
562  {
563  if (t->empty())
564  {
565  t->setRobotTrajectoryMsg(*robot_state_, msg->trajectory_start, msg->trajectory[i]);
566  }
567  else
568  {
570  tmp.setRobotTrajectoryMsg(t->getLastWayPoint(), msg->trajectory[i]);
571  t->append(tmp, 0.0);
572  }
573  }
574  display_->setStatus(rviz_common::properties::StatusProperty::Ok, "Trajectory", "");
575  }
576  catch (const moveit::Exception& e)
577  {
578  display_->setStatus(rviz_common::properties::StatusProperty::Error, "Trajectory", e.what());
579  return;
580  }
581 
582  if (!t->empty())
583  {
584  std::scoped_lock lock(update_trajectory_message_);
586  if (interrupt_display_property_->getBool())
588  }
589 }
590 
591 void TrajectoryVisualization::changedRobotColor()
592 {
593  if (enable_robot_color_property_->getBool())
594  setRobotColor(&(display_path_robot_->getRobot()), robot_color_property_->getColor());
595 }
596 
597 void TrajectoryVisualization::enabledRobotColor()
598 {
599  if (enable_robot_color_property_->getBool())
600  setRobotColor(&(display_path_robot_->getRobot()), robot_color_property_->getColor());
601  else
602  unsetRobotColor(&(display_path_robot_->getRobot()));
603 }
604 
605 void TrajectoryVisualization::unsetRobotColor(rviz_default_plugins::robot::Robot* robot)
606 {
607  for (auto& link : robot->getLinks())
608  link.second->unsetColor();
609 }
610 
612 {
613  default_attached_object_color_.r = color.redF();
614  default_attached_object_color_.g = color.greenF();
615  default_attached_object_color_.b = color.blueF();
616  default_attached_object_color_.a = color.alphaF();
617 
619  {
620  display_path_robot_->setDefaultAttachedObjectColor(default_attached_object_color_);
621  display_path_robot_->updateAttachedObjectColors(default_attached_object_color_);
622  }
623  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
624  r->updateAttachedObjectColors(default_attached_object_color_);
625 }
626 
627 void TrajectoryVisualization::setRobotColor(rviz_default_plugins::robot::Robot* robot, const QColor& color)
628 {
629  for (auto& link : robot->getLinks())
630  robot->getLink(link.first)->setColor(color.redF(), color.greenF(), color.blueF());
631 }
632 
633 void TrajectoryVisualization::trajectorySliderPanelVisibilityChange(bool enable)
634 {
636  return;
637 
638  if (enable)
640  else
642 }
643 
645 {
646  robot_model_.reset();
647  robot_state_.reset();
648 }
649 
650 } // namespace moveit_rviz_plugin
This may be thrown if unrecoverable errors occur.
Definition: exceptions.h:53
void update(int way_point_count)
rviz_common::properties::BoolProperty * enable_robot_color_property_
void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr &msg)
ROS callback for an incoming path message.
rviz_common::properties::BoolProperty * display_path_visual_enabled_property_
rviz_common::properties::BoolProperty * interrupt_display_property_
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
robot_trajectory::RobotTrajectoryPtr displaying_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_
rviz_common::properties::BoolProperty * display_path_collision_enabled_property_
rviz_common::properties::RosTopicProperty * trajectory_topic_property_
rviz_common::properties::BoolProperty * use_sim_time_property_
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
rviz_common::properties::EditableEnumProperty * state_display_time_property_
rviz_common::properties::IntProperty * trail_step_size_property_
std::vector< RobotStateVisualizationUniquePtr > trajectory_trail_
void unsetRobotColor(rviz_default_plugins::robot::Robot *robot)
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr &robot_model)
virtual void update(float wall_dt, float sim_dt)
rviz_common::properties::FloatProperty * robot_path_alpha_property_
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...
robot
Definition: pick.py:53
r
Definition: plan.py:56
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31