moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
move_group_interface.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, SRI International
5 * Copyright (c) 2013, Ioan A. Sucan
6 * Copyright (c) 2012, Willow Garage, Inc.
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of Willow Garage nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36
37/* Author: Ioan Sucan, Sachin Chitta */
38
39#include <stdexcept>
40#include <sstream>
41#include <memory>
42#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
53#include <moveit_msgs/action/execute_trajectory.hpp>
54#include <moveit_msgs/srv/query_planner_interfaces.hpp>
55#include <moveit_msgs/srv/get_cartesian_path.hpp>
56#include <moveit_msgs/srv/grasp_planning.hpp>
57#include <moveit_msgs/srv/get_planner_params.hpp>
58#include <moveit_msgs/srv/set_planner_params.hpp>
61
62#include <std_msgs/msg/string.hpp>
63#include <geometry_msgs/msg/transform_stamped.hpp>
64// TODO: Remove conditional include when released to all active distros.
65#if __has_include(<tf2/utils.hpp>)
66#include <tf2/utils.hpp>
67#else
68#include <tf2/utils.h>
69#endif
70#include <tf2_eigen/tf2_eigen.hpp>
71#include <tf2_ros/transform_listener.h>
72#include <rclcpp/rclcpp.hpp>
73#include <rclcpp/version.h>
74
75namespace moveit
76{
77namespace planning_interface
78{
80 "robot_description"; // name of the robot description (a param name, so it can be changed externally)
81
82const std::string GRASP_PLANNING_SERVICE_NAME = "plan_grasps"; // name of the service that can be used to plan grasps
83
84namespace
85{
86enum ActiveTargetType
87{
88 JOINT,
89 POSE,
90 POSITION,
91 ORIENTATION
92};
93
94// Function to support both Rolling and Humble on the main branch
95// Rolling has deprecated the version of the create_client method that takes
96// rmw_qos_profile_services_default for the QoS argument
97#if RCLCPP_VERSION_GTE(17, 0, 0) // Rolling
98auto qosDefault()
99{
100 return rclcpp::SystemDefaultsQoS();
101}
102#else // Humble
103auto qosDefault()
104{
105 return rmw_qos_profile_services_default;
106}
107#endif
108
109} // namespace
110
112{
113 friend MoveGroupInterface;
114
115public:
116 MoveGroupInterfaceImpl(const rclcpp::Node::SharedPtr& node, const Options& opt,
117 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const rclcpp::Duration& wait_for_servers)
118 : opt_(opt), node_(node), logger_(moveit::getLogger("moveit.ros.move_group_interface")), tf_buffer_(tf_buffer)
119 {
120 // We have no control on how the passed node is getting executed. To make sure MGI is functional, we're creating
121 // our own callback group which is managed in a separate callback thread
122 callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
123 false /* don't spin with node executor */);
124 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
125 callback_thread_ = std::thread([this]() { callback_executor_.spin(); });
126
127 robot_model_ = opt.robot_model ? opt.robot_model : getSharedRobotModel(node_, opt.robot_description);
128 if (!getRobotModel())
129 {
130 std::string error = "Unable to construct robot model. Please make sure all needed information is on the "
131 "parameter server.";
132 RCLCPP_FATAL_STREAM(logger_, error);
133 throw std::runtime_error(error);
134 }
135
136 if (!getRobotModel()->hasJointModelGroup(opt.group_name))
137 {
138 std::string error = "Group '" + opt.group_name + "' was not found.";
139 RCLCPP_FATAL_STREAM(logger_, error);
140 throw std::runtime_error(error);
141 }
142
144 joint_model_group_ = getRobotModel()->getJointModelGroup(opt.group_name);
145
146 joint_state_target_ = std::make_shared<moveit::core::RobotState>(getRobotModel());
147 joint_state_target_->setToDefaultValues();
148 active_target_ = JOINT;
149 can_look_ = false;
150 look_around_attempts_ = 0;
151 can_replan_ = false;
152 replan_delay_ = 2.0;
153 replan_attempts_ = 1;
154 goal_joint_tolerance_ = 1e-4;
155 goal_position_tolerance_ = 1e-4; // 0.1 mm
156 goal_orientation_tolerance_ = 1e-3; // ~0.1 deg
157 allowed_planning_time_ = 5.0;
158 num_planning_attempts_ = 1;
159 node_->get_parameter_or<double>("robot_description_planning.default_velocity_scaling_factor",
160 max_velocity_scaling_factor_, 0.1);
161 node_->get_parameter_or<double>("robot_description_planning.default_acceleration_scaling_factor",
162 max_acceleration_scaling_factor_, 0.1);
163 initializing_constraints_ = false;
164
165 if (joint_model_group_->isChain())
166 end_effector_link_ = joint_model_group_->getLinkModelNames().back();
167 pose_reference_frame_ = getRobotModel()->getModelFrame();
168 // Append the slash between two topic components
169 trajectory_event_publisher_ = node_->create_publisher<std_msgs::msg::String>(
172 1);
173 attached_object_publisher_ = node_->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
176 1);
177
178 current_state_monitor_ = getSharedStateMonitor(node_, robot_model_, tf_buffer_);
179
180 move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
181 node_, rclcpp::names::append(opt_.move_group_namespace, move_group::MOVE_ACTION), callback_group_);
182 move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
183 execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
184 node_, rclcpp::names::append(opt_.move_group_namespace, move_group::EXECUTE_ACTION_NAME), callback_group_);
185 execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
186
187 query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
188 rclcpp::names::append(opt_.move_group_namespace, move_group::QUERY_PLANNERS_SERVICE_NAME), qosDefault(),
189 callback_group_);
190 get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
191 rclcpp::names::append(opt_.move_group_namespace, move_group::GET_PLANNER_PARAMS_SERVICE_NAME), qosDefault(),
192 callback_group_);
193 set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
194 rclcpp::names::append(opt_.move_group_namespace, move_group::SET_PLANNER_PARAMS_SERVICE_NAME), qosDefault(),
195 callback_group_);
196 cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
197 rclcpp::names::append(opt_.move_group_namespace, move_group::CARTESIAN_PATH_SERVICE_NAME), qosDefault(),
198 callback_group_);
199
200 RCLCPP_INFO_STREAM(logger_, "Ready to take commands for planning group " << opt.group_name << '.');
201 }
202
204 {
205 if (constraints_init_thread_)
206 constraints_init_thread_->join();
207
208 callback_executor_.cancel();
209
210 if (callback_thread_.joinable())
211 callback_thread_.join();
212 }
213
214 const std::shared_ptr<tf2_ros::Buffer>& getTF() const
215 {
216 return tf_buffer_;
217 }
218
219 const Options& getOptions() const
220 {
221 return opt_;
222 }
223
224 const moveit::core::RobotModelConstPtr& getRobotModel() const
225 {
226 return robot_model_;
227 }
228
230 {
231 return joint_model_group_;
232 }
233
234 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const
235 {
236 return *move_action_client_;
237 }
238
239 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc)
240 {
241 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
242 auto future_response = query_service_->async_send_request(req);
243
244 if (future_response.valid())
245 {
246 const auto& response = future_response.get();
247 if (!response->planner_interfaces.empty())
248 {
249 desc = response->planner_interfaces.front();
250 return true;
251 }
252 }
253 return false;
254 }
255
256 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
257 {
258 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
259 auto future_response = query_service_->async_send_request(req);
260 if (future_response.valid())
261 {
262 const auto& response = future_response.get();
263 if (!response->planner_interfaces.empty())
264 {
265 desc = response->planner_interfaces;
266 return true;
267 }
268 }
269 return false;
270 }
271
272 std::map<std::string, std::string> getPlannerParams(const std::string& planner_id, const std::string& group = "")
273 {
274 auto req = std::make_shared<moveit_msgs::srv::GetPlannerParams::Request>();
275 moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response;
276 req->planner_config = planner_id;
277 req->group = group;
278 std::map<std::string, std::string> result;
279
280 auto future_response = get_params_service_->async_send_request(req);
281 if (future_response.valid())
282 {
283 response = future_response.get();
284 for (unsigned int i = 0, end = response->params.keys.size(); i < end; ++i)
285 result[response->params.keys[i]] = response->params.values[i];
286 }
287 return result;
288 }
289
290 void setPlannerParams(const std::string& planner_id, const std::string& group,
291 const std::map<std::string, std::string>& params, bool replace = false)
292 {
293 auto req = std::make_shared<moveit_msgs::srv::SetPlannerParams::Request>();
294 req->planner_config = planner_id;
295 req->group = group;
296 req->replace = replace;
297 for (const std::pair<const std::string, std::string>& param : params)
298 {
299 req->params.keys.push_back(param.first);
300 req->params.values.push_back(param.second);
301 }
302 set_params_service_->async_send_request(req);
303 }
304
306 {
307 std::string default_planning_pipeline;
308 node_->get_parameter("move_group.default_planning_pipeline", default_planning_pipeline);
309 return default_planning_pipeline;
310 }
311
312 void setPlanningPipelineId(const std::string& pipeline_id)
313 {
314 if (pipeline_id != planning_pipeline_id_)
315 {
316 planning_pipeline_id_ = pipeline_id;
317
318 // Reset planner_id if planning pipeline changed
319 planner_id_ = "";
320 }
321 }
322
323 const std::string& getPlanningPipelineId() const
324 {
325 return planning_pipeline_id_;
326 }
327
328 std::string getDefaultPlannerId(const std::string& group) const
329 {
330 // Check what planning pipeline config should be used
331 std::string pipeline_id = getDefaultPlanningPipelineId();
332 if (!planning_pipeline_id_.empty())
333 pipeline_id = planning_pipeline_id_;
334
335 std::stringstream param_name;
336 param_name << "move_group";
337 if (!pipeline_id.empty())
338 param_name << "/planning_pipelines/" << pipeline_id;
339 if (!group.empty())
340 param_name << '.' << group;
341 param_name << ".default_planner_config";
342
343 std::string default_planner_config;
344 node_->get_parameter(param_name.str(), default_planner_config);
345 return default_planner_config;
346 }
347
348 void setPlannerId(const std::string& planner_id)
349 {
350 planner_id_ = planner_id;
351 }
352
353 const std::string& getPlannerId() const
354 {
355 return planner_id_;
356 }
357
358 void setNumPlanningAttempts(unsigned int num_planning_attempts)
359 {
360 num_planning_attempts_ = num_planning_attempts;
361 }
362
364 {
365 setMaxScalingFactor(max_velocity_scaling_factor_, value, "velocity_scaling_factor", 0.1);
366 }
367
369 {
370 return max_velocity_scaling_factor_;
371 }
372
374 {
375 setMaxScalingFactor(max_acceleration_scaling_factor_, value, "acceleration_scaling_factor", 0.1);
376 }
377
379 {
380 return max_acceleration_scaling_factor_;
381 }
382
383 void setMaxScalingFactor(double& variable, const double target_value, const char* factor_name, double fallback_value)
384 {
385 if (target_value > 1.0)
386 {
387 RCLCPP_WARN(logger_, "Limiting max_%s (%.2f) to 1.0.", factor_name, target_value);
388 variable = 1.0;
389 }
390 else if (target_value <= 0.0)
391 {
392 node_->get_parameter_or<double>(std::string("robot_description_planning.default_") + factor_name, variable,
393 fallback_value);
394 if (target_value < 0.0)
395 {
396 RCLCPP_WARN(logger_, "max_%s < 0.0! Setting to default: %.2f.", factor_name, variable);
397 }
398 }
399 else
400 {
401 variable = target_value;
402 }
403 }
404
406 {
407 return *joint_state_target_;
408 }
409
411 {
412 return *joint_state_target_;
413 }
414
415 void setStartState(const moveit_msgs::msg::RobotState& start_state)
416 {
417 considered_start_state_ = start_state;
418 }
419
421 {
422 considered_start_state_ = moveit_msgs::msg::RobotState();
423 moveit::core::robotStateToRobotStateMsg(start_state, considered_start_state_, true);
424 }
425
427 {
428 // set message to empty diff
429 considered_start_state_ = moveit_msgs::msg::RobotState();
430 considered_start_state_.is_diff = true;
431 }
432
433 moveit::core::RobotStatePtr getStartState()
434 {
435 moveit::core::RobotStatePtr s;
437 moveit::core::robotStateMsgToRobotState(considered_start_state_, *s, true);
438 return s;
439 }
440
441 bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link,
442 const std::string& frame, bool approx)
443 {
444 const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
445 // this only works if we have an end-effector
446 if (!eef.empty())
447 {
448 // first we set the goal to be the same as the start state
449 moveit::core::RobotStatePtr c = getStartState();
450 if (c)
451 {
452 setTargetType(JOINT);
453 c->enforceBounds();
454 getTargetRobotState() = *c;
455 if (!getTargetRobotState().satisfiesBounds(getGoalJointTolerance()))
456 return false;
457 }
458 else
459 return false;
460
461 // we may need to do approximate IK
464
465 // if no frame transforms are needed, call IK directly
466 if (frame.empty() || moveit::core::Transforms::sameFrame(frame, getRobotModel()->getModelFrame()))
467 {
468 return getTargetRobotState().setFromIK(getJointModelGroup(), eef_pose, eef, 0.0,
470 }
471 else
472 {
473 // transform the pose into the model frame, then do IK
474 bool frame_found;
475 const Eigen::Isometry3d& t = getTargetRobotState().getFrameTransform(frame, &frame_found);
476 if (frame_found)
477 {
478 Eigen::Isometry3d p;
479 tf2::fromMsg(eef_pose, p);
480 return getTargetRobotState().setFromIK(getJointModelGroup(), t * p, eef, 0.0,
482 }
483 else
484 {
485 RCLCPP_ERROR(logger_, "Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
486 getRobotModel()->getModelFrame().c_str());
487 return false;
488 }
489 }
490 }
491 else
492 return false;
493 }
494
495 void setEndEffectorLink(const std::string& end_effector)
496 {
497 end_effector_link_ = end_effector;
498 }
499
500 void clearPoseTarget(const std::string& end_effector_link)
501 {
502 pose_targets_.erase(end_effector_link);
503 }
504
506 {
507 pose_targets_.clear();
508 }
509
510 const std::string& getEndEffectorLink() const
511 {
512 return end_effector_link_;
513 }
514
515 const std::string& getEndEffector() const
516 {
517 if (!end_effector_link_.empty())
518 {
519 const std::vector<std::string>& possible_eefs =
520 getRobotModel()->getJointModelGroup(opt_.group_name)->getAttachedEndEffectorNames();
521 for (const std::string& possible_eef : possible_eefs)
522 {
523 if (getRobotModel()->getEndEffector(possible_eef)->hasLinkModel(end_effector_link_))
524 return possible_eef;
525 }
526 }
527 static std::string empty;
528 return empty;
529 }
530
531 bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& poses, const std::string& end_effector_link)
532 {
533 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
534 if (eef.empty())
535 {
536 RCLCPP_ERROR(logger_, "No end-effector to set the pose for");
537 return false;
538 }
539 else
540 {
541 pose_targets_[eef] = poses;
542 // make sure we don't store an actual stamp, since that will become stale can potentially cause tf errors
543 std::vector<geometry_msgs::msg::PoseStamped>& stored_poses = pose_targets_[eef];
544 for (geometry_msgs::msg::PoseStamped& stored_pose : stored_poses)
545 stored_pose.header.stamp = rclcpp::Time(0);
546 }
547 return true;
548 }
549
550 bool hasPoseTarget(const std::string& end_effector_link) const
551 {
552 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
553 return pose_targets_.find(eef) != pose_targets_.end();
554 }
555
556 const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link) const
557 {
558 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
559
560 // if multiple pose targets are set, return the first one
561 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
562 if (jt != pose_targets_.end())
563 {
564 if (!jt->second.empty())
565 return jt->second.at(0);
566 }
567
568 // or return an error
569 static const geometry_msgs::msg::PoseStamped UNKNOWN;
570 RCLCPP_ERROR(logger_, "Pose for end-effector '%s' not known.", eef.c_str());
571 return UNKNOWN;
572 }
573
574 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link) const
575 {
576 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
577
578 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
579 if (jt != pose_targets_.end())
580 {
581 if (!jt->second.empty())
582 return jt->second;
583 }
584
585 // or return an error
586 static const std::vector<geometry_msgs::msg::PoseStamped> EMPTY;
587 RCLCPP_ERROR(logger_, "Poses for end-effector '%s' are not known.", eef.c_str());
588 return EMPTY;
589 }
590
591 void setPoseReferenceFrame(const std::string& pose_reference_frame)
592 {
593 pose_reference_frame_ = pose_reference_frame;
594 }
595
596 const std::string& getPoseReferenceFrame() const
597 {
598 return pose_reference_frame_;
599 }
600
601 void setTargetType(ActiveTargetType type)
602 {
603 active_target_ = type;
604 }
605
606 ActiveTargetType getTargetType() const
607 {
608 return active_target_;
609 }
610
611 bool startStateMonitor(double wait)
612 {
613 if (!current_state_monitor_)
614 {
615 RCLCPP_ERROR(logger_, "Unable to monitor current robot state");
616 return false;
617 }
618
619 // if needed, start the monitor and wait up to 1 second for a full robot state
620 if (!current_state_monitor_->isActive())
621 current_state_monitor_->startStateMonitor();
622
623 current_state_monitor_->waitForCompleteState(opt_.group_name, wait);
624 return true;
625 }
626
627 bool getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds = 1.0)
628 {
629 if (!current_state_monitor_)
630 {
631 RCLCPP_ERROR(logger_, "Unable to get current robot state");
632 return false;
633 }
634
635 // if needed, start the monitor and wait up to 1 second for a full robot state
636 if (!current_state_monitor_->isActive())
637 current_state_monitor_->startStateMonitor();
638
639 if (!current_state_monitor_->waitForCurrentState(node_->now(), wait_seconds))
640 {
641 RCLCPP_ERROR(logger_, "Failed to fetch current robot state");
642 return false;
643 }
644
645 current_state = current_state_monitor_->getCurrentState();
646 return true;
647 }
648
650 {
651 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
652 {
653 RCLCPP_INFO_STREAM(logger_, "MoveGroup action client/server not ready");
654 return moveit::core::MoveItErrorCode::FAILURE;
655 }
656 RCLCPP_INFO_STREAM(logger_, "MoveGroup action client/server ready");
657
658 moveit_msgs::action::MoveGroup::Goal goal;
659 constructGoal(goal);
660 goal.planning_options.plan_only = true;
661 goal.planning_options.look_around = false;
662 goal.planning_options.replan = false;
663 goal.planning_options.planning_scene_diff.is_diff = true;
664 goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
665
666 bool done = false;
667 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
668 std::shared_ptr<moveit_msgs::action::MoveGroup::Result> res;
669 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
670
671 send_goal_opts.goal_response_callback =
672 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
673 if (!goal_handle)
674 {
675 done = true;
676 RCLCPP_INFO(logger_, "Planning request rejected");
677 }
678 else
679 RCLCPP_INFO(logger_, "Planning request accepted");
680 };
681 send_goal_opts.result_callback =
682 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
683 res = result.result;
684 code = result.code;
685 done = true;
686
687 switch (result.code)
688 {
689 case rclcpp_action::ResultCode::SUCCEEDED:
690 RCLCPP_INFO(logger_, "Planning request complete!");
691 break;
692 case rclcpp_action::ResultCode::ABORTED:
693 RCLCPP_INFO(logger_, "Planning request aborted");
694 return;
695 case rclcpp_action::ResultCode::CANCELED:
696 RCLCPP_INFO(logger_, "Planning request canceled");
697 return;
698 default:
699 RCLCPP_INFO(logger_, "Planning request unknown result code");
700 return;
701 }
702 };
703
704 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
705
706 // wait until send_goal_opts.result_callback is called
707 while (!done)
708 {
709 std::this_thread::sleep_for(std::chrono::milliseconds(1));
710 }
711
712 if (code != rclcpp_action::ResultCode::SUCCEEDED)
713 {
714 RCLCPP_ERROR_STREAM(logger_, "MoveGroupInterface::plan() failed or timeout reached");
715 return res->error_code;
716 }
717
718 plan.trajectory = res->planned_trajectory;
719 plan.start_state = res->trajectory_start;
720 plan.planning_time = res->planning_time;
721 RCLCPP_INFO(logger_, "time taken to generate plan: %g seconds", plan.planning_time);
722
723 return res->error_code;
724 }
725
727 {
728 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
729 {
730 RCLCPP_INFO_STREAM(logger_, "MoveGroup action client/server not ready");
731 return moveit::core::MoveItErrorCode::FAILURE;
732 }
733
734 moveit_msgs::action::MoveGroup::Goal goal;
735 constructGoal(goal);
736 goal.planning_options.plan_only = false;
737 goal.planning_options.look_around = can_look_;
738 goal.planning_options.replan = can_replan_;
739 goal.planning_options.replan_delay = replan_delay_;
740 goal.planning_options.planning_scene_diff.is_diff = true;
741 goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
742
743 bool done = false;
744 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
745 std::shared_ptr<moveit_msgs::action::MoveGroup_Result> res;
746 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
747
748 send_goal_opts.goal_response_callback =
749 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
750 if (!goal_handle)
751 {
752 done = true;
753 RCLCPP_INFO(logger_, "Plan and Execute request rejected");
754 }
755 else
756 RCLCPP_INFO(logger_, "Plan and Execute request accepted");
757 };
758 send_goal_opts.result_callback =
759 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
760 res = result.result;
761 code = result.code;
762 done = true;
763
764 switch (result.code)
765 {
766 case rclcpp_action::ResultCode::SUCCEEDED:
767 RCLCPP_INFO(logger_, "Plan and Execute request complete!");
768 break;
769 case rclcpp_action::ResultCode::ABORTED:
770 RCLCPP_INFO(logger_, "Plan and Execute request aborted");
771 return;
772 case rclcpp_action::ResultCode::CANCELED:
773 RCLCPP_INFO(logger_, "Plan and Execute request canceled");
774 return;
775 default:
776 RCLCPP_INFO(logger_, "Plan and Execute request unknown result code");
777 return;
778 }
779 };
780 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
781 if (!wait)
782 return moveit::core::MoveItErrorCode::SUCCESS;
783
784 // wait until send_goal_opts.result_callback is called
785 while (!done)
786 {
787 std::this_thread::sleep_for(std::chrono::milliseconds(1));
788 }
789
790 if (code != rclcpp_action::ResultCode::SUCCEEDED)
791 {
792 RCLCPP_ERROR_STREAM(logger_, "MoveGroupInterface::move() failed or timeout reached");
793 }
794 return res->error_code;
795 }
796
797 moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory, bool wait,
798 const std::vector<std::string>& controllers = std::vector<std::string>())
799 {
800 if (!execute_action_client_ || !execute_action_client_->action_server_is_ready())
801 {
802 RCLCPP_INFO_STREAM(logger_, "execute_action_client_ client/server not ready");
803 return moveit::core::MoveItErrorCode::FAILURE;
804 }
805
806 bool done = false;
807 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
808 std::shared_ptr<moveit_msgs::action::ExecuteTrajectory_Result> res;
809 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();
810
811 send_goal_opts.goal_response_callback =
812 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr& goal_handle) {
813 if (!goal_handle)
814 {
815 done = true;
816 RCLCPP_INFO(logger_, "Execute request rejected");
817 }
818 else
819 RCLCPP_INFO(logger_, "Execute request accepted");
820 };
821 send_goal_opts.result_callback =
822 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::WrappedResult& result) {
823 res = result.result;
824 code = result.code;
825 done = true;
826
827 switch (result.code)
828 {
829 case rclcpp_action::ResultCode::SUCCEEDED:
830 RCLCPP_INFO(logger_, "Execute request success!");
831 break;
832 case rclcpp_action::ResultCode::ABORTED:
833 RCLCPP_INFO(logger_, "Execute request aborted");
834 return;
835 case rclcpp_action::ResultCode::CANCELED:
836 RCLCPP_INFO(logger_, "Execute request canceled");
837 return;
838 default:
839 RCLCPP_INFO(logger_, "Execute request unknown result code");
840 return;
841 }
842 };
843
844 moveit_msgs::action::ExecuteTrajectory::Goal goal;
845 goal.trajectory = trajectory;
846 goal.controller_names = controllers;
847
848 auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts);
849 if (!wait)
850 return moveit::core::MoveItErrorCode::SUCCESS;
851
852 // wait until send_goal_opts.result_callback is called
853 while (!done)
854 {
855 std::this_thread::sleep_for(std::chrono::milliseconds(1));
856 }
857
858 if (code != rclcpp_action::ResultCode::SUCCEEDED)
859 {
860 RCLCPP_ERROR_STREAM(logger_, "MoveGroupInterface::execute() failed or timeout reached");
861 }
862 return res->error_code;
863 }
864
865 double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double step,
866 moveit_msgs::msg::RobotTrajectory& msg,
867 const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions,
868 moveit_msgs::msg::MoveItErrorCodes& error_code)
869 {
870 auto req = std::make_shared<moveit_msgs::srv::GetCartesianPath::Request>();
871 moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response;
872
873 req->start_state = considered_start_state_;
874 req->group_name = opt_.group_name;
875 req->header.frame_id = getPoseReferenceFrame();
876 req->header.stamp = getClock()->now();
877 req->waypoints = waypoints;
878 req->max_step = step;
879 req->path_constraints = path_constraints;
880 req->avoid_collisions = avoid_collisions;
881 req->link_name = getEndEffectorLink();
882 req->max_velocity_scaling_factor = max_velocity_scaling_factor_;
883 req->max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
884
885 auto future_response = cartesian_path_service_->async_send_request(req);
886 if (future_response.valid())
887 {
888 response = future_response.get();
889 error_code = response->error_code;
890 if (response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
891 {
892 msg = response->solution;
893 return response->fraction;
894 }
895 else
896 return -1.0;
897 }
898 else
899 {
900 error_code.val = error_code.FAILURE;
901 return -1.0;
902 }
903 }
904
905 void stop()
906 {
907 if (trajectory_event_publisher_)
908 {
909 std_msgs::msg::String event;
910 event.data = "stop";
911 trajectory_event_publisher_->publish(event);
912 }
913 }
914
915 bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links)
916 {
917 std::string l = link.empty() ? getEndEffectorLink() : link;
918 if (l.empty())
919 {
920 const std::vector<std::string>& links = joint_model_group_->getLinkModelNames();
921 if (!links.empty())
922 l = links[0];
923 }
924 if (l.empty())
925 {
926 RCLCPP_ERROR(logger_, "No known link to attach object '%s' to", object.c_str());
927 return false;
928 }
929 moveit_msgs::msg::AttachedCollisionObject aco;
930 aco.object.id = object;
931 aco.link_name.swap(l);
932 if (touch_links.empty())
933 {
934 aco.touch_links.push_back(aco.link_name);
935 }
936 else
937 {
938 aco.touch_links = touch_links;
939 }
940 aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
941 attached_object_publisher_->publish(aco);
942 return true;
943 }
944
945 bool detachObject(const std::string& name)
946 {
947 moveit_msgs::msg::AttachedCollisionObject aco;
948 // if name is a link
949 if (!name.empty() && joint_model_group_->hasLinkModel(name))
950 {
951 aco.link_name = name;
952 }
953 else
954 {
955 aco.object.id = name;
956 }
957 aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
958 if (aco.link_name.empty() && aco.object.id.empty())
959 {
960 // we only want to detach objects for this group
961 const std::vector<std::string>& lnames = joint_model_group_->getLinkModelNames();
962 for (const std::string& lname : lnames)
963 {
964 aco.link_name = lname;
965 attached_object_publisher_->publish(aco);
966 }
967 }
968 else
969 {
970 attached_object_publisher_->publish(aco);
971 }
972 return true;
973 }
974
976 {
977 return goal_position_tolerance_;
978 }
979
981 {
982 return goal_orientation_tolerance_;
983 }
984
986 {
987 return goal_joint_tolerance_;
988 }
989
990 void setGoalJointTolerance(double tolerance)
991 {
992 goal_joint_tolerance_ = tolerance;
993 }
994
995 void setGoalPositionTolerance(double tolerance)
996 {
997 goal_position_tolerance_ = tolerance;
998 }
999
1000 void setGoalOrientationTolerance(double tolerance)
1001 {
1002 goal_orientation_tolerance_ = tolerance;
1003 }
1004
1005 void setPlanningTime(double seconds)
1006 {
1007 if (seconds > 0.0)
1008 allowed_planning_time_ = seconds;
1009 }
1010
1011 double getPlanningTime() const
1012 {
1013 return allowed_planning_time_;
1014 }
1015
1016 void constructRobotState(moveit_msgs::msg::RobotState& state) const
1017 {
1018 state = considered_start_state_;
1019 }
1020
1021 void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request) const
1022 {
1023 request.group_name = opt_.group_name;
1024 request.num_planning_attempts = num_planning_attempts_;
1025 request.max_velocity_scaling_factor = max_velocity_scaling_factor_;
1026 request.max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
1027 request.allowed_planning_time = allowed_planning_time_;
1028 request.pipeline_id = planning_pipeline_id_;
1029 request.planner_id = planner_id_;
1030 request.workspace_parameters = workspace_parameters_;
1031 request.start_state = considered_start_state_;
1032
1033 if (active_target_ == JOINT)
1034 {
1035 request.goal_constraints.resize(1);
1036 request.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(
1037 getTargetRobotState(), joint_model_group_, goal_joint_tolerance_);
1038 }
1039 else if (active_target_ == POSE || active_target_ == POSITION || active_target_ == ORIENTATION)
1040 {
1041 // find out how many goals are specified
1042 std::size_t goal_count = 0;
1043 for (const auto& pose_target : pose_targets_)
1044 goal_count = std::max(goal_count, pose_target.second.size());
1045
1046 // start filling the goals;
1047 // each end effector has a number of possible poses (K) as valid goals
1048 // but there could be multiple end effectors specified, so we want each end effector
1049 // to reach the goal that corresponds to the goals of the other end effectors
1050 request.goal_constraints.resize(goal_count);
1051
1052 for (const auto& pose_target : pose_targets_)
1053 {
1054 for (std::size_t i = 0; i < pose_target.second.size(); ++i)
1055 {
1056 moveit_msgs::msg::Constraints c = kinematic_constraints::constructGoalConstraints(
1057 pose_target.first, pose_target.second[i], goal_position_tolerance_, goal_orientation_tolerance_);
1058 if (active_target_ == ORIENTATION)
1059 c.position_constraints.clear();
1060 if (active_target_ == POSITION)
1061 c.orientation_constraints.clear();
1062 request.goal_constraints[i] = kinematic_constraints::mergeConstraints(request.goal_constraints[i], c);
1063 }
1064 }
1065 }
1066 else
1067 RCLCPP_ERROR(logger_, "Unable to construct MotionPlanRequest representation");
1068
1069 if (path_constraints_)
1070 request.path_constraints = *path_constraints_;
1071 if (trajectory_constraints_)
1072 request.trajectory_constraints = *trajectory_constraints_;
1073 }
1074
1075 void constructGoal(moveit_msgs::action::MoveGroup::Goal& goal) const
1076 {
1077 constructMotionPlanRequest(goal.request);
1078 }
1079
1080 void setPathConstraints(const moveit_msgs::msg::Constraints& constraint)
1081 {
1082 path_constraints_ = std::make_unique<moveit_msgs::msg::Constraints>(constraint);
1083 }
1084
1085 bool setPathConstraints(const std::string& constraint)
1086 {
1087 if (constraints_storage_)
1088 {
1090 if (constraints_storage_->getConstraints(msg_m, constraint, robot_model_->getName(), opt_.group_name))
1091 {
1092 path_constraints_ =
1093 std::make_unique<moveit_msgs::msg::Constraints>(static_cast<moveit_msgs::msg::Constraints>(*msg_m));
1094 return true;
1095 }
1096 else
1097 return false;
1098 }
1099 else
1100 return false;
1101 }
1102
1104 {
1105 path_constraints_.reset();
1106 }
1107
1108 void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint)
1109 {
1110 trajectory_constraints_ = std::make_unique<moveit_msgs::msg::TrajectoryConstraints>(constraint);
1111 }
1112
1114 {
1115 trajectory_constraints_.reset();
1116 }
1117
1118 std::vector<std::string> getKnownConstraints() const
1119 {
1120 while (initializing_constraints_)
1121 {
1122 std::chrono::duration<double> d(0.01);
1123 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(d), rclcpp::Context::SharedPtr(nullptr));
1124 }
1125
1126 std::vector<std::string> c;
1127 if (constraints_storage_)
1128 constraints_storage_->getKnownConstraints(c, robot_model_->getName(), opt_.group_name);
1129
1130 return c;
1131 }
1132
1133 moveit_msgs::msg::Constraints getPathConstraints() const
1134 {
1135 if (path_constraints_)
1136 {
1137 return *path_constraints_;
1138 }
1139 else
1140 {
1141 return moveit_msgs::msg::Constraints();
1142 }
1143 }
1144
1145 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
1146 {
1147 if (trajectory_constraints_)
1148 {
1149 return *trajectory_constraints_;
1150 }
1151 else
1152 {
1153 return moveit_msgs::msg::TrajectoryConstraints();
1154 }
1155 }
1156
1157 void initializeConstraintsStorage(const std::string& host, unsigned int port)
1158 {
1159 initializing_constraints_ = true;
1160 if (constraints_init_thread_)
1161 constraints_init_thread_->join();
1162 constraints_init_thread_ =
1163 std::make_unique<std::thread>([this, host, port] { initializeConstraintsStorageThread(host, port); });
1164 }
1165
1166 void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
1167 {
1168 workspace_parameters_.header.frame_id = getRobotModel()->getModelFrame();
1169 workspace_parameters_.header.stamp = getClock()->now();
1170 workspace_parameters_.min_corner.x = minx;
1171 workspace_parameters_.min_corner.y = miny;
1172 workspace_parameters_.min_corner.z = minz;
1173 workspace_parameters_.max_corner.x = maxx;
1174 workspace_parameters_.max_corner.y = maxy;
1175 workspace_parameters_.max_corner.z = maxz;
1176 }
1177
1178 rclcpp::Clock::SharedPtr getClock()
1179 {
1180 return node_->get_clock();
1181 }
1182
1183private:
1184 void initializeConstraintsStorageThread(const std::string& host, unsigned int port)
1185 {
1186 // Set up db
1187 try
1188 {
1189 warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node_);
1190 conn->setParams(host, port);
1191 if (conn->connect())
1192 {
1193 constraints_storage_ = std::make_unique<moveit_warehouse::ConstraintsStorage>(conn);
1194 }
1195 }
1196 catch (std::exception& ex)
1197 {
1198 RCLCPP_ERROR(logger_, "%s", ex.what());
1199 }
1200 initializing_constraints_ = false;
1201 }
1202
1203 Options opt_;
1204 rclcpp::Node::SharedPtr node_;
1205 rclcpp::Logger logger_;
1206 rclcpp::CallbackGroup::SharedPtr callback_group_;
1207 rclcpp::executors::SingleThreadedExecutor callback_executor_;
1208 std::thread callback_thread_;
1209 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
1210 moveit::core::RobotModelConstPtr robot_model_;
1211 planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
1212
1213 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::MoveGroup>> move_action_client_;
1214 // std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::Pickup>> pick_action_client_;
1215 // std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::Place>> place_action_client_;
1216 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>> execute_action_client_;
1217
1218 // general planning params
1219 moveit_msgs::msg::RobotState considered_start_state_;
1220 moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
1221 double allowed_planning_time_;
1222 std::string planning_pipeline_id_;
1223 std::string planner_id_;
1224 unsigned int num_planning_attempts_;
1225 double max_velocity_scaling_factor_;
1226 double max_acceleration_scaling_factor_;
1227 double goal_joint_tolerance_;
1228 double goal_position_tolerance_;
1229 double goal_orientation_tolerance_;
1230 bool can_look_;
1231 int32_t look_around_attempts_;
1232 bool can_replan_;
1233 int32_t replan_attempts_;
1234 double replan_delay_;
1235
1236 // joint state goal
1237 moveit::core::RobotStatePtr joint_state_target_;
1238 const moveit::core::JointModelGroup* joint_model_group_;
1239
1240 // pose goal;
1241 // for each link we have a set of possible goal locations;
1242 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>> pose_targets_;
1243
1244 // common properties for goals
1245 ActiveTargetType active_target_;
1246 std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
1247 std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;
1248 std::string end_effector_link_;
1249 std::string pose_reference_frame_;
1250
1251 // ROS communication
1252 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr trajectory_event_publisher_;
1253 rclcpp::Publisher<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_object_publisher_;
1254 rclcpp::Client<moveit_msgs::srv::QueryPlannerInterfaces>::SharedPtr query_service_;
1255 rclcpp::Client<moveit_msgs::srv::GetPlannerParams>::SharedPtr get_params_service_;
1256 rclcpp::Client<moveit_msgs::srv::SetPlannerParams>::SharedPtr set_params_service_;
1257 rclcpp::Client<moveit_msgs::srv::GetCartesianPath>::SharedPtr cartesian_path_service_;
1258 // rclcpp::Client<moveit_msgs::srv::GraspPlanning>::SharedPtr plan_grasps_service_;
1259 std::unique_ptr<moveit_warehouse::ConstraintsStorage> constraints_storage_;
1260 std::unique_ptr<std::thread> constraints_init_thread_;
1261 bool initializing_constraints_;
1262};
1263
1264MoveGroupInterface::MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group_name,
1265 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1266 const rclcpp::Duration& wait_for_servers)
1267 : logger_(moveit::getLogger("moveit.ros.move_group_interface"))
1268{
1269 if (!rclcpp::ok())
1270 throw std::runtime_error("ROS does not seem to be running");
1271 impl_ =
1272 new MoveGroupInterfaceImpl(node, Options(group_name), tf_buffer ? tf_buffer : getSharedTF(), wait_for_servers);
1273}
1274
1275MoveGroupInterface::MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
1276 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1277 const rclcpp::Duration& wait_for_servers)
1278 : logger_(moveit::getLogger("moveit.ros.move_group_interface"))
1279{
1280 impl_ = new MoveGroupInterfaceImpl(node, opt, tf_buffer ? tf_buffer : getSharedTF(), wait_for_servers);
1281}
1282
1284{
1285 delete impl_;
1286}
1287
1289 : remembered_joint_values_(std::move(other.remembered_joint_values_))
1290 , impl_(other.impl_)
1291 , logger_(std::move(other.logger_))
1292{
1293 other.impl_ = nullptr;
1294}
1295
1297{
1298 if (this != &other)
1299 {
1300 delete impl_;
1301 impl_ = other.impl_;
1302 logger_ = other.logger_;
1303 remembered_joint_values_ = std::move(other.remembered_joint_values_);
1304 other.impl_ = nullptr;
1305 }
1306
1307 return *this;
1308}
1309
1310const std::string& MoveGroupInterface::getName() const
1311{
1312 return impl_->getOptions().group_name;
1313}
1314
1315const std::vector<std::string>& MoveGroupInterface::getNamedTargets() const
1316{
1317 // The pointer returned by getJointModelGroup is guaranteed by the class
1318 // constructor to always be non-null
1319 return impl_->getJointModelGroup()->getDefaultStateNames();
1320}
1321
1322const std::shared_ptr<tf2_ros::Buffer>& MoveGroupInterface::getTF() const
1323{
1324 return impl_->getTF();
1325}
1326
1327moveit::core::RobotModelConstPtr MoveGroupInterface::getRobotModel() const
1328{
1329 return impl_->getRobotModel();
1330}
1331
1332bool MoveGroupInterface::getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const
1333{
1334 return impl_->getInterfaceDescription(desc);
1335}
1336
1337bool MoveGroupInterface::getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const
1338{
1339 return impl_->getInterfaceDescriptions(desc);
1340}
1341
1342std::map<std::string, std::string> MoveGroupInterface::getPlannerParams(const std::string& planner_id,
1343 const std::string& group) const
1344{
1345 return impl_->getPlannerParams(planner_id, group);
1346}
1347
1348void MoveGroupInterface::setPlannerParams(const std::string& planner_id, const std::string& group,
1349 const std::map<std::string, std::string>& params, bool replace)
1350{
1351 impl_->setPlannerParams(planner_id, group, params, replace);
1352}
1353
1355{
1356 return impl_->getDefaultPlanningPipelineId();
1357}
1358
1359void MoveGroupInterface::setPlanningPipelineId(const std::string& pipeline_id)
1360{
1361 impl_->setPlanningPipelineId(pipeline_id);
1362}
1363
1365{
1366 return impl_->getPlanningPipelineId();
1367}
1368
1369std::string MoveGroupInterface::getDefaultPlannerId(const std::string& group) const
1370{
1371 return impl_->getDefaultPlannerId(group);
1372}
1373
1374void MoveGroupInterface::setPlannerId(const std::string& planner_id)
1375{
1376 impl_->setPlannerId(planner_id);
1377}
1378
1379const std::string& MoveGroupInterface::getPlannerId() const
1380{
1381 return impl_->getPlannerId();
1382}
1383
1384void MoveGroupInterface::setNumPlanningAttempts(unsigned int num_planning_attempts)
1385{
1386 impl_->setNumPlanningAttempts(num_planning_attempts);
1387}
1388
1389void MoveGroupInterface::setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
1390{
1391 impl_->setMaxVelocityScalingFactor(max_velocity_scaling_factor);
1392}
1393
1398
1399void MoveGroupInterface::setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
1400{
1401 impl_->setMaxAccelerationScalingFactor(max_acceleration_scaling_factor);
1402}
1403
1408
1413
1414rclcpp_action::Client<moveit_msgs::action::MoveGroup>& MoveGroupInterface::getMoveGroupClient() const
1415{
1416 return impl_->getMoveGroupClient();
1417}
1418
1420{
1421 return impl_->move(true);
1422}
1423
1425 const std::vector<std::string>& controllers)
1426{
1427 return impl_->execute(plan.trajectory, false, controllers);
1428}
1429
1430moveit::core::MoveItErrorCode MoveGroupInterface::asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
1431 const std::vector<std::string>& controllers)
1432{
1433 return impl_->execute(trajectory, false, controllers);
1434}
1435
1436moveit::core::MoveItErrorCode MoveGroupInterface::execute(const Plan& plan, const std::vector<std::string>& controllers)
1437{
1438 return impl_->execute(plan.trajectory, true, controllers);
1439}
1440
1441moveit::core::MoveItErrorCode MoveGroupInterface::execute(const moveit_msgs::msg::RobotTrajectory& trajectory,
1442 const std::vector<std::string>& controllers)
1443{
1444 return impl_->execute(trajectory, true, controllers);
1445}
1446
1451
1452double MoveGroupInterface::computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
1453 moveit_msgs::msg::RobotTrajectory& trajectory, bool avoid_collisions,
1454 moveit_msgs::msg::MoveItErrorCodes* error_code)
1455{
1456 moveit_msgs::msg::Constraints path_constraints_tmp;
1457 return computeCartesianPath(waypoints, eef_step, trajectory, moveit_msgs::msg::Constraints(), avoid_collisions,
1458 error_code);
1459}
1460
1461double MoveGroupInterface::computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
1462 moveit_msgs::msg::RobotTrajectory& trajectory,
1463 const moveit_msgs::msg::Constraints& path_constraints,
1464 bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1465{
1466 if (error_code)
1467 {
1468 return impl_->computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, *error_code);
1469 }
1470 else
1471 {
1472 moveit_msgs::msg::MoveItErrorCodes err_tmp;
1473 err_tmp.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1474 moveit_msgs::msg::MoveItErrorCodes& err = error_code ? *error_code : err_tmp;
1475 return impl_->computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, err);
1476 }
1477}
1478
1480{
1481 impl_->stop();
1482}
1483
1484void MoveGroupInterface::setStartState(const moveit_msgs::msg::RobotState& start_state)
1485{
1486 impl_->setStartState(start_state);
1487}
1488
1490{
1491 impl_->setStartState(start_state);
1492}
1493
1498
1504
1505const std::vector<std::string>& MoveGroupInterface::getJointNames() const
1506{
1507 return impl_->getJointModelGroup()->getVariableNames();
1508}
1509
1510const std::vector<std::string>& MoveGroupInterface::getLinkNames() const
1511{
1512 return impl_->getJointModelGroup()->getLinkModelNames();
1513}
1514
1515std::map<std::string, double> MoveGroupInterface::getNamedTargetValues(const std::string& name) const
1516{
1517 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1518 std::map<std::string, double> positions;
1519
1520 if (it != remembered_joint_values_.cend())
1521 {
1522 std::vector<std::string> names = impl_->getJointModelGroup()->getVariableNames();
1523 for (size_t x = 0; x < names.size(); ++x)
1524 {
1525 positions[names[x]] = it->second[x];
1526 }
1527 }
1528 else
1529 {
1530 if (!impl_->getJointModelGroup()->getVariableDefaultPositions(name, positions))
1531 {
1532 RCLCPP_ERROR(logger_, "The requested named target '%s' does not exist, returning empty positions.", name.c_str());
1533 }
1534 }
1535 return positions;
1536}
1537
1538bool MoveGroupInterface::setNamedTarget(const std::string& name)
1539{
1540 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1541 if (it != remembered_joint_values_.end())
1542 {
1543 return setJointValueTarget(it->second);
1544 }
1545 else
1546 {
1547 if (impl_->getTargetRobotState().setToDefaultValues(impl_->getJointModelGroup(), name))
1548 {
1549 impl_->setTargetType(JOINT);
1550 return true;
1551 }
1552 RCLCPP_ERROR(logger_, "The requested named target '%s' does not exist", name.c_str());
1553 return false;
1554 }
1555}
1556
1557void MoveGroupInterface::getJointValueTarget(std::vector<double>& group_variable_values) const
1558{
1559 impl_->getTargetRobotState().copyJointGroupPositions(impl_->getJointModelGroup(), group_variable_values);
1560}
1561
1562bool MoveGroupInterface::setJointValueTarget(const std::vector<double>& joint_values)
1563{
1564 const auto n_group_joints = impl_->getJointModelGroup()->getVariableCount();
1565 if (joint_values.size() != n_group_joints)
1566 {
1567 RCLCPP_DEBUG_STREAM(logger_, "Provided joint value list has length " << joint_values.size() << " but group "
1568 << impl_->getJointModelGroup()->getName()
1569 << " has " << n_group_joints << " joints");
1570 return false;
1571 }
1572 impl_->setTargetType(JOINT);
1573 impl_->getTargetRobotState().setJointGroupPositions(impl_->getJointModelGroup(), joint_values);
1575}
1576
1577bool MoveGroupInterface::setJointValueTarget(const std::map<std::string, double>& variable_values)
1578{
1579 const auto& allowed = impl_->getJointModelGroup()->getVariableNames();
1580 for (const auto& pair : variable_values)
1581 {
1582 if (std::find(allowed.begin(), allowed.end(), pair.first) == allowed.end())
1583 {
1584 RCLCPP_ERROR_STREAM(logger_, "joint variable " << pair.first << " is not part of group "
1585 << impl_->getJointModelGroup()->getName());
1586 return false;
1587 }
1588 }
1589
1590 impl_->setTargetType(JOINT);
1591 impl_->getTargetRobotState().setVariablePositions(variable_values);
1593}
1594
1595bool MoveGroupInterface::setJointValueTarget(const std::vector<std::string>& variable_names,
1596 const std::vector<double>& variable_values)
1597{
1598 if (variable_names.size() != variable_values.size())
1599 {
1600 RCLCPP_ERROR_STREAM(logger_, "sizes of name and position arrays do not match");
1601 return false;
1602 }
1603 const auto& allowed = impl_->getJointModelGroup()->getVariableNames();
1604 for (const auto& variable_name : variable_names)
1605 {
1606 if (std::find(allowed.begin(), allowed.end(), variable_name) == allowed.end())
1607 {
1608 RCLCPP_ERROR_STREAM(logger_, "joint variable " << variable_name << " is not part of group "
1609 << impl_->getJointModelGroup()->getName());
1610 return false;
1611 }
1612 }
1613
1614 impl_->setTargetType(JOINT);
1615 impl_->getTargetRobotState().setVariablePositions(variable_names, variable_values);
1617}
1618
1620{
1621 impl_->setTargetType(JOINT);
1622 impl_->getTargetRobotState() = rstate;
1624}
1625
1626bool MoveGroupInterface::setJointValueTarget(const std::string& joint_name, double value)
1627{
1628 std::vector<double> values(1, value);
1629 return setJointValueTarget(joint_name, values);
1630}
1631
1632bool MoveGroupInterface::setJointValueTarget(const std::string& joint_name, const std::vector<double>& values)
1633{
1634 impl_->setTargetType(JOINT);
1635 const moveit::core::JointModel* jm = impl_->getJointModelGroup()->getJointModel(joint_name);
1636 if (jm && jm->getVariableCount() == values.size())
1637 {
1638 impl_->getTargetRobotState().setJointPositions(jm, values);
1639 return impl_->getTargetRobotState().satisfiesBounds(jm, impl_->getGoalJointTolerance());
1640 }
1641
1642 RCLCPP_ERROR_STREAM(logger_,
1643 "joint " << joint_name << " is not part of group " << impl_->getJointModelGroup()->getName());
1644 return false;
1645}
1646
1647bool MoveGroupInterface::setJointValueTarget(const sensor_msgs::msg::JointState& state)
1648{
1649 return setJointValueTarget(state.name, state.position);
1650}
1651
1652bool MoveGroupInterface::setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
1653 const std::string& end_effector_link)
1654{
1655 return impl_->setJointValueTarget(eef_pose, end_effector_link, "", false);
1656}
1657
1658bool MoveGroupInterface::setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
1659 const std::string& end_effector_link)
1660{
1661 return impl_->setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id, false);
1662}
1663
1664bool MoveGroupInterface::setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link)
1665{
1666 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1667 return setJointValueTarget(msg, end_effector_link);
1668}
1669
1670bool MoveGroupInterface::setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
1671 const std::string& end_effector_link)
1672{
1673 return impl_->setJointValueTarget(eef_pose, end_effector_link, "", true);
1674}
1675
1676bool MoveGroupInterface::setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
1677 const std::string& end_effector_link)
1678{
1679 return impl_->setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id, true);
1680}
1681
1682bool MoveGroupInterface::setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose,
1683 const std::string& end_effector_link)
1684{
1685 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1686 return setApproximateJointValueTarget(msg, end_effector_link);
1687}
1688
1693
1695{
1696 return impl_->getEndEffectorLink();
1697}
1698
1699const std::string& MoveGroupInterface::getEndEffector() const
1700{
1701 return impl_->getEndEffector();
1702}
1703
1704bool MoveGroupInterface::setEndEffectorLink(const std::string& link_name)
1705{
1706 if (impl_->getEndEffectorLink().empty() || link_name.empty())
1707 return false;
1708 impl_->setEndEffectorLink(link_name);
1709 impl_->setTargetType(POSE);
1710 return true;
1711}
1712
1713bool MoveGroupInterface::setEndEffector(const std::string& eef_name)
1714{
1715 const moveit::core::JointModelGroup* jmg = impl_->getRobotModel()->getEndEffector(eef_name);
1716 if (jmg)
1717 return setEndEffectorLink(jmg->getEndEffectorParentGroup().second);
1718 return false;
1719}
1720
1721void MoveGroupInterface::clearPoseTarget(const std::string& end_effector_link)
1722{
1723 impl_->clearPoseTarget(end_effector_link);
1724}
1725
1730
1731bool MoveGroupInterface::setPoseTarget(const Eigen::Isometry3d& pose, const std::string& end_effector_link)
1732{
1733 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1734 pose_msg[0].pose = tf2::toMsg(pose);
1735 pose_msg[0].header.frame_id = getPoseReferenceFrame();
1736 pose_msg[0].header.stamp = impl_->getClock()->now();
1737 return setPoseTargets(pose_msg, end_effector_link);
1738}
1739
1740bool MoveGroupInterface::setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link)
1741{
1742 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1743 pose_msg[0].pose = target;
1744 pose_msg[0].header.frame_id = getPoseReferenceFrame();
1745 pose_msg[0].header.stamp = impl_->getClock()->now();
1746 return setPoseTargets(pose_msg, end_effector_link);
1747}
1748
1749bool MoveGroupInterface::setPoseTarget(const geometry_msgs::msg::PoseStamped& target,
1750 const std::string& end_effector_link)
1751{
1752 std::vector<geometry_msgs::msg::PoseStamped> targets(1, target);
1753 return setPoseTargets(targets, end_effector_link);
1754}
1755
1756bool MoveGroupInterface::setPoseTargets(const EigenSTL::vector_Isometry3d& target, const std::string& end_effector_link)
1757{
1758 std::vector<geometry_msgs::msg::PoseStamped> pose_out(target.size());
1759 rclcpp::Time tm = impl_->getClock()->now();
1760 const std::string& frame_id = getPoseReferenceFrame();
1761 for (std::size_t i = 0; i < target.size(); ++i)
1762 {
1763 pose_out[i].pose = tf2::toMsg(target[i]);
1764 pose_out[i].header.stamp = tm;
1765 pose_out[i].header.frame_id = frame_id;
1766 }
1767 return setPoseTargets(pose_out, end_effector_link);
1768}
1769
1770bool MoveGroupInterface::setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target,
1771 const std::string& end_effector_link)
1772{
1773 std::vector<geometry_msgs::msg::PoseStamped> target_stamped(target.size());
1774 rclcpp::Time tm = impl_->getClock()->now();
1775 const std::string& frame_id = getPoseReferenceFrame();
1776 for (std::size_t i = 0; i < target.size(); ++i)
1777 {
1778 target_stamped[i].pose = target[i];
1779 target_stamped[i].header.stamp = tm;
1780 target_stamped[i].header.frame_id = frame_id;
1781 }
1782 return setPoseTargets(target_stamped, end_effector_link);
1783}
1784
1785bool MoveGroupInterface::setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
1786 const std::string& end_effector_link)
1787{
1788 if (target.empty())
1789 {
1790 RCLCPP_ERROR(logger_, "No pose specified as goal target");
1791 return false;
1792 }
1793 else
1794 {
1795 impl_->setTargetType(POSE);
1796 return impl_->setPoseTargets(target, end_effector_link);
1797 }
1798}
1799
1800const geometry_msgs::msg::PoseStamped& MoveGroupInterface::getPoseTarget(const std::string& end_effector_link) const
1801{
1802 return impl_->getPoseTarget(end_effector_link);
1803}
1804
1805const std::vector<geometry_msgs::msg::PoseStamped>&
1806MoveGroupInterface::getPoseTargets(const std::string& end_effector_link) const
1807{
1808 return impl_->getPoseTargets(end_effector_link);
1809}
1810
1811namespace
1812{
1813inline void transformPose(const tf2_ros::Buffer& tf_buffer, const std::string& desired_frame,
1814 geometry_msgs::msg::PoseStamped& target)
1815{
1816 if (desired_frame != target.header.frame_id)
1817 {
1818 geometry_msgs::msg::PoseStamped target_in(target);
1819 tf_buffer.transform(target_in, target, desired_frame);
1820 // we leave the stamp to ros::Time(0) on purpose
1821 target.header.stamp = rclcpp::Time(0);
1822 }
1823}
1824} // namespace
1825
1826bool MoveGroupInterface::setPositionTarget(double x, double y, double z, const std::string& end_effector_link)
1827{
1828 geometry_msgs::msg::PoseStamped target;
1829 if (impl_->hasPoseTarget(end_effector_link))
1830 {
1831 target = getPoseTarget(end_effector_link);
1832 transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
1833 }
1834 else
1835 {
1836 target.pose.orientation.x = 0.0;
1837 target.pose.orientation.y = 0.0;
1838 target.pose.orientation.z = 0.0;
1839 target.pose.orientation.w = 1.0;
1840 target.header.frame_id = impl_->getPoseReferenceFrame();
1841 }
1842
1843 target.pose.position.x = x;
1844 target.pose.position.y = y;
1845 target.pose.position.z = z;
1846 bool result = setPoseTarget(target, end_effector_link);
1847 impl_->setTargetType(POSITION);
1848 return result;
1849}
1850
1851bool MoveGroupInterface::setRPYTarget(double r, double p, double y, const std::string& end_effector_link)
1852{
1853 geometry_msgs::msg::PoseStamped target;
1854 if (impl_->hasPoseTarget(end_effector_link))
1855 {
1856 target = getPoseTarget(end_effector_link);
1857 transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
1858 }
1859 else
1860 {
1861 target.pose.position.x = 0.0;
1862 target.pose.position.y = 0.0;
1863 target.pose.position.z = 0.0;
1864 target.header.frame_id = impl_->getPoseReferenceFrame();
1865 }
1866 tf2::Quaternion q;
1867 q.setRPY(r, p, y);
1868 target.pose.orientation = tf2::toMsg(q);
1869 bool result = setPoseTarget(target, end_effector_link);
1870 impl_->setTargetType(ORIENTATION);
1871 return result;
1872}
1873
1874bool MoveGroupInterface::setOrientationTarget(double x, double y, double z, double w,
1875 const std::string& end_effector_link)
1876{
1877 geometry_msgs::msg::PoseStamped target;
1878 if (impl_->hasPoseTarget(end_effector_link))
1879 {
1880 target = getPoseTarget(end_effector_link);
1881 transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
1882 }
1883 else
1884 {
1885 target.pose.position.x = 0.0;
1886 target.pose.position.y = 0.0;
1887 target.pose.position.z = 0.0;
1888 target.header.frame_id = impl_->getPoseReferenceFrame();
1889 }
1890
1891 target.pose.orientation.x = x;
1892 target.pose.orientation.y = y;
1893 target.pose.orientation.z = z;
1894 target.pose.orientation.w = w;
1895 bool result = setPoseTarget(target, end_effector_link);
1896 impl_->setTargetType(ORIENTATION);
1897 return result;
1898}
1899
1900void MoveGroupInterface::setPoseReferenceFrame(const std::string& pose_reference_frame)
1901{
1902 impl_->setPoseReferenceFrame(pose_reference_frame);
1903}
1904
1906{
1907 return impl_->getPoseReferenceFrame();
1908}
1909
1911{
1912 return impl_->getGoalJointTolerance();
1913}
1914
1916{
1917 return impl_->getGoalPositionTolerance();
1918}
1919
1924
1926{
1927 setGoalJointTolerance(tolerance);
1928 setGoalPositionTolerance(tolerance);
1929 setGoalOrientationTolerance(tolerance);
1930}
1931
1933{
1934 impl_->setGoalJointTolerance(tolerance);
1935}
1936
1938{
1939 impl_->setGoalPositionTolerance(tolerance);
1940}
1941
1943{
1944 impl_->setGoalOrientationTolerance(tolerance);
1945}
1946
1947void MoveGroupInterface::rememberJointValues(const std::string& name)
1948{
1950}
1951
1953{
1954 return impl_->startStateMonitor(wait);
1955}
1956
1958{
1959 moveit::core::RobotStatePtr current_state;
1960 std::vector<double> values;
1961 if (impl_->getCurrentState(current_state))
1962 current_state->copyJointGroupPositions(getName(), values);
1963 return values;
1964}
1965
1967{
1968 std::vector<double> r;
1970 return r;
1971}
1972
1973geometry_msgs::msg::PoseStamped MoveGroupInterface::getRandomPose(const std::string& end_effector_link) const
1974{
1975 const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
1976 Eigen::Isometry3d pose;
1977 pose.setIdentity();
1978 if (eef.empty())
1979 {
1980 RCLCPP_ERROR(logger_, "No end-effector specified");
1981 }
1982 else
1983 {
1984 moveit::core::RobotStatePtr current_state;
1985 if (impl_->getCurrentState(current_state))
1986 {
1987 current_state->setToRandomPositions(impl_->getJointModelGroup());
1988 const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
1989 if (lm)
1990 pose = current_state->getGlobalLinkTransform(lm);
1991 }
1992 }
1993 geometry_msgs::msg::PoseStamped pose_msg;
1994 pose_msg.header.stamp = impl_->getClock()->now();
1995 pose_msg.header.frame_id = impl_->getRobotModel()->getModelFrame();
1996 pose_msg.pose = tf2::toMsg(pose);
1997 return pose_msg;
1998}
1999
2000geometry_msgs::msg::PoseStamped MoveGroupInterface::getCurrentPose(const std::string& end_effector_link) const
2001{
2002 const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
2003 Eigen::Isometry3d pose;
2004 pose.setIdentity();
2005 if (eef.empty())
2006 {
2007 RCLCPP_ERROR(logger_, "No end-effector specified");
2008 }
2009 else
2010 {
2011 moveit::core::RobotStatePtr current_state;
2012 if (impl_->getCurrentState(current_state))
2013 {
2014 const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
2015 if (lm)
2016 pose = current_state->getGlobalLinkTransform(lm);
2017 }
2018 }
2019 geometry_msgs::msg::PoseStamped pose_msg;
2020 pose_msg.header.stamp = impl_->getClock()->now();
2021 pose_msg.header.frame_id = impl_->getRobotModel()->getModelFrame();
2022 pose_msg.pose = tf2::toMsg(pose);
2023 return pose_msg;
2024}
2025
2026std::vector<double> MoveGroupInterface::getCurrentRPY(const std::string& end_effector_link) const
2027{
2028 std::vector<double> result;
2029 const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
2030 if (eef.empty())
2031 {
2032 RCLCPP_ERROR(logger_, "No end-effector specified");
2033 }
2034 else
2035 {
2036 moveit::core::RobotStatePtr current_state;
2037 if (impl_->getCurrentState(current_state))
2038 {
2039 const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
2040 if (lm)
2041 {
2042 result.resize(3);
2043 geometry_msgs::msg::TransformStamped tfs = tf2::eigenToTransform(current_state->getGlobalLinkTransform(lm));
2044 double pitch, roll, yaw;
2045 tf2::getEulerYPR<geometry_msgs::msg::Quaternion>(tfs.transform.rotation, yaw, pitch, roll);
2046 result[0] = roll;
2047 result[1] = pitch;
2048 result[2] = yaw;
2049 }
2050 }
2051 }
2052 return result;
2053}
2054
2055const std::vector<std::string>& MoveGroupInterface::getActiveJoints() const
2056{
2058}
2059
2060const std::vector<std::string>& MoveGroupInterface::getJoints() const
2061{
2062 return impl_->getJointModelGroup()->getJointModelNames();
2063}
2064
2066{
2067 return impl_->getJointModelGroup()->getVariableCount();
2068}
2069
2070moveit::core::RobotStatePtr MoveGroupInterface::getCurrentState(double wait) const
2071{
2072 moveit::core::RobotStatePtr current_state;
2073 impl_->getCurrentState(current_state, wait);
2074 return current_state;
2075}
2076
2077void MoveGroupInterface::rememberJointValues(const std::string& name, const std::vector<double>& values)
2078{
2079 remembered_joint_values_[name] = values;
2080}
2081
2082void MoveGroupInterface::forgetJointValues(const std::string& name)
2083{
2084 remembered_joint_values_.erase(name);
2085}
2086
2088{
2089 impl_->can_look_ = flag;
2090 RCLCPP_DEBUG(logger_, "Looking around: %s", flag ? "yes" : "no");
2091}
2092
2094{
2095 if (attempts < 0)
2096 {
2097 RCLCPP_ERROR(logger_, "Tried to set negative number of look-around attempts");
2098 }
2099 else
2100 {
2101 RCLCPP_DEBUG_STREAM(logger_, "Look around attempts: " << attempts);
2102 impl_->look_around_attempts_ = attempts;
2103 }
2104}
2105
2107{
2108 impl_->can_replan_ = flag;
2109 RCLCPP_DEBUG(logger_, "Replanning: %s", flag ? "yes" : "no");
2110}
2111
2113{
2114 if (attempts < 0)
2115 {
2116 RCLCPP_ERROR(logger_, "Tried to set negative number of replan attempts");
2117 }
2118 else
2119 {
2120 RCLCPP_DEBUG_STREAM(logger_, "Replan Attempts: " << attempts);
2121 impl_->replan_attempts_ = attempts;
2122 }
2123}
2124
2126{
2127 if (delay < 0.0)
2128 {
2129 RCLCPP_ERROR(logger_, "Tried to set negative replan delay");
2130 }
2131 else
2132 {
2133 RCLCPP_DEBUG_STREAM(logger_, "Replan Delay: " << delay);
2134 impl_->replan_delay_ = delay;
2135 }
2136}
2137
2138std::vector<std::string> MoveGroupInterface::getKnownConstraints() const
2139{
2140 return impl_->getKnownConstraints();
2141}
2142
2143moveit_msgs::msg::Constraints MoveGroupInterface::getPathConstraints() const
2144{
2145 return impl_->getPathConstraints();
2146}
2147
2148bool MoveGroupInterface::setPathConstraints(const std::string& constraint)
2149{
2150 return impl_->setPathConstraints(constraint);
2151}
2152
2153void MoveGroupInterface::setPathConstraints(const moveit_msgs::msg::Constraints& constraint)
2154{
2155 impl_->setPathConstraints(constraint);
2156}
2157
2162
2163moveit_msgs::msg::TrajectoryConstraints MoveGroupInterface::getTrajectoryConstraints() const
2164{
2165 return impl_->getTrajectoryConstraints();
2166}
2167
2168void MoveGroupInterface::setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint)
2169{
2170 impl_->setTrajectoryConstraints(constraint);
2171}
2172
2177
2178void MoveGroupInterface::setConstraintsDatabase(const std::string& host, unsigned int port)
2179{
2180 impl_->initializeConstraintsStorage(host, port);
2181}
2182
2183void MoveGroupInterface::setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
2184{
2185 impl_->setWorkspace(minx, miny, minz, maxx, maxy, maxz);
2186}
2187
2190{
2191 impl_->setPlanningTime(seconds);
2192}
2193
2196{
2197 return impl_->getPlanningTime();
2198}
2199
2200const rclcpp::Node::SharedPtr& MoveGroupInterface::getNode() const
2201{
2202 return impl_->node_;
2203}
2204
2206{
2207 return impl_->getRobotModel()->getModelFrame();
2208}
2209
2210const std::vector<std::string>& MoveGroupInterface::getJointModelGroupNames() const
2211{
2212 return impl_->getRobotModel()->getJointModelGroupNames();
2213}
2214
2215bool MoveGroupInterface::attachObject(const std::string& object, const std::string& link)
2216{
2217 return attachObject(object, link, std::vector<std::string>());
2218}
2219
2220bool MoveGroupInterface::attachObject(const std::string& object, const std::string& link,
2221 const std::vector<std::string>& touch_links)
2222{
2223 return impl_->attachObject(object, link, touch_links);
2224}
2225
2226bool MoveGroupInterface::detachObject(const std::string& name)
2227{
2228 return impl_->detachObject(name);
2229}
2230
2231void MoveGroupInterface::constructRobotState(moveit_msgs::msg::RobotState& state)
2232{
2233 impl_->constructRobotState(state);
2234}
2235
2236void MoveGroupInterface::constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& goal_out)
2237{
2238 impl_->constructMotionPlanRequest(goal_out);
2239}
2240
2241} // namespace planning_interface
2242} // namespace moveit
bool isChain() const
Check if this group is a linear chain.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
Get the name of the group this end-effector attaches to (first) and the name of the link in that grou...
const std::string & getName() const
Get the name of the joint group.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure.
const std::vector< std::string > & getDefaultStateNames() const
Get the names of the known default states (as specified in the SRDF)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
void setJointPositions(const std::string &joint_name, const double *position)
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() const
void constructGoal(moveit_msgs::action::MoveGroup::Goal &goal) const
void setMaxScalingFactor(double &variable, const double target_value, const char *factor_name, double fallback_value)
bool getCurrentState(moveit::core::RobotStatePtr &current_state, double wait_seconds=1.0)
bool attachObject(const std::string &object, const std::string &link, const std::vector< std::string > &touch_links)
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="")
void initializeConstraintsStorage(const std::string &host, unsigned int port)
void setPathConstraints(const moveit_msgs::msg::Constraints &constraint)
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double step, moveit_msgs::msg::RobotTrajectory &msg, const moveit_msgs::msg::Constraints &path_constraints, bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes &error_code)
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request) const
MoveGroupInterfaceImpl(const rclcpp::Node::SharedPtr &node, const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const rclcpp::Duration &wait_for_servers)
bool setPoseTargets(const std::vector< geometry_msgs::msg::PoseStamped > &poses, const std::string &end_effector_link)
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link) const
moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory &trajectory, bool wait, const std::vector< std::string > &controllers=std::vector< std::string >())
bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription &desc)
void setStartState(const moveit_msgs::msg::RobotState &start_state)
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link) const
bool setJointValueTarget(const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link, const std::string &frame, bool approx)
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > &params, bool replace=false)
bool getInterfaceDescriptions(std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &desc)
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Client class to conveniently use the ROS interfaces provided by the move_group node.
std::vector< double > getRandomJointValues() const
Get random joint values for the joints planned for by this instance (see getJoints())
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double eef_step, double, moveit_msgs::msg::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::msg::MoveItErrorCodes *error_code=nullptr)
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters...
void setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,...
const std::string & getEndEffectorLink() const
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly ...
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
const std::vector< std::string > & getNamedTargets() const
Get the names of the named robot states available as targets, both either remembered states or defaul...
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="") const
Get the planner parameters for given group and planner_id.
void stop()
Stop any trajectory execution, if one is active.
MoveGroupInterface(const rclcpp::Node::SharedPtr &node, const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), const rclcpp::Duration &wait_for_servers=rclcpp::Duration::from_seconds(-1))
Construct a MoveGroupInterface instance call using a specified set of options opt.
const std::string & getPlannerId() const
Get the current planner_id.
void setReplanDelay(double delay)
Sleep this duration between replanning attempts (in walltime seconds)
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
moveit::core::MoveItErrorCode plan(Plan &plan)
Compute a motion plan that takes the group declared in the constructor from the current state to the ...
void setGoalTolerance(double tolerance)
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance fo...
void setGoalPositionTolerance(double tolerance)
Set the position tolerance that is used for reaching the goal when moving to a pose.
const std::string & getPlanningFrame() const
Get the name of the frame in which the robot is planning.
bool setPoseTargets(const EigenSTL::vector_Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set goal poses for end_effector_link.
bool setPoseTarget(const Eigen::Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set the goal pose of the end-effector end_effector_link.
moveit::core::MoveItErrorCode asyncMove()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
void setPlanningPipelineId(const std::string &pipeline_id)
Specify a planning pipeline to be used for further planning.
double getGoalJointTolerance() const
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configur...
bool setEndEffectorLink(const std::string &end_effector_link)
Specify the parent link of the end-effector. This end_effector_link will be used in calls to pose tar...
void setStartStateToCurrentState()
Set the starting state for planning to be that reported by the robot's joint state publication.
bool getInterfaceDescriptions(std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &desc) const
Get the descriptions of all planning plugins loaded by the action server.
void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0...
bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link="")
Set the goal position of the end-effector end_effector_link to be (x, y, z).
const std::string & getEndEffector() const
Get the current end-effector name. This returns the value set by setEndEffector() (or indirectly by s...
void clearPathConstraints()
Specify that no path constraints are to be used. This removes any path constraints set in previous ca...
bool attachObject(const std::string &object, const std::string &link="")
Given the name of an object in the planning scene, make the object attached to a link of the robot....
moveit_msgs::msg::Constraints getPathConstraints() const
Get the actual set of constraints in use with this MoveGroupInterface.
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of times the motion plan is to be computed from scratch before the shortest solution i...
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() const
Get the move_group action client used by the MoveGroupInterface. The client can be used for querying ...
std::vector< double > getCurrentJointValues() const
Get the current joint values for the joints planned for by this instance (see getJoints())
bool setNamedTarget(const std::string &name)
Set the current joint values to be ones previously remembered by rememberJointValues() or,...
const std::vector< std::string > & getJointNames() const
Get vector of names of joints available in move group.
moveit::core::MoveItErrorCode move()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
void setReplanAttempts(int32_t attempts)
Maximum number of replanning attempts.
void allowReplanning(bool flag)
Specify whether the robot is allowed to replan if it detects changes in the environment.
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
moveit::core::MoveItErrorCode execute(const Plan &plan, const std::vector< std::string > &controllers=std::vector< std::string >())
Given a plan, execute it while waiting for completion.
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request)
Build the MotionPlanRequest that would be sent to the move_group action with plan() or move() and sto...
bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,...
bool setJointValueTarget(const std::vector< double > &group_variable_values)
Set the JointValueTarget and use it for future planning requests.
const rclcpp::Node::SharedPtr & getNode() const
Get the ROS node handle of this instance operates on.
bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians.
void setGoalOrientationTolerance(double tolerance)
Set the orientation tolerance that is used for reaching the goal when moving to a pose.
void clearPoseTarget(const std::string &end_effector_link="")
Forget pose(s) specified for end_effector_link.
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link="") const
void setGoalJointTolerance(double tolerance)
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint va...
std::string getDefaultPlannerId(const std::string &group="") const
Get the default planner of the current planning pipeline for the given group (or the pipeline's defau...
void setRandomTarget()
Set the joint state goal to a random joint configuration.
moveit::core::RobotStatePtr getCurrentState(double wait=1) const
Get the current state of the robot within the duration specified by wait.
void getJointValueTarget(std::vector< double > &group_variable_values) const
Get the current joint state goal in a form compatible to setJointValueTarget()
const std::vector< std::string > & getActiveJoints() const
Get only the active (actuated) joints this instance operates on.
void rememberJointValues(const std::string &name)
Remember the current joint values (of the robot being monitored) under name. These can be used by set...
void setLookAroundAttempts(int32_t attempts)
How often is the system allowed to move the camera to update environment model when looking.
bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription &desc) const
Get the description of the default planning plugin loaded by the action server.
const std::string & getName() const
Get the name of the group this instance operates on.
moveit::core::MoveItErrorCode asyncExecute(const Plan &plan, const std::vector< std::string > &controllers=std::vector< std::string >())
Given a plan, execute it without waiting for completion.
const std::vector< std::string > & getJoints() const
Get all the joints this instance operates on (including fixed joints)
bool detachObject(const std::string &name="")
Detach an object. name specifies the name of the object attached to this group, or the name of the li...
void setPoseReferenceFrame(const std::string &pose_reference_frame)
Specify which reference frame to assume for poses specified without a reference frame.
const std::shared_ptr< tf2_ros::Buffer > & getTF() const
Get the tf2_ros::Buffer.
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link="") const
double getMaxVelocityScalingFactor() const
Get the max velocity scaling factor set by setMaxVelocityScalingFactor().
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
const std::vector< std::string > & getLinkNames() const
Get vector of names of links available in move group.
double getMaxAccelerationScalingFactor() const
Get the max acceleration scaling factor set by setMaxAccelerationScalingFactor().
void setStartState(const moveit_msgs::msg::RobotState &start_state)
If a different start state should be considered instead of the current state of the robot,...
bool setPathConstraints(const std::string &constraint)
Specify a set of path constraints to use. The constraints are looked up by name from the Mongo databa...
void clearPoseTargets()
Forget any poses specified for all end-effectors.
void setPlannerId(const std::string &planner_id)
Specify a planner to be used for further planning.
bool setEndEffector(const std::string &eef_name)
Specify the name of the end-effector to use. This is equivalent to setting the EndEffectorLink to the...
const std::string & getPoseReferenceFrame() const
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the...
const std::string & getPlanningPipelineId() const
Get the current planning_pipeline_id.
void setConstraintsDatabase(const std::string &host, unsigned int port)
Specify where the database server that holds known constraints resides.
std::vector< double > getCurrentRPY(const std::string &end_effector_link="") const
Get the roll-pitch-yaw (XYZ) for the end-effector end_effector_link. If end_effector_link is empty (t...
void forgetJointValues(const std::string &name)
Forget the joint values remembered under name.
std::vector< std::string > getKnownConstraints() const
Get the names of the known constraints as read from the Mongo database, if a connection was achieved.
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
const moveit::core::RobotState & getTargetRobotState() const
geometry_msgs::msg::PoseStamped getRandomPose(const std::string &end_effector_link="") const
Get a random reachable pose for the end-effector end_effector_link. If end_effector_link is empty (th...
double getGoalOrientationTolerance() const
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll,...
void allowLooking(bool flag)
Specify whether the robot is allowed to look around before moving if it determines it should (default...
std::map< std::string, double > getNamedTargetValues(const std::string &name) const
Get the joint angles for targets specified by name.
geometry_msgs::msg::PoseStamped getCurrentPose(const std::string &end_effector_link="") const
Get the pose for the end-effector end_effector_link. If end_effector_link is empty (the default value...
bool startStateMonitor(double wait=1.0)
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically co...
unsigned int getVariableCount() const
Get the number of variables used to describe the state of this group. This is larger or equal to the ...
double getGoalPositionTolerance() const
Get the tolerance that is used for reaching a position goal. This is be the radius of a sphere where ...
double getPlanningTime() const
Get the number of seconds set by setPlanningTime()
void setPlanningTime(double seconds)
Specify the maximum amount of time to use when planning.
bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link="")
Set the joint state goal for a particular joint by computing IK.
void constructRobotState(moveit_msgs::msg::RobotState &state)
Build a RobotState message for use with plan() or computeCartesianPath() If the move_group has a cust...
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > &params, bool bReplace=false)
Set the planner parameters for given group and planner_id.
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Specify the workspace bounding box. The box is specified in the planning frame (i....
const std::vector< std::string > & getJointModelGroupNames() const
Get the available planning group names.
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
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
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
Definition utils.cpp:64
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.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
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::core::RobotModelConstPtr getSharedRobotModel(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
getSharedStateMonitor
const std::string GRASP_PLANNING_SERVICE_NAME
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
std::string append(const std::string &left, const std::string &right)
A set of options for the kinematics solver.
Specification of options to use when constructing the MoveGroupInterface class.
std::string move_group_namespace
The namespace for the move group node.
std::string robot_description
The robot description parameter name (if different from default)
moveit::core::RobotModelConstPtr robot_model
Optionally, an instance of the RobotModel to use can be also specified.
std::string group_name
The group to construct the class instance for.
The representation of a motion plan (as ROS messages)