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 <string>
60 
61 using namespace std::placeholders;
62 
63 namespace moveit_rviz_plugin
64 {
65 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_rviz_plugin_render_tools.trajectory_visualization");
66 
67 TrajectoryVisualization::TrajectoryVisualization(rviz_common::properties::Property* widget,
68  rviz_common::Display* display)
69  : animating_path_(false)
70  , drop_displaying_trajectory_(false)
71  , current_state_(-1)
72  , display_(display)
73  , widget_(widget)
74  , trajectory_slider_panel_(nullptr)
75  , trajectory_slider_dock_panel_(nullptr)
76 {
77  trajectory_topic_property_ = new rviz_common::properties::RosTopicProperty(
78  "Trajectory Topic", "/display_planned_path",
79  rosidl_generator_traits::data_type<moveit_msgs::msg::DisplayTrajectory>(),
80  "The topic on which the moveit_msgs::msg::DisplayTrajectory messages are received", widget,
81  SLOT(changedTrajectoryTopic()), this);
82 
84  new rviz_common::properties::BoolProperty("Show Robot Visual", true,
85  "Indicates whether the geometry of the robot as defined for "
86  "visualisation purposes should be displayed",
87  widget, SLOT(changedDisplayPathVisualEnabled()), this);
88 
90  new rviz_common::properties::BoolProperty("Show Robot Collision", false,
91  "Indicates whether the geometry of the robot as defined "
92  "for collision detection purposes should be displayed",
93  widget, SLOT(changedDisplayPathCollisionEnabled()), this);
94 
95  robot_path_alpha_property_ = new rviz_common::properties::FloatProperty(
96  "Robot Alpha", 0.5f, "Specifies the alpha for the robot links", widget, SLOT(changedRobotPathAlpha()), this);
97  robot_path_alpha_property_->setMin(0.0);
98  robot_path_alpha_property_->setMax(1.0);
99 
101  new rviz_common::properties::EditableEnumProperty("State Display Time", "3x",
102  "Replay speed of trajectory. Either as factor of its time"
103  "parameterization or as constant time (s) per waypoint.",
104  widget, SLOT(changedStateDisplayTime()), this);
105  state_display_time_property_->addOptionStd("3x");
106  state_display_time_property_->addOptionStd("1x");
107  state_display_time_property_->addOptionStd("0.5x");
108  state_display_time_property_->addOptionStd("0.05s");
109  state_display_time_property_->addOptionStd("0.1s");
110  state_display_time_property_->addOptionStd("0.5s");
111 
112  use_sim_time_property_ = new rviz_common::properties::BoolProperty(
113  "Use Sim Time", false, "Indicates whether simulation time or wall-time is used for state display timing.", widget,
114  nullptr, this);
115 
116  loop_display_property_ = new rviz_common::properties::BoolProperty("Loop Animation", false,
117  "Indicates whether the last received path "
118  "is to be animated in a loop",
119  widget, SLOT(changedLoopDisplay()), this);
120 
121  trail_display_property_ = new rviz_common::properties::BoolProperty("Show Trail", false, "Show a path trail", widget,
122  SLOT(changedShowTrail()), this);
123 
124  trail_step_size_property_ = new rviz_common::properties::IntProperty("Trail Step Size", 1,
125  "Specifies the step size of the samples "
126  "shown in the trajectory trail.",
127  widget, SLOT(changedTrailStepSize()), this);
128  trail_step_size_property_->setMin(1);
129 
130  interrupt_display_property_ = new rviz_common::properties::BoolProperty(
131  "Interrupt Display", false,
132  "Immediately show newly planned trajectory, interrupting the currently displayed one.", widget);
133 
134  robot_color_property_ = new rviz_common::properties::ColorProperty(
135  "Robot Color", QColor(150, 50, 150), "The color of the animated robot", widget, SLOT(changedRobotColor()), this);
136 
137  enable_robot_color_property_ = new rviz_common::properties::BoolProperty(
138  "Color Enabled", false, "Specifies whether robot coloring is enabled", widget, SLOT(enabledRobotColor()), this);
139 }
140 
142 {
146 
147  display_path_robot_.reset();
150 }
151 
152 void TrajectoryVisualization::onInitialize(const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
153  rviz_common::DisplayContext* context)
154 {
155  // Save pointers for later use
156  scene_node_ = scene_node;
157  context_ = context;
158  node_ = node;
159 
160  auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
161  if (!ros_node_abstraction)
162  {
163  RVIZ_COMMON_LOG_WARNING("Unable to lock weak_ptr from DisplayContext in TrajectoryVisualization constructor");
164  return;
165  }
166  trajectory_topic_property_->initialize(ros_node_abstraction);
167 
168  // Load trajectory robot
169  display_path_robot_ = std::make_shared<RobotStateVisualization>(scene_node_, context_, "Planned Path", widget_);
170  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
171  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
172  display_path_robot_->setVisible(false);
173 
174  rviz_common::WindowManagerInterface* window_context = context_->getWindowManager();
175  if (window_context)
176  {
177  trajectory_slider_panel_ = new TrajectoryPanel(window_context->getParentWindow());
179  window_context->addPane(display_->getName() + " - Trajectory Slider", trajectory_slider_panel_);
180  trajectory_slider_dock_panel_->setIcon(display_->getIcon());
181  connect(trajectory_slider_dock_panel_, SIGNAL(visibilityChanged(bool)), this,
182  SLOT(trajectorySliderPanelVisibilityChange(bool)));
184  }
185 
186  trajectory_topic_sub_ = node_->create_subscription<moveit_msgs::msg::DisplayTrajectory>(
187  trajectory_topic_property_->getStdString(), rclcpp::SystemDefaultsQoS(),
188  [this](const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg) { return incomingDisplayTrajectory(msg); });
189 }
190 
192 {
194  trajectory_slider_dock_panel_->setWindowTitle(name + " - Slider");
195 }
196 
197 void TrajectoryVisualization::onRobotModelLoaded(const moveit::core::RobotModelConstPtr& robot_model)
198 {
199  robot_model_ = robot_model;
200 
201  // Error check
202  if (!robot_model_)
203  {
204  RCLCPP_ERROR_STREAM(LOGGER, "No robot model found");
205  return;
206  }
207 
208  // Load robot state
209  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
210  robot_state_->setToDefaultValues();
211 
212  // Load rviz robot
213  display_path_robot_->load(*robot_model_->getURDF());
214  enabledRobotColor(); // force-refresh to account for saved display configuration
215  // perform post-poned subscription to trajectory topic
216  // Check if topic name is empty
217  if (trajectory_topic_sub_->get_topic_name())
218  changedTrajectoryTopic();
219 }
220 
222 {
226  animating_path_ = false;
227 
228  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
229  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
230  display_path_robot_->setVisible(false);
231 }
232 
234 {
235  trajectory_trail_.clear();
236 }
237 
238 void TrajectoryVisualization::changedLoopDisplay()
239 {
243 }
244 
245 void TrajectoryVisualization::changedShowTrail()
246 {
248 
249  if (!trail_display_property_->getBool())
250  return;
251  robot_trajectory::RobotTrajectoryPtr t = trajectory_message_to_display_;
252  if (!t)
254  if (!t)
255  return;
256 
257  int stepsize = trail_step_size_property_->getInt();
258  // always include last trajectory point
259  trajectory_trail_.resize(static_cast<int>(std::ceil((t->getWayPointCount() + stepsize - 1) / (float)stepsize)));
260  for (std::size_t i = 0; i < trajectory_trail_.size(); ++i)
261  {
262  int waypoint_i = std::min(i * stepsize, t->getWayPointCount() - 1); // limit to last trajectory point
263  auto r =
264  std::make_unique<RobotStateVisualization>(scene_node_, context_, "Trail Robot " + std::to_string(i), nullptr);
265  r->load(*robot_model_->getURDF());
266  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
267  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
268  r->setAlpha(robot_path_alpha_property_->getFloat());
269  r->update(t->getWayPointPtr(waypoint_i), default_attached_object_color_);
270  if (enable_robot_color_property_->getBool())
271  setRobotColor(&(r->getRobot()), robot_color_property_->getColor());
272  r->setVisible(display_->isEnabled() && (!animating_path_ || waypoint_i <= current_state_));
273  trajectory_trail_[i] = std::move(r);
274  }
275 }
276 
277 void TrajectoryVisualization::changedTrailStepSize()
278 {
279  if (trail_display_property_->getBool())
280  changedShowTrail();
281 }
282 
283 void TrajectoryVisualization::changedRobotPathAlpha()
284 {
285  display_path_robot_->setAlpha(robot_path_alpha_property_->getFloat());
286  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
287  r->setAlpha(robot_path_alpha_property_->getFloat());
288 }
289 
290 void TrajectoryVisualization::changedTrajectoryTopic()
291 {
292  // post-pone subscription if robot_state_ is not yet defined, i.e. onRobotModelLoaded() not yet called
293  if (!trajectory_topic_property_->getStdString().empty() && robot_state_)
294  {
295  trajectory_topic_sub_ = node_->create_subscription<moveit_msgs::msg::DisplayTrajectory>(
296  trajectory_topic_property_->getStdString(), rclcpp::SystemDefaultsQoS(),
297  [this](const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg) {
298  return incomingDisplayTrajectory(msg);
299  });
300  }
301 }
302 
303 void TrajectoryVisualization::changedDisplayPathVisualEnabled()
304 {
305  if (display_->isEnabled())
306  {
307  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
309  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
310  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
311  }
312 }
313 
314 void TrajectoryVisualization::changedStateDisplayTime()
315 {
316 }
317 
318 void TrajectoryVisualization::changedDisplayPathCollisionEnabled()
319 {
320  if (display_->isEnabled())
321  {
322  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
324  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
325  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
326  }
327 }
328 
330 {
331  changedRobotPathAlpha(); // set alpha property
332 
333  display_path_robot_->setVisualVisible(display_path_visual_enabled_property_->getBool());
334  display_path_robot_->setCollisionVisible(display_path_collision_enabled_property_->getBool());
336  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
337  {
338  r->setVisualVisible(display_path_visual_enabled_property_->getBool());
339  r->setCollisionVisible(display_path_collision_enabled_property_->getBool());
340  r->setVisible(true);
341  }
342 
343  changedTrajectoryTopic(); // load topic at startup if default used
344 }
345 
347 {
348  display_path_robot_->setVisible(false);
349  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
350  r->setVisible(false);
352  animating_path_ = false;
355 }
356 
358 {
359  // update() starts a new trajectory as soon as it is available
360  // interrupting may cause the newly received trajectory to interrupt
361  // hence, only interrupt when current_state_ already advanced past first
362  if (current_state_ > 0)
363  animating_path_ = false;
364 }
365 
367 {
368  constexpr char default_time_string[] = "3x";
369  constexpr float default_time_value = -3.0f;
370 
371  std::string tm = state_display_time_property_->getStdString();
372  boost::trim(tm);
373 
374  float type;
375 
376  if (tm.back() == 'x')
377  {
378  type = -1.0f;
379  }
380  else if (tm.back() == 's')
381  {
382  type = 1.0f;
383  }
384  else
385  {
386  state_display_time_property_->setStdString(default_time_string);
387  return default_time_value;
388  }
389 
390  tm.resize(tm.size() - 1);
391  boost::trim_right(tm);
392 
393  float value;
394  try
395  {
396  value = std::stof(tm);
397  }
398  catch (const std::invalid_argument& ex)
399  {
400  state_display_time_property_->setStdString(default_time_string);
401  return default_time_value;
402  }
403 
404  if (value <= 0)
405  {
406  state_display_time_property_->setStdString(default_time_string);
407  return default_time_value;
408  }
409 
410  return type * value;
411 }
412 
414 {
416 }
417 
418 void TrajectoryVisualization::update(float wall_dt, float sim_dt)
419 {
421  {
422  animating_path_ = false;
426  }
427  if (!animating_path_)
428  { // finished last animation?
429  std::scoped_lock lock(update_trajectory_message_);
430 
431  // new trajectory available to display?
433  {
434  animating_path_ = true;
436  changedShowTrail();
439  }
441  {
442  if (loop_display_property_->getBool())
443  { // do loop? -> start over too
444  animating_path_ = true;
445  }
446  else if (trajectory_slider_panel_ && trajectory_slider_panel_->isVisible())
447  {
448  if (static_cast<unsigned int>(trajectory_slider_panel_->getSliderPosition()) >=
449  displaying_trajectory_message_->getWayPointCount() - 1)
450  return; // nothing more to do
451  else
452  animating_path_ = true;
453  }
454  }
456 
457  if (animating_path_)
458  {
459  // restart animation
460  current_state_ = -1;
461  }
462  }
463 
464  if (animating_path_)
465  {
466  int previous_state = current_state_;
467  int waypoint_count = displaying_trajectory_message_->getWayPointCount();
468  if (use_sim_time_property_->getBool())
469  {
470  current_state_time_ += sim_dt;
471  }
472  else
473  {
474  current_state_time_ += wall_dt;
475  }
476  float tm = getStateDisplayTime();
477 
479  {
481  current_state_time_ = displaying_trajectory_message_->getWayPointDurationFromPrevious(current_state_);
482  }
483  else if (current_state_ < 0)
484  { // special case indicating restart of animation
485  current_state_ = 0;
486  current_state_time_ = 0.0;
487  }
488  else if (tm < 0.0)
489  {
490  // using realtime factors: skip to next waypoint based on elapsed display time
491  const float rt_factor = -tm; // negative tm is the intended realtime factor
492  while (current_state_ < waypoint_count &&
493  (tm = displaying_trajectory_message_->getWayPointDurationFromPrevious(current_state_ + 1) / rt_factor) <
495  {
496  current_state_time_ -= tm;
497  // if we are stuck in the while loop we should move the robot along the path to keep up
498  if (tm < current_state_time_)
500  ++current_state_;
501  }
502  }
503  else if (current_state_time_ > tm)
504  { // fixed display time per state
505  current_state_time_ = 0.0;
506  ++current_state_;
507  }
508 
509  if (current_state_ == previous_state)
510  return;
511 
512  if (current_state_ < waypoint_count)
513  {
517  for (std::size_t i = 0; i < trajectory_trail_.size(); ++i)
518  trajectory_trail_[i]->setVisible(
519  std::min(waypoint_count - 1, static_cast<int>(i) * trail_step_size_property_->getInt()) <= current_state_);
520  }
521  else
522  {
523  animating_path_ = false; // animation finished
524  if (trajectory_slider_panel_) // make sure we move the slider to the end
525  // so the user can re-play
527  display_path_robot_->update(displaying_trajectory_message_->getWayPointPtr(waypoint_count - 1));
528  display_path_robot_->setVisible(loop_display_property_->getBool());
531  }
532  }
533  // set visibility
534  display_path_robot_->setVisible(display_->isEnabled() && displaying_trajectory_message_ &&
535  (animating_path_ || trail_display_property_->getBool() ||
537 }
538 
539 void TrajectoryVisualization::incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg)
540 {
541  // Error check
542  if (!robot_state_ || !robot_model_)
543  {
544  RCLCPP_ERROR_STREAM(LOGGER, "No robot state or robot model loaded");
545  return;
546  }
547 
548  if (!msg->model_id.empty() && msg->model_id != robot_model_->getName())
549  RCLCPP_WARN(LOGGER, "Received a trajectory to display for model '%s' but model '%s' was expected",
550  msg->model_id.c_str(), robot_model_->getName().c_str());
551 
553 
554  auto t = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, "");
555  try
556  {
557  for (std::size_t i = 0; i < msg->trajectory.size(); ++i)
558  {
559  if (t->empty())
560  {
561  t->setRobotTrajectoryMsg(*robot_state_, msg->trajectory_start, msg->trajectory[i]);
562  }
563  else
564  {
566  tmp.setRobotTrajectoryMsg(t->getLastWayPoint(), msg->trajectory[i]);
567  t->append(tmp, 0.0);
568  }
569  }
570  display_->setStatus(rviz_common::properties::StatusProperty::Ok, "Trajectory", "");
571  }
572  catch (const moveit::Exception& e)
573  {
574  display_->setStatus(rviz_common::properties::StatusProperty::Error, "Trajectory", e.what());
575  return;
576  }
577 
578  if (!t->empty())
579  {
580  std::scoped_lock lock(update_trajectory_message_);
582  if (interrupt_display_property_->getBool())
584  }
585 }
586 
587 void TrajectoryVisualization::changedRobotColor()
588 {
589  if (enable_robot_color_property_->getBool())
590  setRobotColor(&(display_path_robot_->getRobot()), robot_color_property_->getColor());
591 }
592 
593 void TrajectoryVisualization::enabledRobotColor()
594 {
595  if (enable_robot_color_property_->getBool())
596  setRobotColor(&(display_path_robot_->getRobot()), robot_color_property_->getColor());
597  else
598  unsetRobotColor(&(display_path_robot_->getRobot()));
599 }
600 
601 void TrajectoryVisualization::unsetRobotColor(rviz_default_plugins::robot::Robot* robot)
602 {
603  for (auto& link : robot->getLinks())
604  link.second->unsetColor();
605 }
606 
608 {
609  default_attached_object_color_.r = color.redF();
610  default_attached_object_color_.g = color.greenF();
611  default_attached_object_color_.b = color.blueF();
612  default_attached_object_color_.a = color.alphaF();
613 
615  {
616  display_path_robot_->setDefaultAttachedObjectColor(default_attached_object_color_);
617  display_path_robot_->updateAttachedObjectColors(default_attached_object_color_);
618  }
619  for (const RobotStateVisualizationUniquePtr& r : trajectory_trail_)
620  r->updateAttachedObjectColors(default_attached_object_color_);
621 }
622 
623 void TrajectoryVisualization::setRobotColor(rviz_default_plugins::robot::Robot* robot, const QColor& color)
624 {
625  for (auto& link : robot->getLinks())
626  robot->getLink(link.first)->setColor(color.redF(), color.greenF(), color.blueF());
627 }
628 
629 void TrajectoryVisualization::trajectorySliderPanelVisibilityChange(bool enable)
630 {
632  return;
633 
634  if (enable)
636  else
638 }
639 
641 {
642  robot_model_.reset();
643  robot_state_.reset();
644 }
645 
646 } // 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