moveit2
The MoveIt Motion Planning Framework for ROS 2.
motion_planning_frame_planning.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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: Ioan Sucan */
36 
40 
43 
44 #include <std_srvs/srv/empty.hpp>
45 #include <moveit_msgs/msg/robot_state.hpp>
46 #include <tf2_eigen/tf2_eigen.hpp>
48 
49 #include "ui_motion_planning_rviz_plugin_frame.h"
50 
51 namespace moveit_rviz_plugin
52 {
53 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_visualization.motion_planning_frame_planning");
54 
55 void MotionPlanningFrame::planButtonClicked()
56 {
57  publishSceneIfNeeded();
58  planning_display_->addBackgroundJob([this] { computePlanButtonClicked(); }, "compute plan");
59 }
60 
61 void MotionPlanningFrame::executeButtonClicked()
62 {
63  ui_->execute_button->setEnabled(false);
64  // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution
65  planning_display_->spawnBackgroundJob([this] { computeExecuteButtonClicked(); });
66 }
67 
68 void MotionPlanningFrame::planAndExecuteButtonClicked()
69 {
70  publishSceneIfNeeded();
71  ui_->plan_and_execute_button->setEnabled(false);
72  ui_->execute_button->setEnabled(false);
73  // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution
74  planning_display_->spawnBackgroundJob([this] { computePlanAndExecuteButtonClicked(); });
75 }
76 
77 void MotionPlanningFrame::stopButtonClicked()
78 {
79  ui_->stop_button->setEnabled(false); // avoid clicking again
80  planning_display_->addBackgroundJob([this] { computeStopButtonClicked(); }, "stop");
81 }
82 
83 void MotionPlanningFrame::allowReplanningToggled(bool checked)
84 {
85  if (move_group_)
86  move_group_->allowReplanning(checked);
87 }
88 
89 void MotionPlanningFrame::allowLookingToggled(bool checked)
90 {
91  if (move_group_)
92  move_group_->allowLooking(checked);
93 }
94 
95 void MotionPlanningFrame::pathConstraintsIndexChanged(int index)
96 {
97  if (move_group_)
98  {
99  if (index > 0)
100  {
101  std::string c = ui_->path_constraints_combo_box->itemText(index).toStdString();
102  if (!move_group_->setPathConstraints(c))
103  RCLCPP_WARN_STREAM(LOGGER, "Unable to set the path constraints: " << c);
104  }
105  else
106  move_group_->clearPathConstraints();
107  }
108 }
109 
110 void MotionPlanningFrame::onClearOctomapClicked()
111 {
112  auto req = std::make_shared<std_srvs::srv::Empty::Request>();
113  auto result = clear_octomap_service_client_->async_send_request(req);
114 
115  if (result.wait_for(std::chrono::seconds(0)) != std::future_status::ready)
116  {
117  RCLCPP_ERROR(LOGGER, "Failed to call clear_octomap_service");
118  }
119  ui_->clear_octomap_button->setEnabled(false);
120 }
121 
122 bool MotionPlanningFrame::computeCartesianPlan()
123 {
124  rclcpp::Time start = rclcpp::Clock().now();
125  // get goal pose
127  std::vector<geometry_msgs::msg::Pose> waypoints;
128  const std::string& link_name = move_group_->getEndEffectorLink();
129  const moveit::core::LinkModel* link = move_group_->getRobotModel()->getLinkModel(link_name);
130  if (!link)
131  {
132  RCLCPP_ERROR_STREAM(LOGGER, "Failed to determine unique end-effector link: " << link_name);
133  return false;
134  }
135  waypoints.push_back(tf2::toMsg(goal.getGlobalLinkTransform(link)));
136 
137  // setup default params
138  double cart_step_size = 0.01;
139  double cart_jump_thresh = 0.0;
140  bool avoid_collisions = true;
141 
142  // compute trajectory
143  moveit_msgs::msg::RobotTrajectory trajectory;
144  double fraction =
145  move_group_->computeCartesianPath(waypoints, cart_step_size, cart_jump_thresh, trajectory, avoid_collisions);
146 
147  if (fraction >= 1.0)
148  {
149  RCLCPP_INFO(LOGGER, "Achieved %f %% of Cartesian path", fraction * 100.);
150 
151  // Compute time parameterization to also provide velocities
152  // https://groups.google.com/forum/#!topic/moveit-users/MOoFxy2exT4
153  robot_trajectory::RobotTrajectory rt(move_group_->getRobotModel(), move_group_->getName());
154  rt.setRobotTrajectoryMsg(*move_group_->getCurrentState(), trajectory);
156  bool success = time_parameterization.computeTimeStamps(rt, ui_->velocity_scaling_factor->value(),
157  ui_->acceleration_scaling_factor->value());
158  RCLCPP_INFO(LOGGER, "Computing time stamps %s", success ? "SUCCEEDED" : "FAILED");
159 
160  // Store trajectory in current_plan_
161  current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
162  rt.getRobotTrajectoryMsg(current_plan_->trajectory_);
163  current_plan_->planning_time_ = (rclcpp::Clock().now() - start).seconds();
164  return success;
165  }
166  return false;
167 }
168 
169 bool MotionPlanningFrame::computeJointSpacePlan()
170 {
171  current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
172  return move_group_->plan(*current_plan_) == moveit::core::MoveItErrorCode::SUCCESS;
173 }
174 
175 void MotionPlanningFrame::computePlanButtonClicked()
176 {
177  if (!move_group_)
178  return;
179 
180  // Clear status
181  ui_->result_label->setText("Planning...");
182 
183  configureForPlanning();
185  bool success = (ui_->use_cartesian_path->isEnabled() && ui_->use_cartesian_path->checkState()) ?
186  computeCartesianPlan() :
187  computeJointSpacePlan();
188 
189  if (success)
190  {
191  ui_->execute_button->setEnabled(true);
192  ui_->result_label->setText(QString("Time: ").append(QString::number(current_plan_->planning_time_, 'f', 3)));
193  }
194  else
195  {
196  current_plan_.reset();
197  ui_->result_label->setText("Failed");
198  }
199  Q_EMIT planningFinished();
200 }
201 
202 void MotionPlanningFrame::computeExecuteButtonClicked()
203 {
204  // ensures the MoveGroupInterface is not destroyed while executing
205  moveit::planning_interface::MoveGroupInterfacePtr mgi(move_group_);
206  if (mgi && current_plan_)
207  {
208  ui_->stop_button->setEnabled(true); // enable stopping
209  bool success = mgi->execute(*current_plan_) == moveit::core::MoveItErrorCode::SUCCESS;
210  onFinishedExecution(success);
211  }
212 }
213 
214 void MotionPlanningFrame::computePlanAndExecuteButtonClicked()
215 {
216  // ensures the MoveGroupInterface is not destroyed while executing
217  moveit::planning_interface::MoveGroupInterfacePtr mgi(move_group_);
218  if (!mgi)
219  return;
220  configureForPlanning();
222  // move_group::move() on the server side, will always start from the current state
223  // to suppress a warning, we pass an empty state (which encodes "start from current state")
224  mgi->setStartStateToCurrentState();
225  ui_->stop_button->setEnabled(true);
226  if (ui_->use_cartesian_path->isEnabled() && ui_->use_cartesian_path->checkState())
227  {
228  if (computeCartesianPlan())
229  computeExecuteButtonClicked();
230  }
231  else
232  {
233  bool success = mgi->move() == moveit::core::MoveItErrorCode::SUCCESS;
234  onFinishedExecution(success);
235  }
236  ui_->plan_and_execute_button->setEnabled(true);
237 }
238 
239 void MotionPlanningFrame::computeStopButtonClicked()
240 {
241  if (move_group_)
242  move_group_->stop();
243 }
244 
245 void MotionPlanningFrame::onFinishedExecution(bool success)
246 {
247  // visualize result of execution
248  if (success)
249  ui_->result_label->setText("Executed");
250  else
251  ui_->result_label->setText(!ui_->stop_button->isEnabled() ? "Stopped" : "Failed");
252  // disable stop button
253  ui_->stop_button->setEnabled(false);
254 
255  // update query start state to current if necessary
256  if (ui_->start_state_combo_box->currentText() == "<current>")
257  startStateTextChanged(ui_->start_state_combo_box->currentText());
258 
259  // auto-update goal to stored previous state (but only on success)
260  // on failure, the user must update the goal to the previous state himself
261  if (ui_->goal_state_combo_box->currentText() == "<previous>")
262  goalStateTextChanged(ui_->goal_state_combo_box->currentText());
263 }
264 
265 void MotionPlanningFrame::onNewPlanningSceneState()
266 {
267  moveit::core::RobotState current(planning_display_->getPlanningSceneRO()->getCurrentState());
268  if (ui_->start_state_combo_box->currentText() == "<current>")
269  {
272  }
273  if (ui_->goal_state_combo_box->currentText() == "<current>")
275 }
276 
277 void MotionPlanningFrame::startStateTextChanged(const QString& start_state)
278 {
279  // use background job: fetching the current state might take up to a second
280  planning_display_->addBackgroundJob([this, state = start_state.toStdString()] { startStateTextChangedExec(state); },
281  "update start state");
282 }
283 
284 void MotionPlanningFrame::startStateTextChangedExec(const std::string& start_state)
285 {
287  updateQueryStateHelper(start, start_state);
289 }
290 
291 void MotionPlanningFrame::goalStateTextChanged(const QString& goal_state)
292 {
293  // use background job: fetching the current state might take up to a second
294  planning_display_->addBackgroundJob([this, state = goal_state.toStdString()] { goalStateTextChangedExec(state); },
295  "update goal state");
296 }
297 
298 void MotionPlanningFrame::goalStateTextChangedExec(const std::string& goal_state)
299 {
301  updateQueryStateHelper(goal, goal_state);
303 }
304 
305 void MotionPlanningFrame::planningGroupTextChanged(const QString& planning_group)
306 {
307  planning_display_->changePlanningGroup(planning_group.toStdString());
308 }
309 
310 void MotionPlanningFrame::updateQueryStateHelper(moveit::core::RobotState& state, const std::string& v)
311 {
312  if (v == "<random>")
313  {
314  configureWorkspace();
315  if (const moveit::core::JointModelGroup* jmg =
317  state.setToRandomPositions(jmg);
318  return;
319  }
320 
321  if (v == "<random valid>")
322  {
323  configureWorkspace();
324 
325  if (const moveit::core::JointModelGroup* jmg =
327  {
328  // Loop until a collision free state is found
329  static const int MAX_ATTEMPTS = 100;
330  int attempt_count = 0; // prevent loop for going forever
331  while (attempt_count < MAX_ATTEMPTS)
332  {
333  // Generate random state
334  state.setToRandomPositions(jmg);
335 
336  state.update(); // prevent dirty transforms
337 
338  // Test for collision
339  if (planning_display_->getPlanningSceneRO()->isStateValid(state, "", false))
340  break;
341 
342  attempt_count++;
343  }
344  // Explain if no valid rand state found
345  if (attempt_count >= MAX_ATTEMPTS)
346  RCLCPP_WARN(LOGGER, "Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
347  }
348  else
349  {
350  RCLCPP_WARN_STREAM(LOGGER, "Unable to get joint model group " << planning_display_->getCurrentPlanningGroup());
351  }
352  return;
353  }
354 
355  if (v == "<current>")
356  {
357  rclcpp::Time t = node_->now();
360  if (ps)
361  state = ps->getCurrentState();
362  return;
363  }
364 
365  if (v == "<same as goal>")
366  {
368  return;
369  }
370 
371  if (v == "<same as start>")
372  {
374  return;
375  }
376 
377  if (v == "<previous>")
378  {
380  return;
381  }
382 
383  // maybe it is a named state
385  state.setToDefaultValues(jmg, v);
386 }
387 
388 void MotionPlanningFrame::populatePlannersList(const std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
389 {
390  ui_->planning_pipeline_combo_box->clear();
391 
392  planner_descriptions_ = desc;
393  size_t default_planner_index = 0;
394  for (auto& d : planner_descriptions_)
395  {
396  QString item_text(d.pipeline_id.c_str());
397  // Check for default planning pipeline
398  if (d.pipeline_id == default_planning_pipeline_)
399  {
400  if (item_text.isEmpty())
401  item_text = QString::fromStdString(d.name);
402  default_planner_index = ui_->planning_pipeline_combo_box->count();
403  }
404  ui_->planning_pipeline_combo_box->addItem(item_text);
405  }
406  QFont font;
407  font.setBold(true);
408  ui_->planning_pipeline_combo_box->setItemData(default_planner_index, font, Qt::FontRole);
409 
410  // Select default pipeline - triggers populatePlannerDescription() via callback
411  if (!planner_descriptions_.empty())
412  ui_->planning_pipeline_combo_box->setCurrentIndex(default_planner_index);
413 }
414 
415 void MotionPlanningFrame::populatePlannerDescription(const moveit_msgs::msg::PlannerInterfaceDescription& desc)
416 {
418  RCLCPP_DEBUG(LOGGER, "Found %zu planners for group '%s' and pipeline '%s'", desc.planner_ids.size(), group.c_str(),
419  desc.pipeline_id.c_str());
420  ui_->planning_algorithm_combo_box->clear();
421 
422  // set the label for the planning library
423  ui_->library_label->setText(QString::fromStdString(desc.name));
424  ui_->library_label->setStyleSheet("QLabel { color : green; font: bold }");
425 
426  bool found_group = false;
427  // the name of a planner is either "GROUP[planner_id]" or "planner_id"
428  if (!group.empty())
429  {
430  for (const std::string& planner_id : desc.planner_ids)
431  {
432  RCLCPP_DEBUG(LOGGER, "planner id: %s", planner_id.c_str());
433  if (planner_id == group)
434  found_group = true;
435  else if (planner_id.substr(0, group.length()) == group)
436  {
437  if (planner_id.size() > group.length() && planner_id[group.length()] == '[')
438  {
439  std::string id = planner_id.substr(group.length());
440  if (id.size() > 2)
441  {
442  id.resize(id.length() - 1);
443  ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(id.substr(1)));
444  }
445  }
446  }
447  }
448  }
449  if (ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
450  for (const std::string& planner_id : desc.planner_ids)
451  ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(planner_id));
452 
453  ui_->planning_algorithm_combo_box->insertItem(0, "<unspecified>");
454 
455  // retrieve default planner config from parameter server
456  const std::string& default_planner_config = move_group_->getDefaultPlannerId(found_group ? group : std::string());
457  int default_index = ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
458  if (default_index < 0)
459  default_index = 0; // 0 is <unspecified> fallback
460  ui_->planning_algorithm_combo_box->setCurrentIndex(default_index);
461 
462  QFont font;
463  font.setBold(true);
464  ui_->planning_algorithm_combo_box->setItemData(default_index, font, Qt::FontRole);
465 }
466 
467 void MotionPlanningFrame::populateConstraintsList()
468 {
469  if (move_group_)
470  planning_display_->addMainLoopJob([this]() { populateConstraintsList(move_group_->getKnownConstraints()); });
471 }
472 
473 void MotionPlanningFrame::populateConstraintsList(const std::vector<std::string>& constr)
474 {
475  ui_->path_constraints_combo_box->clear();
476  ui_->path_constraints_combo_box->addItem("None");
477  for (const std::string& constraint : constr)
478  ui_->path_constraints_combo_box->addItem(QString::fromStdString(constraint));
479 }
480 
482 {
483  mreq.group_name = planning_display_->getCurrentPlanningGroup();
484  mreq.num_planning_attempts = ui_->planning_attempts->value();
485  mreq.allowed_planning_time = ui_->planning_time->value();
486  mreq.max_velocity_scaling_factor = ui_->velocity_scaling_factor->value();
487  mreq.max_acceleration_scaling_factor = ui_->acceleration_scaling_factor->value();
489  mreq.workspace_parameters.min_corner.x = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
490  mreq.workspace_parameters.min_corner.y = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
491  mreq.workspace_parameters.min_corner.z = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
492  mreq.workspace_parameters.max_corner.x = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
493  mreq.workspace_parameters.max_corner.y = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
494  mreq.workspace_parameters.max_corner.z = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
495  moveit::core::RobotStateConstPtr s = planning_display_->getQueryGoalState();
496  const moveit::core::JointModelGroup* jmg = s->getJointModelGroup(mreq.group_name);
497  if (jmg)
498  {
499  mreq.goal_constraints.resize(1);
500  mreq.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(*s, jmg);
501  }
502 }
503 
504 void MotionPlanningFrame::configureWorkspace()
505 {
506  moveit::core::VariableBounds bx, by, bz;
508 
510  bx.min_position_ = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
511  bx.max_position_ = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
512  by.min_position_ = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
513  by.max_position_ = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
514  bz.min_position_ = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
515  bz.max_position_ = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
516 
517  if (move_group_)
519  bz.max_position_);
520  planning_scene_monitor::PlanningSceneMonitorPtr psm = planning_display_->getPlanningSceneMonitor();
521  // get non-const access to the robot_model and update planar & floating joints as indicated by the workspace settings
522  if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
523  {
524  const moveit::core::RobotModelPtr& robot_model = psm->getRobotModelLoader()->getModel();
525  const std::vector<moveit::core::JointModel*>& jm = robot_model->getJointModels();
526  for (moveit::core::JointModel* joint : jm)
527  if (joint->getType() == moveit::core::JointModel::PLANAR)
528  {
529  joint->setVariableBounds(joint->getName() + "/" + joint->getLocalVariableNames()[0], bx);
530  joint->setVariableBounds(joint->getName() + "/" + joint->getLocalVariableNames()[1], by);
531  }
532  else if (joint->getType() == moveit::core::JointModel::FLOATING)
533  {
534  joint->setVariableBounds(joint->getName() + "/" + joint->getLocalVariableNames()[0], bx);
535  joint->setVariableBounds(joint->getName() + "/" + joint->getLocalVariableNames()[1], by);
536  joint->setVariableBounds(joint->getName() + "/" + joint->getLocalVariableNames()[2], bz);
537  }
538  }
539 }
540 
541 void MotionPlanningFrame::configureForPlanning()
542 {
544  move_group_->setJointValueTarget(*planning_display_->getQueryGoalState());
545  move_group_->setPlanningTime(ui_->planning_time->value());
546  move_group_->setNumPlanningAttempts(ui_->planning_attempts->value());
547  move_group_->setMaxVelocityScalingFactor(ui_->velocity_scaling_factor->value());
548  move_group_->setMaxAccelerationScalingFactor(ui_->acceleration_scaling_factor->value());
549  configureWorkspace();
550  if (static_cast<bool>(planning_display_))
552 }
553 
554 void MotionPlanningFrame::remotePlanCallback(const std_msgs::msg::Empty::ConstSharedPtr& /*msg*/)
555 {
556  planButtonClicked();
557 }
558 
559 void MotionPlanningFrame::remoteExecuteCallback(const std_msgs::msg::Empty::ConstSharedPtr& /*msg*/)
560 {
561  executeButtonClicked();
562 }
563 
564 void MotionPlanningFrame::remoteStopCallback(const std_msgs::msg::Empty::ConstSharedPtr& /*msg*/)
565 {
566  stopButtonClicked();
567 }
568 
569 void MotionPlanningFrame::remoteUpdateStartStateCallback(const std_msgs::msg::Empty::ConstSharedPtr& /*msg*/)
570 {
572  {
573  planning_display_->waitForCurrentRobotState(node_->get_clock()->now());
575  if (ps)
576  {
577  moveit::core::RobotState state = ps->getCurrentState();
579  }
580  }
581 }
582 
583 void MotionPlanningFrame::remoteUpdateGoalStateCallback(const std_msgs::msg::Empty::ConstSharedPtr& /*msg*/)
584 {
586  {
587  planning_display_->waitForCurrentRobotState(node_->get_clock()->now());
589  if (ps)
590  {
591  moveit::core::RobotState state = ps->getCurrentState();
593  }
594  }
595 }
596 
597 void MotionPlanningFrame::remoteUpdateCustomStartStateCallback(const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
598 {
599  moveit_msgs::msg::RobotState msg_no_attached(*msg);
600  msg_no_attached.attached_collision_objects.clear();
601  msg_no_attached.is_diff = true;
603  {
604  planning_display_->waitForCurrentRobotState(node_->get_clock()->now());
606  if (ps)
607  {
608  auto state = std::make_shared<moveit::core::RobotState>(ps->getCurrentState());
609  moveit::core::robotStateMsgToRobotState(ps->getTransforms(), msg_no_attached, *state);
611  }
612  }
613 }
614 
615 void MotionPlanningFrame::remoteUpdateCustomGoalStateCallback(const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
616 {
617  moveit_msgs::msg::RobotState msg_no_attached(*msg);
618  msg_no_attached.attached_collision_objects.clear();
619  msg_no_attached.is_diff = true;
621  {
622  planning_display_->waitForCurrentRobotState(node_->get_clock()->now());
624  if (ps)
625  {
626  auto state = std::make_shared<moveit::core::RobotState>(ps->getCurrentState());
627  moveit::core::robotStateMsgToRobotState(ps->getTransforms(), msg_no_attached, *state);
629  }
630  }
631 }
632 } // namespace moveit_rviz_plugin
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void setQueryGoalState(const moveit::core::RobotState &goal)
void setQueryStartState(const moveit::core::RobotState &start)
moveit::core::RobotStateConstPtr getQueryStartState() const
const moveit::core::RobotState & getPreviousState() const
moveit::core::RobotStateConstPtr getQueryGoalState() const
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest &mreq)
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
void spawnBackgroundJob(const std::function< void()> &job)
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
bool waitForCurrentRobotState(const rclcpp::Time &t)
wait for robot state more recent than t
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition: utils.cpp:144
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
std::string append(const std::string &left, const std::string &right)
d
Definition: setup.py:4
const rclcpp::Logger LOGGER
Definition: async_test.h:31