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