moveit2
The MoveIt Motion Planning Framework for ROS 2.
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>
60 
61 #include <std_msgs/msg/string.hpp>
62 #include <geometry_msgs/msg/transform_stamped.hpp>
63 #include <tf2/utils.h>
64 #include <tf2_eigen/tf2_eigen.hpp>
65 #include <tf2_ros/transform_listener.h>
66 
67 namespace moveit
68 {
69 namespace planning_interface
70 {
71 const std::string MoveGroupInterface::ROBOT_DESCRIPTION =
72  "robot_description"; // name of the robot description (a param name, so it can be changed externally)
73 
74 const std::string GRASP_PLANNING_SERVICE_NAME = "plan_grasps"; // name of the service that can be used to plan grasps
75 const rclcpp::Logger LOGGER = rclcpp::get_logger("move_group_interface");
76 
77 namespace
78 {
79 enum ActiveTargetType
80 {
81  JOINT,
82  POSE,
83  POSITION,
85 };
86 }
87 
89 {
90  friend MoveGroupInterface;
91 
92 public:
93  MoveGroupInterfaceImpl(const rclcpp::Node::SharedPtr& node, const Options& opt,
94  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const rclcpp::Duration& wait_for_servers)
95  : opt_(opt), node_(node), tf_buffer_(tf_buffer)
96  {
97  // We have no control on how the passed node is getting executed. To make sure MGI is functional, we're creating
98  // our own callback group which is managed in a separate callback thread
99  callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
100  false /* don't spin with node executor */);
101  callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
102  callback_thread_ = std::thread([this]() { callback_executor_.spin(); });
103 
104  robot_model_ = opt.robot_model_ ? opt.robot_model_ : getSharedRobotModel(node_, opt.robot_description_);
105  if (!getRobotModel())
106  {
107  std::string error = "Unable to construct robot model. Please make sure all needed information is on the "
108  "parameter server.";
109  RCLCPP_FATAL_STREAM(LOGGER, error);
110  throw std::runtime_error(error);
111  }
112 
113  if (!getRobotModel()->hasJointModelGroup(opt.group_name_))
114  {
115  std::string error = "Group '" + opt.group_name_ + "' was not found.";
116  RCLCPP_FATAL_STREAM(LOGGER, error);
117  throw std::runtime_error(error);
118  }
119 
120  joint_model_group_ = getRobotModel()->getJointModelGroup(opt.group_name_);
121 
122  joint_state_target_ = std::make_shared<moveit::core::RobotState>(getRobotModel());
123  joint_state_target_->setToDefaultValues();
124  active_target_ = JOINT;
125  can_look_ = false;
126  look_around_attempts_ = 0;
127  can_replan_ = false;
128  replan_delay_ = 2.0;
129  replan_attempts_ = 1;
130  goal_joint_tolerance_ = 1e-4;
131  goal_position_tolerance_ = 1e-4; // 0.1 mm
132  goal_orientation_tolerance_ = 1e-3; // ~0.1 deg
133  allowed_planning_time_ = 5.0;
134  num_planning_attempts_ = 1;
135  node_->get_parameter_or<double>("robot_description_planning.default_velocity_scaling_factor",
136  max_velocity_scaling_factor_, 0.1);
137  node_->get_parameter_or<double>("robot_description_planning.default_acceleration_scaling_factor",
138  max_acceleration_scaling_factor_, 0.1);
139  initializing_constraints_ = false;
140 
141  if (joint_model_group_->isChain())
142  end_effector_link_ = joint_model_group_->getLinkModelNames().back();
143  pose_reference_frame_ = getRobotModel()->getModelFrame();
144  // Append the slash between two topic components
145  trajectory_event_publisher_ = node_->create_publisher<std_msgs::msg::String>(
148  1);
149  attached_object_publisher_ = node_->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
152  1);
153 
154  current_state_monitor_ = getSharedStateMonitor(node_, robot_model_, tf_buffer_);
155 
156  move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
157  node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::MOVE_ACTION), callback_group_);
158  move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
159  execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
160  node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::EXECUTE_ACTION_NAME), callback_group_);
161  execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
162 
163  query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
164  rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME),
165  rmw_qos_profile_services_default, callback_group_);
166  get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
167  rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME),
168  rmw_qos_profile_services_default, callback_group_);
169  set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
170  rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME),
171  rmw_qos_profile_services_default, callback_group_);
172 
173  cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
174  rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME),
175  rmw_qos_profile_services_default, callback_group_);
176 
177  // plan_grasps_service_ = pnode_->create_client<moveit_msgs::srv::GraspPlanning>(GRASP_PLANNING_SERVICE_NAME);
178 
179  RCLCPP_INFO_STREAM(LOGGER, "Ready to take commands for planning group " << opt.group_name_ << ".");
180  }
181 
183  {
184  if (constraints_init_thread_)
185  constraints_init_thread_->join();
186 
187  if (callback_executor_.is_spinning())
188  callback_executor_.cancel();
189 
190  if (callback_thread_.joinable())
191  callback_thread_.join();
192  }
193 
194  const std::shared_ptr<tf2_ros::Buffer>& getTF() const
195  {
196  return tf_buffer_;
197  }
198 
199  const Options& getOptions() const
200  {
201  return opt_;
202  }
203 
204  const moveit::core::RobotModelConstPtr& getRobotModel() const
205  {
206  return robot_model_;
207  }
208 
210  {
211  return joint_model_group_;
212  }
213 
214  rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const
215  {
216  return *move_action_client_;
217  }
218 
219  bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc)
220  {
221  auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
222  auto future_response = query_service_->async_send_request(req);
223 
224  if (future_response.valid())
225  {
226  const auto& response = future_response.get();
227  if (!response->planner_interfaces.empty())
228  {
229  desc = response->planner_interfaces.front();
230  return true;
231  }
232  }
233  return false;
234  }
235 
236  bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
237  {
238  auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
239  auto future_response = query_service_->async_send_request(req);
240  if (future_response.valid())
241  {
242  const auto& response = future_response.get();
243  if (!response->planner_interfaces.empty())
244  {
245  desc = response->planner_interfaces;
246  return true;
247  }
248  }
249  return false;
250  }
251 
252  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id, const std::string& group = "")
253  {
254  auto req = std::make_shared<moveit_msgs::srv::GetPlannerParams::Request>();
255  moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response;
256  req->planner_config = planner_id;
257  req->group = group;
258  std::map<std::string, std::string> result;
259 
260  auto future_response = get_params_service_->async_send_request(req);
261  if (future_response.valid())
262  {
263  response = future_response.get();
264  for (unsigned int i = 0, end = response->params.keys.size(); i < end; ++i)
265  result[response->params.keys[i]] = response->params.values[i];
266  }
267  return result;
268  }
269 
270  void setPlannerParams(const std::string& planner_id, const std::string& group,
271  const std::map<std::string, std::string>& params, bool replace = false)
272  {
273  auto req = std::make_shared<moveit_msgs::srv::SetPlannerParams::Request>();
274  req->planner_config = planner_id;
275  req->group = group;
276  req->replace = replace;
277  for (const std::pair<const std::string, std::string>& param : params)
278  {
279  req->params.keys.push_back(param.first);
280  req->params.values.push_back(param.second);
281  }
282  set_params_service_->async_send_request(req);
283  }
284 
285  std::string getDefaultPlanningPipelineId() const
286  {
287  std::string default_planning_pipeline;
288  node_->get_parameter("move_group.default_planning_pipeline", default_planning_pipeline);
289  return default_planning_pipeline;
290  }
291 
292  void setPlanningPipelineId(const std::string& pipeline_id)
293  {
294  if (pipeline_id != planning_pipeline_id_)
295  {
296  planning_pipeline_id_ = pipeline_id;
297 
298  // Reset planner_id if planning pipeline changed
299  planner_id_ = "";
300  }
301  }
302 
303  const std::string& getPlanningPipelineId() const
304  {
305  return planning_pipeline_id_;
306  }
307 
308  std::string getDefaultPlannerId(const std::string& group) const
309  {
310  // Check what planning pipeline config should be used
311  std::string pipeline_id = getDefaultPlanningPipelineId();
312  if (!planning_pipeline_id_.empty())
313  pipeline_id = planning_pipeline_id_;
314 
315  std::stringstream param_name;
316  param_name << "move_group";
317  if (!pipeline_id.empty())
318  param_name << "/planning_pipelines/" << pipeline_id;
319  if (!group.empty())
320  param_name << "." << group;
321  param_name << ".default_planner_config";
322 
323  std::string default_planner_config;
324  node_->get_parameter(param_name.str(), default_planner_config);
325  return default_planner_config;
326  }
327 
328  void setPlannerId(const std::string& planner_id)
329  {
330  planner_id_ = planner_id;
331  }
332 
333  const std::string& getPlannerId() const
334  {
335  return planner_id_;
336  }
337 
338  void setNumPlanningAttempts(unsigned int num_planning_attempts)
339  {
340  num_planning_attempts_ = num_planning_attempts;
341  }
342 
343  void setMaxVelocityScalingFactor(double value)
344  {
345  setMaxScalingFactor(max_velocity_scaling_factor_, value, "velocity_scaling_factor", 0.1);
346  }
347 
349  {
350  setMaxScalingFactor(max_acceleration_scaling_factor_, value, "acceleration_scaling_factor", 0.1);
351  }
352 
353  void setMaxScalingFactor(double& variable, const double target_value, const char* factor_name, double fallback_value)
354  {
355  if (target_value > 1.0)
356  {
357  RCLCPP_WARN(rclcpp::get_logger("move_group_interface"), "Limiting max_%s (%.2f) to 1.0.", factor_name,
358  target_value);
359  variable = 1.0;
360  }
361  else if (target_value <= 0.0)
362  {
363  node_->get_parameter_or<double>(std::string("robot_description_planning.default_") + factor_name, variable,
364  fallback_value);
365  if (target_value < 0.0)
366  {
367  RCLCPP_WARN(rclcpp::get_logger("move_group_interface"), "max_%s < 0.0! Setting to default: %.2f.", factor_name,
368  variable);
369  }
370  }
371  else
372  {
373  variable = target_value;
374  }
375  }
376 
378  {
379  return *joint_state_target_;
380  }
381 
383  {
384  return *joint_state_target_;
385  }
386 
387  void setStartState(const moveit::core::RobotState& start_state)
388  {
389  considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
390  }
391 
393  {
394  considered_start_state_.reset();
395  }
396 
397  moveit::core::RobotStatePtr getStartState()
398  {
399  if (considered_start_state_)
400  return considered_start_state_;
401  else
402  {
403  moveit::core::RobotStatePtr s;
404  getCurrentState(s);
405  return s;
406  }
407  }
408 
409  bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link,
410  const std::string& frame, bool approx)
411  {
412  const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
413  // this only works if we have an end-effector
414  if (!eef.empty())
415  {
416  // first we set the goal to be the same as the start state
417  moveit::core::RobotStatePtr c = getStartState();
418  if (c)
419  {
421  c->enforceBounds();
422  getTargetRobotState() = *c;
423  if (!getTargetRobotState().satisfiesBounds(getGoalJointTolerance()))
424  return false;
425  }
426  else
427  return false;
428 
429  // we may need to do approximate IK
431  o.return_approximate_solution = approx;
432 
433  // if no frame transforms are needed, call IK directly
434  if (frame.empty() || moveit::core::Transforms::sameFrame(frame, getRobotModel()->getModelFrame()))
435  return getTargetRobotState().setFromIK(getJointModelGroup(), eef_pose, eef, 0.0,
437  else
438  {
439  // transform the pose into the model frame, then do IK
440  bool frame_found;
441  const Eigen::Isometry3d& t = getTargetRobotState().getFrameTransform(frame, &frame_found);
442  if (frame_found)
443  {
444  Eigen::Isometry3d p;
445  tf2::fromMsg(eef_pose, p);
446  return getTargetRobotState().setFromIK(getJointModelGroup(), t * p, eef, 0.0,
448  }
449  else
450  {
451  RCLCPP_ERROR(LOGGER, "Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
452  getRobotModel()->getModelFrame().c_str());
453  return false;
454  }
455  }
456  }
457  else
458  return false;
459  }
460 
461  void setEndEffectorLink(const std::string& end_effector)
462  {
463  end_effector_link_ = end_effector;
464  }
465 
466  void clearPoseTarget(const std::string& end_effector_link)
467  {
468  pose_targets_.erase(end_effector_link);
469  }
470 
472  {
473  pose_targets_.clear();
474  }
475 
476  const std::string& getEndEffectorLink() const
477  {
478  return end_effector_link_;
479  }
480 
481  const std::string& getEndEffector() const
482  {
483  if (!end_effector_link_.empty())
484  {
485  const std::vector<std::string>& possible_eefs =
486  getRobotModel()->getJointModelGroup(opt_.group_name_)->getAttachedEndEffectorNames();
487  for (const std::string& possible_eef : possible_eefs)
488  if (getRobotModel()->getEndEffector(possible_eef)->hasLinkModel(end_effector_link_))
489  return possible_eef;
490  }
491  static std::string empty;
492  return empty;
493  }
494 
495  bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& poses, const std::string& end_effector_link)
496  {
497  const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
498  if (eef.empty())
499  {
500  RCLCPP_ERROR(LOGGER, "No end-effector to set the pose for");
501  return false;
502  }
503  else
504  {
505  pose_targets_[eef] = poses;
506  // make sure we don't store an actual stamp, since that will become stale can potentially cause tf errors
507  std::vector<geometry_msgs::msg::PoseStamped>& stored_poses = pose_targets_[eef];
508  for (geometry_msgs::msg::PoseStamped& stored_pose : stored_poses)
509  stored_pose.header.stamp = rclcpp::Time(0);
510  }
511  return true;
512  }
513 
514  bool hasPoseTarget(const std::string& end_effector_link) const
515  {
516  const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
517  return pose_targets_.find(eef) != pose_targets_.end();
518  }
519 
520  const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link) const
521  {
522  const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
523 
524  // if multiple pose targets are set, return the first one
525  std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
526  if (jt != pose_targets_.end())
527  if (!jt->second.empty())
528  return jt->second.at(0);
529 
530  // or return an error
531  static const geometry_msgs::msg::PoseStamped UNKNOWN;
532  RCLCPP_ERROR(LOGGER, "Pose for end-effector '%s' not known.", eef.c_str());
533  return UNKNOWN;
534  }
535 
536  const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link) const
537  {
538  const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
539 
540  std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
541  if (jt != pose_targets_.end())
542  if (!jt->second.empty())
543  return jt->second;
544 
545  // or return an error
546  static const std::vector<geometry_msgs::msg::PoseStamped> EMPTY;
547  RCLCPP_ERROR(LOGGER, "Poses for end-effector '%s' are not known.", eef.c_str());
548  return EMPTY;
549  }
550 
551  void setPoseReferenceFrame(const std::string& pose_reference_frame)
552  {
553  pose_reference_frame_ = pose_reference_frame;
554  }
555 
556  void setSupportSurfaceName(const std::string& support_surface)
557  {
558  support_surface_ = support_surface;
559  }
560 
561  const std::string& getPoseReferenceFrame() const
562  {
563  return pose_reference_frame_;
564  }
565 
566  void setTargetType(ActiveTargetType type)
567  {
568  active_target_ = type;
569  }
570 
571  ActiveTargetType getTargetType() const
572  {
573  return active_target_;
574  }
575 
576  bool startStateMonitor(double wait)
577  {
578  if (!current_state_monitor_)
579  {
580  RCLCPP_ERROR(LOGGER, "Unable to monitor current robot state");
581  return false;
582  }
583 
584  // if needed, start the monitor and wait up to 1 second for a full robot state
585  if (!current_state_monitor_->isActive())
586  current_state_monitor_->startStateMonitor();
587 
588  current_state_monitor_->waitForCompleteState(opt_.group_name_, wait);
589  return true;
590  }
591 
592  bool getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds = 1.0)
593  {
594  if (!current_state_monitor_)
595  {
596  RCLCPP_ERROR(LOGGER, "Unable to get current robot state");
597  return false;
598  }
599 
600  // if needed, start the monitor and wait up to 1 second for a full robot state
601  if (!current_state_monitor_->isActive())
602  current_state_monitor_->startStateMonitor();
603 
604  if (!current_state_monitor_->waitForCurrentState(node_->now(), wait_seconds))
605  {
606  RCLCPP_ERROR(LOGGER, "Failed to fetch current robot state");
607  return false;
608  }
609 
610  current_state = current_state_monitor_->getCurrentState();
611  return true;
612  }
613 
615  // std::vector<moveit_msgs::msg::PlaceLocation>
616  // posesToPlaceLocations(const std::vector<geometry_msgs::msg::PoseStamped>& poses) const
617  // {
618  // std::vector<moveit_msgs::msg::PlaceLocation> locations;
619  // for (const geometry_msgs::msg::PoseStamped& pose : poses)
620  // {
621  // moveit_msgs::msg::PlaceLocation location;
622  // location.pre_place_approach.direction.vector.z = -1.0;
623  // location.post_place_retreat.direction.vector.x = -1.0;
624  // location.pre_place_approach.direction.header.frame_id = getRobotModel()->getModelFrame();
625  // location.post_place_retreat.direction.header.frame_id = end_effector_link_;
626  //
627  // location.pre_place_approach.min_distance = 0.1;
628  // location.pre_place_approach.desired_distance = 0.2;
629  // location.post_place_retreat.min_distance = 0.0;
630  // location.post_place_retreat.desired_distance = 0.2;
631  // // location.post_place_posture is filled by the pick&place lib with the getDetachPosture from the AttachedBody
632  //
633  // location.place_pose = pose;
634  // locations.push_back(location);
635  // }
636  // RCLCPP_DEBUG(LOGGER, "Move group interface has %u place locations",
637  // (unsigned int)locations.size());
638  // return locations;
639  // }
640 
641  // moveit::core::MoveItErrorCode place(const moveit_msgs::action::Place::Goal& goal)
642  // {
643  // if (!place_action_client_ || !place_action_client_->action_server_is_ready())
644  // {
645  // RCLCPP_ERROR_STREAM(LOGGER, "Place action client not found/not ready");
646  // return moveit::core::MoveItErrorCode::FAILURE;
647  // }
648  //
649  // int64_t timeout = 3.0;
650  // auto future = place_action_client_->async_send_goal(goal);
651  // if (rclcpp::spin_until_future_complete(node_, future, std::chrono::seconds(timeout)) !=
652  // rclcpp::FutureReturnCode::SUCCESS)
653  // {
654  // RCLCPP_ERROR_STREAM(LOGGER, "Place action timeout reached");
655  // return moveit::core::MoveItErrorCode::FAILURE;
656  // }
657  // return moveit::core::MoveItErrorCode::SUCCESS;
658  // }
659 
660  // moveit::core::MoveItErrorCode pick(const moveit_msgs::action::Pickup::Goal& goal)
661  // {
662  // if (!pick_action_client_ || !pick_action_client_->action_server_is_ready())
663  // {
664  // RCLCPP_ERROR_STREAM(LOGGER, "Pick action client not found/not ready");
665  // return moveit::core::MoveItErrorCode::FAILURE;
666  // }
667  //
668  // int64_t timeout = 3.0;
669  // auto future = pick_action_client_->async_send_goal(goal);
670  // if (rclcpp::spin_until_future_complete(node_, future, std::chrono::seconds(timeout)) !=
671  // rclcpp::FutureReturnCode::SUCCESS)
672  // {
673  // RCLCPP_ERROR_STREAM(LOGGER, "Pick action timeout reached");
674  // return moveit::core::MoveItErrorCode::FAILURE;
675  // }
676  // return moveit::core::MoveItErrorCode::SUCCESS;
677  // }
678 
679  // moveit::core::MoveItErrorCode planGraspsAndPick(const std::string& object, bool plan_only = false)
680  // {
681  // if (object.empty())
682  // {
683  // return planGraspsAndPick(moveit_msgs::msg::CollisionObject());
684  // }
685  //
686  // PlanningSceneInterface psi;
687  // std::map<std::string, moveit_msgs::msg::CollisionObject> objects =
688  // psi.getObjects(std::vector<std::string>(1, object));
689  //
690  // if (objects.empty())
691  // {
692  // RCLCPP_ERROR_STREAM(LOGGER, "Asked for grasps for the object '"
693  // << object << "', but the object could not be found");
694  // return moveit::core::MoveItErrorCode::INVALID_OBJECT_NAME;
695  // }
696  //
697  // return planGraspsAndPick(objects[object], plan_only);
698  // }
699 
700  // moveit::core::MoveItErrorCode planGraspsAndPick(const moveit_msgs::msg::CollisionObject& object, bool plan_only = false)
701  // {
702  // if (!plan_grasps_service_)
703  // {
704  // RCLCPP_ERROR_STREAM(LOGGER, "Grasp planning service '"
705  // << GRASP_PLANNING_SERVICE_NAME
706  // << "' is not available."
707  // " This has to be implemented and started separately.");
708  // return moveit::core::MoveItErrorCode::FAILURE;
709  // }
710  //
711  // auto request = std::make_shared<moveit_msgs::srv::GraspPlanning::Request>();
712  // moveit_msgs::srv::GraspPlanning::Response::SharedPtr response;
713  //
714  // request->group_name = opt_.group_name_;
715  // request->target = object;
716  // request->support_surfaces.push_back(support_surface_);
717  //
718  // RCLCPP_DEBUG(LOGGER, "Calling grasp planner...");
719  //
720  // auto res = plan_grasps_service_->async_send_request(request);
721  // if (rclcpp::spin_until_future_complete(node_, res) !=
722  // rclcpp::FutureReturnCode::SUCCESS)
723  // {
724  // RCLCPP_ERROR(LOGGER, "Grasp planning failed. Unable to pick.");
725  // return moveit::core::MoveItErrorCode::FAILURE;
726  // }
727  // response = res.get();
728  // if (response->error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
729  // {
730  // RCLCPP_ERROR(LOGGER, "Grasp planning failed. Unable to pick.");
731  // return moveit::core::MoveItErrorCode::FAILURE;
732  // }
733  // return pick(constructPickupGoal(object.id, std::move(response->grasps), plan_only));
734  // }
735 
737  {
738  if (!move_action_client_ || !move_action_client_->action_server_is_ready())
739  {
740  RCLCPP_INFO_STREAM(LOGGER, "MoveGroup action client/server not ready");
741  return moveit::core::MoveItErrorCode::FAILURE;
742  }
743  RCLCPP_INFO_STREAM(LOGGER, "MoveGroup action client/server ready");
744 
745  moveit_msgs::action::MoveGroup::Goal goal;
746  constructGoal(goal);
747  goal.planning_options.plan_only = true;
748  goal.planning_options.look_around = false;
749  goal.planning_options.replan = false;
750  goal.planning_options.planning_scene_diff.is_diff = true;
751  goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
752 
753  bool done = false;
754  rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
755  std::shared_ptr<moveit_msgs::action::MoveGroup::Result> res;
756  auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
757 
758  send_goal_opts.goal_response_callback =
759  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
760  if (!goal_handle)
761  {
762  done = true;
763  RCLCPP_INFO(LOGGER, "Planning request rejected");
764  }
765  else
766  RCLCPP_INFO(LOGGER, "Planning request accepted");
767  };
768  send_goal_opts.result_callback =
769  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
770  res = result.result;
771  code = result.code;
772  done = true;
773 
774  switch (result.code)
775  {
776  case rclcpp_action::ResultCode::SUCCEEDED:
777  RCLCPP_INFO(LOGGER, "Planning request complete!");
778  break;
779  case rclcpp_action::ResultCode::ABORTED:
780  RCLCPP_INFO(LOGGER, "Planning request aborted");
781  return;
782  case rclcpp_action::ResultCode::CANCELED:
783  RCLCPP_INFO(LOGGER, "Planning request canceled");
784  return;
785  default:
786  RCLCPP_INFO(LOGGER, "Planning request unknown result code");
787  return;
788  }
789  };
790 
791  auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
792 
793  // wait until send_goal_opts.result_callback is called
794  while (!done)
795  {
796  std::this_thread::sleep_for(std::chrono::milliseconds(1));
797  }
798 
799  if (code != rclcpp_action::ResultCode::SUCCEEDED)
800  {
801  RCLCPP_ERROR_STREAM(LOGGER, "MoveGroupInterface::plan() failed or timeout reached");
802  return res->error_code;
803  }
804 
805  plan.trajectory_ = res->planned_trajectory;
806  plan.start_state_ = res->trajectory_start;
807  plan.planning_time_ = res->planning_time;
808  RCLCPP_INFO(LOGGER, "time taken to generate plan: %g seconds", plan.planning_time_);
809 
810  return res->error_code;
811  }
812 
814  {
815  if (!move_action_client_ || !move_action_client_->action_server_is_ready())
816  {
817  RCLCPP_INFO_STREAM(LOGGER, "MoveGroup action client/server not ready");
818  return moveit::core::MoveItErrorCode::FAILURE;
819  }
820 
821  moveit_msgs::action::MoveGroup::Goal goal;
822  constructGoal(goal);
823  goal.planning_options.plan_only = false;
824  goal.planning_options.look_around = can_look_;
825  goal.planning_options.replan = can_replan_;
826  goal.planning_options.replan_delay = replan_delay_;
827  goal.planning_options.planning_scene_diff.is_diff = true;
828  goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
829 
830  bool done = false;
831  rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
832  std::shared_ptr<moveit_msgs::action::MoveGroup_Result> res;
833  auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
834 
835  send_goal_opts.goal_response_callback =
836  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
837  if (!goal_handle)
838  {
839  done = true;
840  RCLCPP_INFO(LOGGER, "Plan and Execute request rejected");
841  }
842  else
843  RCLCPP_INFO(LOGGER, "Plan and Execute request accepted");
844  };
845  send_goal_opts.result_callback =
846  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
847  res = result.result;
848  code = result.code;
849  done = true;
850 
851  switch (result.code)
852  {
853  case rclcpp_action::ResultCode::SUCCEEDED:
854  RCLCPP_INFO(LOGGER, "Plan and Execute request complete!");
855  break;
856  case rclcpp_action::ResultCode::ABORTED:
857  RCLCPP_INFO(LOGGER, "Plan and Execute request aborted");
858  return;
859  case rclcpp_action::ResultCode::CANCELED:
860  RCLCPP_INFO(LOGGER, "Plan and Execute request canceled");
861  return;
862  default:
863  RCLCPP_INFO(LOGGER, "Plan and Execute request unknown result code");
864  return;
865  }
866  };
867  auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
868  if (!wait)
869  return moveit::core::MoveItErrorCode::SUCCESS;
870 
871  // wait until send_goal_opts.result_callback is called
872  while (!done)
873  {
874  std::this_thread::sleep_for(std::chrono::milliseconds(1));
875  }
876 
877  if (code != rclcpp_action::ResultCode::SUCCEEDED)
878  {
879  RCLCPP_ERROR_STREAM(LOGGER, "MoveGroupInterface::move() failed or timeout reached");
880  }
881  return res->error_code;
882  }
883 
884  moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory, bool wait)
885  {
886  if (!execute_action_client_ || !execute_action_client_->action_server_is_ready())
887  {
888  RCLCPP_INFO_STREAM(LOGGER, "execute_action_client_ client/server not ready");
889  return moveit::core::MoveItErrorCode::FAILURE;
890  }
891 
892  bool done = false;
893  rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
894  std::shared_ptr<moveit_msgs::action::ExecuteTrajectory_Result> res;
895  auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();
896 
897  send_goal_opts.goal_response_callback =
898  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr& goal_handle) {
899  if (!goal_handle)
900  {
901  done = true;
902  RCLCPP_INFO(LOGGER, "Execute request rejected");
903  }
904  else
905  RCLCPP_INFO(LOGGER, "Execute request accepted");
906  };
907  send_goal_opts.result_callback =
908  [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::WrappedResult& result) {
909  res = result.result;
910  code = result.code;
911  done = true;
912 
913  switch (result.code)
914  {
915  case rclcpp_action::ResultCode::SUCCEEDED:
916  RCLCPP_INFO(LOGGER, "Execute request success!");
917  break;
918  case rclcpp_action::ResultCode::ABORTED:
919  RCLCPP_INFO(LOGGER, "Execute request aborted");
920  return;
921  case rclcpp_action::ResultCode::CANCELED:
922  RCLCPP_INFO(LOGGER, "Execute request canceled");
923  return;
924  default:
925  RCLCPP_INFO(LOGGER, "Execute request unknown result code");
926  return;
927  }
928  };
929 
930  moveit_msgs::action::ExecuteTrajectory::Goal goal;
931  goal.trajectory = trajectory;
932 
933  auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts);
934  if (!wait)
935  return moveit::core::MoveItErrorCode::SUCCESS;
936 
937  // wait until send_goal_opts.result_callback is called
938  while (!done)
939  {
940  std::this_thread::sleep_for(std::chrono::milliseconds(1));
941  }
942 
943  if (code != rclcpp_action::ResultCode::SUCCEEDED)
944  {
945  RCLCPP_ERROR_STREAM(LOGGER, "MoveGroupInterface::execute() failed or timeout reached");
946  }
947  return res->error_code;
948  }
949 
950  double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double step,
951  double jump_threshold, moveit_msgs::msg::RobotTrajectory& msg,
952  const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions,
953  moveit_msgs::msg::MoveItErrorCodes& error_code)
954  {
955  auto req = std::make_shared<moveit_msgs::srv::GetCartesianPath::Request>();
956  moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response;
957 
958  if (considered_start_state_)
959  moveit::core::robotStateToRobotStateMsg(*considered_start_state_, req->start_state);
960  else
961  req->start_state.is_diff = true;
962 
963  req->group_name = opt_.group_name_;
964  req->header.frame_id = getPoseReferenceFrame();
965  req->header.stamp = getClock()->now();
966  req->waypoints = waypoints;
967  req->max_step = step;
968  req->jump_threshold = jump_threshold;
969  req->path_constraints = path_constraints;
970  req->avoid_collisions = avoid_collisions;
971  req->link_name = getEndEffectorLink();
972 
973  auto future_response = cartesian_path_service_->async_send_request(req);
974  if (future_response.valid())
975  {
976  response = future_response.get();
977  error_code = response->error_code;
978  if (response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
979  {
980  msg = response->solution;
981  return response->fraction;
982  }
983  else
984  return -1.0;
985  }
986  else
987  {
988  error_code.val = error_code.FAILURE;
989  return -1.0;
990  }
991  }
992 
993  void stop()
994  {
995  if (trajectory_event_publisher_)
996  {
997  std_msgs::msg::String event;
998  event.data = "stop";
999  trajectory_event_publisher_->publish(event);
1000  }
1001  }
1002 
1003  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links)
1004  {
1005  std::string l = link.empty() ? getEndEffectorLink() : link;
1006  if (l.empty())
1007  {
1008  const std::vector<std::string>& links = joint_model_group_->getLinkModelNames();
1009  if (!links.empty())
1010  l = links[0];
1011  }
1012  if (l.empty())
1013  {
1014  RCLCPP_ERROR(LOGGER, "No known link to attach object '%s' to", object.c_str());
1015  return false;
1016  }
1017  moveit_msgs::msg::AttachedCollisionObject aco;
1018  aco.object.id = object;
1019  aco.link_name.swap(l);
1020  if (touch_links.empty())
1021  aco.touch_links.push_back(aco.link_name);
1022  else
1023  aco.touch_links = touch_links;
1024  aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
1025  attached_object_publisher_->publish(aco);
1026  return true;
1027  }
1028 
1029  bool detachObject(const std::string& name)
1030  {
1031  moveit_msgs::msg::AttachedCollisionObject aco;
1032  // if name is a link
1033  if (!name.empty() && joint_model_group_->hasLinkModel(name))
1034  aco.link_name = name;
1035  else
1036  aco.object.id = name;
1037  aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
1038  if (aco.link_name.empty() && aco.object.id.empty())
1039  {
1040  // we only want to detach objects for this group
1041  const std::vector<std::string>& lnames = joint_model_group_->getLinkModelNames();
1042  for (const std::string& lname : lnames)
1043  {
1044  aco.link_name = lname;
1045  attached_object_publisher_->publish(aco);
1046  }
1047  }
1048  else
1049  {
1050  attached_object_publisher_->publish(aco);
1051  }
1052  return true;
1053  }
1054 
1056  {
1057  return goal_position_tolerance_;
1058  }
1059 
1061  {
1062  return goal_orientation_tolerance_;
1063  }
1064 
1065  double getGoalJointTolerance() const
1066  {
1067  return goal_joint_tolerance_;
1068  }
1069 
1070  void setGoalJointTolerance(double tolerance)
1071  {
1072  goal_joint_tolerance_ = tolerance;
1073  }
1074 
1075  void setGoalPositionTolerance(double tolerance)
1076  {
1077  goal_position_tolerance_ = tolerance;
1078  }
1079 
1080  void setGoalOrientationTolerance(double tolerance)
1081  {
1082  goal_orientation_tolerance_ = tolerance;
1083  }
1084 
1085  void setPlanningTime(double seconds)
1086  {
1087  if (seconds > 0.0)
1088  allowed_planning_time_ = seconds;
1089  }
1090 
1091  double getPlanningTime() const
1092  {
1093  return allowed_planning_time_;
1094  }
1095 
1097  {
1098  request.group_name = opt_.group_name_;
1099  request.num_planning_attempts = num_planning_attempts_;
1100  request.max_velocity_scaling_factor = max_velocity_scaling_factor_;
1101  request.max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
1102  request.allowed_planning_time = allowed_planning_time_;
1103  request.pipeline_id = planning_pipeline_id_;
1104  request.planner_id = planner_id_;
1105  request.workspace_parameters = workspace_parameters_;
1106 
1107  if (considered_start_state_)
1108  moveit::core::robotStateToRobotStateMsg(*considered_start_state_, request.start_state);
1109  else
1110  request.start_state.is_diff = true;
1111 
1112  if (active_target_ == JOINT)
1113  {
1114  request.goal_constraints.resize(1);
1115  request.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(
1116  getTargetRobotState(), joint_model_group_, goal_joint_tolerance_);
1117  }
1118  else if (active_target_ == POSE || active_target_ == POSITION || active_target_ == ORIENTATION)
1119  {
1120  // find out how many goals are specified
1121  std::size_t goal_count = 0;
1122  for (const auto& pose_target : pose_targets_)
1123  goal_count = std::max(goal_count, pose_target.second.size());
1124 
1125  // start filling the goals;
1126  // each end effector has a number of possible poses (K) as valid goals
1127  // but there could be multiple end effectors specified, so we want each end effector
1128  // to reach the goal that corresponds to the goals of the other end effectors
1129  request.goal_constraints.resize(goal_count);
1130 
1131  for (const auto& pose_target : pose_targets_)
1132  {
1133  for (std::size_t i = 0; i < pose_target.second.size(); ++i)
1134  {
1135  moveit_msgs::msg::Constraints c = kinematic_constraints::constructGoalConstraints(
1136  pose_target.first, pose_target.second[i], goal_position_tolerance_, goal_orientation_tolerance_);
1137  if (active_target_ == ORIENTATION)
1138  c.position_constraints.clear();
1139  if (active_target_ == POSITION)
1140  c.orientation_constraints.clear();
1141  request.goal_constraints[i] = kinematic_constraints::mergeConstraints(request.goal_constraints[i], c);
1142  }
1143  }
1144  }
1145  else
1146  RCLCPP_ERROR(LOGGER, "Unable to construct MotionPlanRequest representation");
1147 
1148  if (path_constraints_)
1149  request.path_constraints = *path_constraints_;
1150  if (trajectory_constraints_)
1151  request.trajectory_constraints = *trajectory_constraints_;
1152  }
1153 
1154  void constructGoal(moveit_msgs::action::MoveGroup::Goal& goal) const
1155  {
1156  constructMotionPlanRequest(goal.request);
1157  }
1158 
1159  // moveit_msgs::action::Pickup::Goal constructPickupGoal(const std::string& object,
1160  // std::vector<moveit_msgs::msg::Grasp>&& grasps,
1161  // bool plan_only = false) const
1162  // {
1163  // moveit_msgs::action::Pickup::Goal goal;
1164  // goal.target_name = object;
1165  // goal.group_name = opt_.group_name_;
1166  // goal.end_effector = getEndEffector();
1167  // goal.support_surface_name = support_surface_;
1168  // goal.possible_grasps = std::move(grasps);
1169  // if (!support_surface_.empty())
1170  // goal.allow_gripper_support_collision = true;
1171  //
1172  // if (path_constraints_)
1173  // goal.path_constraints = *path_constraints_;
1174  //
1175  // goal.planner_id = planner_id_;
1176  // goal.allowed_planning_time = allowed_planning_time_;
1177  //
1178  // goal.planning_options.plan_only = plan_only;
1179  // goal.planning_options.look_around = can_look_;
1180  // goal.planning_options.replan = can_replan_;
1181  // goal.planning_options.replan_delay = replan_delay_;
1182  // goal.planning_options.planning_scene_diff.is_diff = true;
1183  // goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
1184  // return goal;
1185  // }
1186 
1187  // moveit_msgs::action::Place::Goal constructPlaceGoal(const std::string& object,
1188  // std::vector<moveit_msgs::msg::PlaceLocation>&& locations,
1189  // bool plan_only = false) const
1190  // {
1191  // moveit_msgs::action::Place::Goal goal;
1192  // goal.group_name = opt_.group_name_;
1193  // goal.attached_object_name = object;
1194  // goal.support_surface_name = support_surface_;
1195  // goal.place_locations = std::move(locations);
1196  // if (!support_surface_.empty())
1197  // goal.allow_gripper_support_collision = true;
1198  //
1199  // if (path_constraints_)
1200  // goal.path_constraints = *path_constraints_;
1201  //
1202  // goal.planner_id = planner_id_;
1203  // goal.allowed_planning_time = allowed_planning_time_;
1204  //
1205  // goal.planning_options.plan_only = plan_only;
1206  // goal.planning_options.look_around = can_look_;
1207  // goal.planning_options.replan = can_replan_;
1208  // goal.planning_options.replan_delay = replan_delay_;
1209  // goal.planning_options.planning_scene_diff.is_diff = true;
1210  // goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
1211  // return goal;
1212  // }
1213 
1214  void setPathConstraints(const moveit_msgs::msg::Constraints& constraint)
1215  {
1216  path_constraints_ = std::make_unique<moveit_msgs::msg::Constraints>(constraint);
1217  }
1218 
1219  bool setPathConstraints(const std::string& constraint)
1220  {
1221  if (constraints_storage_)
1222  {
1224  if (constraints_storage_->getConstraints(msg_m, constraint, robot_model_->getName(), opt_.group_name_))
1225  {
1226  path_constraints_ =
1227  std::make_unique<moveit_msgs::msg::Constraints>(static_cast<moveit_msgs::msg::Constraints>(*msg_m));
1228  return true;
1229  }
1230  else
1231  return false;
1232  }
1233  else
1234  return false;
1235  }
1236 
1238  {
1239  path_constraints_.reset();
1240  }
1241 
1242  void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint)
1243  {
1244  trajectory_constraints_ = std::make_unique<moveit_msgs::msg::TrajectoryConstraints>(constraint);
1245  }
1246 
1248  {
1249  trajectory_constraints_.reset();
1250  }
1251 
1252  std::vector<std::string> getKnownConstraints() const
1253  {
1254  while (initializing_constraints_)
1255  {
1256  std::chrono::duration<double> d(0.01);
1257  rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(d), rclcpp::Context::SharedPtr(nullptr));
1258  }
1259 
1260  std::vector<std::string> c;
1261  if (constraints_storage_)
1262  constraints_storage_->getKnownConstraints(c, robot_model_->getName(), opt_.group_name_);
1263 
1264  return c;
1265  }
1266 
1267  moveit_msgs::msg::Constraints getPathConstraints() const
1268  {
1269  if (path_constraints_)
1270  return *path_constraints_;
1271  else
1272  return moveit_msgs::msg::Constraints();
1273  }
1274 
1275  moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
1276  {
1277  if (trajectory_constraints_)
1278  return *trajectory_constraints_;
1279  else
1280  return moveit_msgs::msg::TrajectoryConstraints();
1281  }
1282 
1283  void initializeConstraintsStorage(const std::string& host, unsigned int port)
1284  {
1285  initializing_constraints_ = true;
1286  if (constraints_init_thread_)
1287  constraints_init_thread_->join();
1288  constraints_init_thread_ =
1289  std::make_unique<std::thread>([this, host, port] { initializeConstraintsStorageThread(host, port); });
1290  }
1291 
1292  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
1293  {
1294  workspace_parameters_.header.frame_id = getRobotModel()->getModelFrame();
1295  workspace_parameters_.header.stamp = getClock()->now();
1296  workspace_parameters_.min_corner.x = minx;
1297  workspace_parameters_.min_corner.y = miny;
1298  workspace_parameters_.min_corner.z = minz;
1299  workspace_parameters_.max_corner.x = maxx;
1300  workspace_parameters_.max_corner.y = maxy;
1301  workspace_parameters_.max_corner.z = maxz;
1302  }
1303 
1304  rclcpp::Clock::SharedPtr getClock()
1305  {
1306  return node_->get_clock();
1307  }
1308 
1309 private:
1310  void initializeConstraintsStorageThread(const std::string& host, unsigned int port)
1311  {
1312  // Set up db
1313  try
1314  {
1315  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node_);
1316  conn->setParams(host, port);
1317  if (conn->connect())
1318  {
1319  constraints_storage_ = std::make_unique<moveit_warehouse::ConstraintsStorage>(conn);
1320  }
1321  }
1322  catch (std::exception& ex)
1323  {
1324  RCLCPP_ERROR(LOGGER, "%s", ex.what());
1325  }
1326  initializing_constraints_ = false;
1327  }
1328 
1329  Options opt_;
1330  rclcpp::Node::SharedPtr node_;
1331  rclcpp::CallbackGroup::SharedPtr callback_group_;
1332  rclcpp::executors::SingleThreadedExecutor callback_executor_;
1333  std::thread callback_thread_;
1334  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
1335  moveit::core::RobotModelConstPtr robot_model_;
1336  planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
1337 
1338  std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::MoveGroup>> move_action_client_;
1339  // std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::Pickup>> pick_action_client_;
1340  // std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::Place>> place_action_client_;
1341  std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>> execute_action_client_;
1342 
1343  // general planning params
1344  moveit::core::RobotStatePtr considered_start_state_;
1345  moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
1346  double allowed_planning_time_;
1347  std::string planning_pipeline_id_;
1348  std::string planner_id_;
1349  unsigned int num_planning_attempts_;
1350  double max_velocity_scaling_factor_;
1351  double max_acceleration_scaling_factor_;
1352  double goal_joint_tolerance_;
1353  double goal_position_tolerance_;
1354  double goal_orientation_tolerance_;
1355  bool can_look_;
1356  int32_t look_around_attempts_;
1357  bool can_replan_;
1358  int32_t replan_attempts_;
1359  double replan_delay_;
1360 
1361  // joint state goal
1362  moveit::core::RobotStatePtr joint_state_target_;
1363  const moveit::core::JointModelGroup* joint_model_group_;
1364 
1365  // pose goal;
1366  // for each link we have a set of possible goal locations;
1367  std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>> pose_targets_;
1368 
1369  // common properties for goals
1370  ActiveTargetType active_target_;
1371  std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
1372  std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;
1373  std::string end_effector_link_;
1374  std::string pose_reference_frame_;
1375  std::string support_surface_;
1376 
1377  // ROS communication
1378  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr trajectory_event_publisher_;
1379  rclcpp::Publisher<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_object_publisher_;
1380  rclcpp::Client<moveit_msgs::srv::QueryPlannerInterfaces>::SharedPtr query_service_;
1381  rclcpp::Client<moveit_msgs::srv::GetPlannerParams>::SharedPtr get_params_service_;
1382  rclcpp::Client<moveit_msgs::srv::SetPlannerParams>::SharedPtr set_params_service_;
1383  rclcpp::Client<moveit_msgs::srv::GetCartesianPath>::SharedPtr cartesian_path_service_;
1384  // rclcpp::Client<moveit_msgs::srv::GraspPlanning>::SharedPtr plan_grasps_service_;
1385  std::unique_ptr<moveit_warehouse::ConstraintsStorage> constraints_storage_;
1386  std::unique_ptr<std::thread> constraints_init_thread_;
1387  bool initializing_constraints_;
1388 };
1389 
1390 MoveGroupInterface::MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group_name,
1391  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1392  const rclcpp::Duration& wait_for_servers)
1393 {
1394  if (!rclcpp::ok())
1395  throw std::runtime_error("ROS does not seem to be running");
1396  impl_ =
1397  new MoveGroupInterfaceImpl(node, Options(group_name), tf_buffer ? tf_buffer : getSharedTF(), wait_for_servers);
1398 }
1399 
1400 MoveGroupInterface::MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
1401  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1402  const rclcpp::Duration& wait_for_servers)
1403 {
1404  impl_ = new MoveGroupInterfaceImpl(node, opt, tf_buffer ? tf_buffer : getSharedTF(), wait_for_servers);
1405 }
1406 
1408 {
1409  delete impl_;
1410 }
1411 
1413  : remembered_joint_values_(std::move(other.remembered_joint_values_)), impl_(other.impl_)
1414 {
1415  other.impl_ = nullptr;
1416 }
1417 
1419 {
1420  if (this != &other)
1421  {
1422  delete impl_;
1423  impl_ = other.impl_;
1424  remembered_joint_values_ = std::move(other.remembered_joint_values_);
1425  other.impl_ = nullptr;
1426  }
1427 
1428  return *this;
1429 }
1430 
1431 const std::string& MoveGroupInterface::getName() const
1432 {
1433  return impl_->getOptions().group_name_;
1434 }
1435 
1436 const std::vector<std::string>& MoveGroupInterface::getNamedTargets() const
1437 {
1438  // The pointer returned by getJointModelGroup is guaranteed by the class
1439  // constructor to always be non-null
1440  return impl_->getJointModelGroup()->getDefaultStateNames();
1441 }
1442 
1443 moveit::core::RobotModelConstPtr MoveGroupInterface::getRobotModel() const
1444 {
1445  return impl_->getRobotModel();
1446 }
1447 
1448 bool MoveGroupInterface::getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const
1449 {
1450  return impl_->getInterfaceDescription(desc);
1451 }
1452 
1453 bool MoveGroupInterface::getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const
1454 {
1455  return impl_->getInterfaceDescriptions(desc);
1456 }
1457 
1458 std::map<std::string, std::string> MoveGroupInterface::getPlannerParams(const std::string& planner_id,
1459  const std::string& group) const
1460 {
1461  return impl_->getPlannerParams(planner_id, group);
1462 }
1463 
1464 void MoveGroupInterface::setPlannerParams(const std::string& planner_id, const std::string& group,
1465  const std::map<std::string, std::string>& params, bool replace)
1466 {
1467  impl_->setPlannerParams(planner_id, group, params, replace);
1468 }
1469 
1471 {
1472  return impl_->getDefaultPlanningPipelineId();
1473 }
1474 
1475 void MoveGroupInterface::setPlanningPipelineId(const std::string& pipeline_id)
1476 {
1477  impl_->setPlanningPipelineId(pipeline_id);
1478 }
1479 
1481 {
1482  return impl_->getPlanningPipelineId();
1483 }
1484 
1485 std::string MoveGroupInterface::getDefaultPlannerId(const std::string& group) const
1486 {
1487  return impl_->getDefaultPlannerId(group);
1488 }
1489 
1490 void MoveGroupInterface::setPlannerId(const std::string& planner_id)
1491 {
1492  impl_->setPlannerId(planner_id);
1493 }
1494 
1495 const std::string& MoveGroupInterface::getPlannerId() const
1496 {
1497  return impl_->getPlannerId();
1498 }
1499 
1500 void MoveGroupInterface::setNumPlanningAttempts(unsigned int num_planning_attempts)
1501 {
1502  impl_->setNumPlanningAttempts(num_planning_attempts);
1503 }
1504 
1505 void MoveGroupInterface::setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
1506 {
1507  impl_->setMaxVelocityScalingFactor(max_velocity_scaling_factor);
1508 }
1509 
1510 void MoveGroupInterface::setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
1511 {
1512  impl_->setMaxAccelerationScalingFactor(max_acceleration_scaling_factor);
1513 }
1514 
1516 {
1517  return impl_->move(false);
1518 }
1519 
1520 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& MoveGroupInterface::getMoveGroupClient() const
1521 {
1522  return impl_->getMoveGroupClient();
1523 }
1524 
1526 {
1527  return impl_->move(true);
1528 }
1529 
1531 {
1532  return impl_->execute(plan.trajectory_, false);
1533 }
1534 
1535 moveit::core::MoveItErrorCode MoveGroupInterface::asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory)
1536 {
1537  return impl_->execute(trajectory, false);
1538 }
1539 
1541 {
1542  return impl_->execute(plan.trajectory_, true);
1543 }
1544 
1545 moveit::core::MoveItErrorCode MoveGroupInterface::execute(const moveit_msgs::msg::RobotTrajectory& trajectory)
1546 {
1547  return impl_->execute(trajectory, true);
1548 }
1549 
1551 {
1552  return impl_->plan(plan);
1553 }
1554 
1555 // moveit_msgs::action::Pickup::Goal MoveGroupInterface::constructPickupGoal(const std::string& object,
1556 // std::vector<moveit_msgs::msg::Grasp> grasps,
1557 // bool plan_only = false) const
1558 //{
1559 // return impl_->constructPickupGoal(object, std::move(grasps), plan_only);
1560 //}
1561 //
1562 // moveit_msgs::action::Place::Goal MoveGroupInterface::constructPlaceGoal(
1563 // const std::string& object, std::vector<moveit_msgs::msg::PlaceLocation> locations, bool plan_only = false) const
1564 //{
1565 // return impl_->constructPlaceGoal(object, std::move(locations), plan_only);
1566 //}
1567 //
1568 // std::vector<moveit_msgs::msg::PlaceLocation>
1569 // MoveGroupInterface::posesToPlaceLocations(const std::vector<geometry_msgs::msg::PoseStamped>& poses) const
1570 //{
1571 // return impl_->posesToPlaceLocations(poses);
1572 //}
1573 //
1574 // moveit::core::MoveItErrorCode MoveGroupInterface::pick(const moveit_msgs::action::Pickup::Goal& goal)
1575 //{
1576 // return impl_->pick(goal);
1577 //}
1578 //
1579 // moveit::core::MoveItErrorCode MoveGroupInterface::planGraspsAndPick(const std::string& object, bool plan_only)
1580 //{
1581 // return impl_->planGraspsAndPick(object, plan_only);
1582 //}
1583 //
1584 // moveit::core::MoveItErrorCode MoveGroupInterface::planGraspsAndPick(const moveit_msgs::msg::CollisionObject& object,
1585 // bool plan_only)
1586 //{
1587 // return impl_->planGraspsAndPick(object, plan_only);
1588 //}
1589 //
1590 // moveit::core::MoveItErrorCode MoveGroupInterface::place(const moveit_msgs::action::Place::Goal& goal)
1591 //{
1592 // return impl_->place(goal);
1593 //}
1594 
1595 double MoveGroupInterface::computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
1596  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
1597  bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1598 {
1599  moveit_msgs::msg::Constraints path_constraints_tmp;
1600  return computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, path_constraints_tmp, avoid_collisions,
1601  error_code);
1602 }
1603 
1604 double MoveGroupInterface::computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
1605  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
1606  const moveit_msgs::msg::Constraints& path_constraints,
1607  bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1608 {
1609  if (error_code)
1610  {
1611  return impl_->computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, path_constraints,
1612  avoid_collisions, *error_code);
1613  }
1614  else
1615  {
1616  moveit_msgs::msg::MoveItErrorCodes error_code_tmp;
1617  return impl_->computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, path_constraints,
1618  avoid_collisions, error_code_tmp);
1619  }
1620 }
1621 
1623 {
1624  impl_->stop();
1625 }
1626 
1627 void MoveGroupInterface::setStartState(const moveit_msgs::msg::RobotState& start_state)
1628 {
1629  moveit::core::RobotStatePtr rs;
1630  if (start_state.is_diff)
1631  impl_->getCurrentState(rs);
1632  else
1633  {
1634  rs = std::make_shared<moveit::core::RobotState>(getRobotModel());
1635  rs->setToDefaultValues(); // initialize robot state values for conversion
1636  }
1637  moveit::core::robotStateMsgToRobotState(start_state, *rs);
1638  setStartState(*rs);
1639 }
1640 
1642 {
1643  impl_->setStartState(start_state);
1644 }
1645 
1647 {
1648  impl_->setStartStateToCurrentState();
1649 }
1650 
1652 {
1654  impl_->setTargetType(JOINT);
1655 }
1656 
1657 const std::vector<std::string>& MoveGroupInterface::getJointNames() const
1658 {
1659  return impl_->getJointModelGroup()->getVariableNames();
1660 }
1661 
1662 const std::vector<std::string>& MoveGroupInterface::getLinkNames() const
1663 {
1664  return impl_->getJointModelGroup()->getLinkModelNames();
1665 }
1666 
1667 std::map<std::string, double> MoveGroupInterface::getNamedTargetValues(const std::string& name) const
1668 {
1669  std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1670  std::map<std::string, double> positions;
1671 
1672  if (it != remembered_joint_values_.cend())
1673  {
1674  std::vector<std::string> names = impl_->getJointModelGroup()->getVariableNames();
1675  for (size_t x = 0; x < names.size(); ++x)
1676  {
1677  positions[names[x]] = it->second[x];
1678  }
1679  }
1680  else
1681  {
1682  impl_->getJointModelGroup()->getVariableDefaultPositions(name, positions);
1683  }
1684  return positions;
1685 }
1686 
1688 {
1689  std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1690  if (it != remembered_joint_values_.end())
1691  {
1692  return setJointValueTarget(it->second);
1693  }
1694  else
1695  {
1697  {
1698  impl_->setTargetType(JOINT);
1699  return true;
1700  }
1701  RCLCPP_ERROR(LOGGER, "The requested named target '%s' does not exist", name.c_str());
1702  return false;
1703  }
1704 }
1705 
1706 void MoveGroupInterface::getJointValueTarget(std::vector<double>& group_variable_values) const
1707 {
1708  impl_->getTargetRobotState().copyJointGroupPositions(impl_->getJointModelGroup(), group_variable_values);
1709 }
1710 
1711 bool MoveGroupInterface::setJointValueTarget(const std::vector<double>& joint_values)
1712 {
1713  auto const n_group_joints = impl_->getJointModelGroup()->getVariableCount();
1714  if (joint_values.size() != n_group_joints)
1715  {
1716  RCLCPP_DEBUG_STREAM(LOGGER, "Provided joint value list has length " << joint_values.size() << " but group "
1717  << impl_->getJointModelGroup()->getName()
1718  << " has " << n_group_joints << " joints");
1719  return false;
1720  }
1721  impl_->setTargetType(JOINT);
1722  impl_->getTargetRobotState().setJointGroupPositions(impl_->getJointModelGroup(), joint_values);
1724 }
1725 
1726 bool MoveGroupInterface::setJointValueTarget(const std::map<std::string, double>& variable_values)
1727 {
1728  const auto& allowed = impl_->getJointModelGroup()->getVariableNames();
1729  for (const auto& pair : variable_values)
1730  {
1731  if (std::find(allowed.begin(), allowed.end(), pair.first) == allowed.end())
1732  {
1733  RCLCPP_ERROR_STREAM(LOGGER, "joint variable " << pair.first << " is not part of group "
1734  << impl_->getJointModelGroup()->getName());
1735  return false;
1736  }
1737  }
1738 
1739  impl_->setTargetType(JOINT);
1740  impl_->getTargetRobotState().setVariablePositions(variable_values);
1741  return impl_->getTargetRobotState().satisfiesBounds(impl_->getGoalJointTolerance());
1742 }
1743 
1744 bool MoveGroupInterface::setJointValueTarget(const std::vector<std::string>& variable_names,
1745  const std::vector<double>& variable_values)
1746 {
1747  const auto& allowed = impl_->getJointModelGroup()->getVariableNames();
1748  for (const auto& variable_name : variable_names)
1749  {
1750  if (std::find(allowed.begin(), allowed.end(), variable_name) == allowed.end())
1751  {
1752  RCLCPP_ERROR_STREAM(LOGGER, "joint variable " << variable_name << " is not part of group "
1753  << impl_->getJointModelGroup()->getName());
1754  return false;
1755  }
1756  }
1757 
1758  impl_->setTargetType(JOINT);
1759  impl_->getTargetRobotState().setVariablePositions(variable_names, variable_values);
1760  return impl_->getTargetRobotState().satisfiesBounds(impl_->getGoalJointTolerance());
1761 }
1762 
1764 {
1765  impl_->setTargetType(JOINT);
1766  impl_->getTargetRobotState() = rstate;
1767  return impl_->getTargetRobotState().satisfiesBounds(impl_->getGoalJointTolerance());
1768 }
1769 
1770 bool MoveGroupInterface::setJointValueTarget(const std::string& joint_name, double value)
1771 {
1772  std::vector<double> values(1, value);
1773  return setJointValueTarget(joint_name, values);
1774 }
1775 
1776 bool MoveGroupInterface::setJointValueTarget(const std::string& joint_name, const std::vector<double>& values)
1777 {
1778  impl_->setTargetType(JOINT);
1779  const moveit::core::JointModel* jm = impl_->getJointModelGroup()->getJointModel(joint_name);
1780  if (jm && jm->getVariableCount() == values.size())
1781  {
1782  impl_->getTargetRobotState().setJointPositions(jm, values);
1783  return impl_->getTargetRobotState().satisfiesBounds(jm, impl_->getGoalJointTolerance());
1784  }
1785 
1786  RCLCPP_ERROR_STREAM(LOGGER,
1787  "joint " << joint_name << " is not part of group " << impl_->getJointModelGroup()->getName());
1788  return false;
1789 }
1790 
1791 bool MoveGroupInterface::setJointValueTarget(const sensor_msgs::msg::JointState& state)
1792 {
1793  return setJointValueTarget(state.name, state.position);
1794 }
1795 
1796 bool MoveGroupInterface::setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
1797  const std::string& end_effector_link)
1798 {
1799  return impl_->setJointValueTarget(eef_pose, end_effector_link, "", false);
1800 }
1801 
1802 bool MoveGroupInterface::setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
1803  const std::string& end_effector_link)
1804 {
1805  return impl_->setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id, false);
1806 }
1807 
1808 bool MoveGroupInterface::setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link)
1809 {
1810  geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1811  return setJointValueTarget(msg, end_effector_link);
1812 }
1813 
1814 bool MoveGroupInterface::setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
1815  const std::string& end_effector_link)
1816 {
1817  return impl_->setJointValueTarget(eef_pose, end_effector_link, "", true);
1818 }
1819 
1820 bool MoveGroupInterface::setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
1821  const std::string& end_effector_link)
1822 {
1823  return impl_->setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id, true);
1824 }
1825 
1826 bool MoveGroupInterface::setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose,
1827  const std::string& end_effector_link)
1828 {
1829  geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1830  return setApproximateJointValueTarget(msg, end_effector_link);
1831 }
1832 
1834 {
1835  return impl_->getTargetRobotState();
1836 }
1837 
1839 {
1840  return impl_->getTargetRobotState();
1841 }
1842 
1843 const std::string& MoveGroupInterface::getEndEffectorLink() const
1844 {
1845  return impl_->getEndEffectorLink();
1846 }
1847 
1848 const std::string& MoveGroupInterface::getEndEffector() const
1849 {
1850  return impl_->getEndEffector();
1851 }
1852 
1853 bool MoveGroupInterface::setEndEffectorLink(const std::string& link_name)
1854 {
1855  if (impl_->getEndEffectorLink().empty() || link_name.empty())
1856  return false;
1857  impl_->setEndEffectorLink(link_name);
1858  impl_->setTargetType(POSE);
1859  return true;
1860 }
1861 
1862 bool MoveGroupInterface::setEndEffector(const std::string& eef_name)
1863 {
1864  const moveit::core::JointModelGroup* jmg = impl_->getRobotModel()->getEndEffector(eef_name);
1865  if (jmg)
1866  return setEndEffectorLink(jmg->getEndEffectorParentGroup().second);
1867  return false;
1868 }
1869 
1870 void MoveGroupInterface::clearPoseTarget(const std::string& end_effector_link)
1871 {
1872  impl_->clearPoseTarget(end_effector_link);
1873 }
1874 
1876 {
1877  impl_->clearPoseTargets();
1878 }
1879 
1880 bool MoveGroupInterface::setPoseTarget(const Eigen::Isometry3d& pose, const std::string& end_effector_link)
1881 {
1882  std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1883  pose_msg[0].pose = tf2::toMsg(pose);
1884  pose_msg[0].header.frame_id = getPoseReferenceFrame();
1885  pose_msg[0].header.stamp = impl_->getClock()->now();
1886  return setPoseTargets(pose_msg, end_effector_link);
1887 }
1888 
1889 bool MoveGroupInterface::setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link)
1890 {
1891  std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1892  pose_msg[0].pose = target;
1893  pose_msg[0].header.frame_id = getPoseReferenceFrame();
1894  pose_msg[0].header.stamp = impl_->getClock()->now();
1895  return setPoseTargets(pose_msg, end_effector_link);
1896 }
1897 
1898 bool MoveGroupInterface::setPoseTarget(const geometry_msgs::msg::PoseStamped& target,
1899  const std::string& end_effector_link)
1900 {
1901  std::vector<geometry_msgs::msg::PoseStamped> targets(1, target);
1902  return setPoseTargets(targets, end_effector_link);
1903 }
1904 
1905 bool MoveGroupInterface::setPoseTargets(const EigenSTL::vector_Isometry3d& target, const std::string& end_effector_link)
1906 {
1907  std::vector<geometry_msgs::msg::PoseStamped> pose_out(target.size());
1908  rclcpp::Time tm = impl_->getClock()->now();
1909  const std::string& frame_id = getPoseReferenceFrame();
1910  for (std::size_t i = 0; i < target.size(); ++i)
1911  {
1912  pose_out[i].pose = tf2::toMsg(target[i]);
1913  pose_out[i].header.stamp = tm;
1914  pose_out[i].header.frame_id = frame_id;
1915  }
1916  return setPoseTargets(pose_out, end_effector_link);
1917 }
1918 
1919 bool MoveGroupInterface::setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target,
1920  const std::string& end_effector_link)
1921 {
1922  std::vector<geometry_msgs::msg::PoseStamped> target_stamped(target.size());
1923  rclcpp::Time tm = impl_->getClock()->now();
1924  const std::string& frame_id = getPoseReferenceFrame();
1925  for (std::size_t i = 0; i < target.size(); ++i)
1926  {
1927  target_stamped[i].pose = target[i];
1928  target_stamped[i].header.stamp = tm;
1929  target_stamped[i].header.frame_id = frame_id;
1930  }
1931  return setPoseTargets(target_stamped, end_effector_link);
1932 }
1933 
1934 bool MoveGroupInterface::setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
1935  const std::string& end_effector_link)
1936 {
1937  if (target.empty())
1938  {
1939  RCLCPP_ERROR(LOGGER, "No pose specified as goal target");
1940  return false;
1941  }
1942  else
1943  {
1944  impl_->setTargetType(POSE);
1945  return impl_->setPoseTargets(target, end_effector_link);
1946  }
1947 }
1948 
1949 const geometry_msgs::msg::PoseStamped& MoveGroupInterface::getPoseTarget(const std::string& end_effector_link) const
1950 {
1951  return impl_->getPoseTarget(end_effector_link);
1952 }
1953 
1954 const std::vector<geometry_msgs::msg::PoseStamped>&
1955 MoveGroupInterface::getPoseTargets(const std::string& end_effector_link) const
1956 {
1957  return impl_->getPoseTargets(end_effector_link);
1958 }
1959 
1960 namespace
1961 {
1962 inline void transformPose(const tf2_ros::Buffer& tf_buffer, const std::string& desired_frame,
1963  geometry_msgs::msg::PoseStamped& target)
1964 {
1965  if (desired_frame != target.header.frame_id)
1966  {
1967  geometry_msgs::msg::PoseStamped target_in(target);
1968  tf_buffer.transform(target_in, target, desired_frame);
1969  // we leave the stamp to ros::Time(0) on purpose
1970  target.header.stamp = rclcpp::Time(0);
1971  }
1972 }
1973 } // namespace
1974 
1975 bool MoveGroupInterface::setPositionTarget(double x, double y, double z, const std::string& end_effector_link)
1976 {
1977  geometry_msgs::msg::PoseStamped target;
1978  if (impl_->hasPoseTarget(end_effector_link))
1979  {
1980  target = getPoseTarget(end_effector_link);
1981  transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
1982  }
1983  else
1984  {
1985  target.pose.orientation.x = 0.0;
1986  target.pose.orientation.y = 0.0;
1987  target.pose.orientation.z = 0.0;
1988  target.pose.orientation.w = 1.0;
1989  target.header.frame_id = impl_->getPoseReferenceFrame();
1990  }
1991 
1992  target.pose.position.x = x;
1993  target.pose.position.y = y;
1994  target.pose.position.z = z;
1995  bool result = setPoseTarget(target, end_effector_link);
1996  impl_->setTargetType(POSITION);
1997  return result;
1998 }
1999 
2000 bool MoveGroupInterface::setRPYTarget(double r, double p, double y, const std::string& end_effector_link)
2001 {
2002  geometry_msgs::msg::PoseStamped target;
2003  if (impl_->hasPoseTarget(end_effector_link))
2004  {
2005  target = getPoseTarget(end_effector_link);
2006  transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
2007  }
2008  else
2009  {
2010  target.pose.position.x = 0.0;
2011  target.pose.position.y = 0.0;
2012  target.pose.position.z = 0.0;
2013  target.header.frame_id = impl_->getPoseReferenceFrame();
2014  }
2015  tf2::Quaternion q;
2016  q.setRPY(r, p, y);
2017  target.pose.orientation = tf2::toMsg(q);
2018  bool result = setPoseTarget(target, end_effector_link);
2019  impl_->setTargetType(ORIENTATION);
2020  return result;
2021 }
2022 
2023 bool MoveGroupInterface::setOrientationTarget(double x, double y, double z, double w,
2024  const std::string& end_effector_link)
2025 {
2026  geometry_msgs::msg::PoseStamped target;
2027  if (impl_->hasPoseTarget(end_effector_link))
2028  {
2029  target = getPoseTarget(end_effector_link);
2030  transformPose(*impl_->getTF(), impl_->getPoseReferenceFrame(), target);
2031  }
2032  else
2033  {
2034  target.pose.position.x = 0.0;
2035  target.pose.position.y = 0.0;
2036  target.pose.position.z = 0.0;
2037  target.header.frame_id = impl_->getPoseReferenceFrame();
2038  }
2039 
2040  target.pose.orientation.x = x;
2041  target.pose.orientation.y = y;
2042  target.pose.orientation.z = z;
2043  target.pose.orientation.w = w;
2044  bool result = setPoseTarget(target, end_effector_link);
2045  impl_->setTargetType(ORIENTATION);
2046  return result;
2047 }
2048 
2049 void MoveGroupInterface::setPoseReferenceFrame(const std::string& pose_reference_frame)
2050 {
2051  impl_->setPoseReferenceFrame(pose_reference_frame);
2052 }
2053 
2055 {
2056  return impl_->getPoseReferenceFrame();
2057 }
2058 
2060 {
2061  return impl_->getGoalJointTolerance();
2062 }
2063 
2065 {
2066  return impl_->getGoalPositionTolerance();
2067 }
2068 
2070 {
2071  return impl_->getGoalOrientationTolerance();
2072 }
2073 
2075 {
2076  setGoalJointTolerance(tolerance);
2077  setGoalPositionTolerance(tolerance);
2078  setGoalOrientationTolerance(tolerance);
2079 }
2080 
2082 {
2083  impl_->setGoalJointTolerance(tolerance);
2084 }
2085 
2087 {
2088  impl_->setGoalPositionTolerance(tolerance);
2089 }
2090 
2092 {
2093  impl_->setGoalOrientationTolerance(tolerance);
2094 }
2095 
2097 {
2099 }
2100 
2102 {
2103  return impl_->startStateMonitor(wait);
2104 }
2105 
2107 {
2108  moveit::core::RobotStatePtr current_state;
2109  std::vector<double> values;
2110  if (impl_->getCurrentState(current_state))
2111  current_state->copyJointGroupPositions(getName(), values);
2112  return values;
2113 }
2114 
2115 std::vector<double> MoveGroupInterface::getRandomJointValues() const
2116 {
2117  std::vector<double> r;
2119  return r;
2120 }
2121 
2122 geometry_msgs::msg::PoseStamped MoveGroupInterface::getRandomPose(const std::string& end_effector_link) const
2123 {
2124  const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
2125  Eigen::Isometry3d pose;
2126  pose.setIdentity();
2127  if (eef.empty())
2128  RCLCPP_ERROR(LOGGER, "No end-effector specified");
2129  else
2130  {
2131  moveit::core::RobotStatePtr current_state;
2132  if (impl_->getCurrentState(current_state))
2133  {
2134  current_state->setToRandomPositions(impl_->getJointModelGroup());
2135  const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
2136  if (lm)
2137  pose = current_state->getGlobalLinkTransform(lm);
2138  }
2139  }
2140  geometry_msgs::msg::PoseStamped pose_msg;
2141  pose_msg.header.stamp = impl_->getClock()->now();
2142  pose_msg.header.frame_id = impl_->getRobotModel()->getModelFrame();
2143  pose_msg.pose = tf2::toMsg(pose);
2144  return pose_msg;
2145 }
2146 
2147 geometry_msgs::msg::PoseStamped MoveGroupInterface::getCurrentPose(const std::string& end_effector_link) const
2148 {
2149  const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
2150  Eigen::Isometry3d pose;
2151  pose.setIdentity();
2152  if (eef.empty())
2153  RCLCPP_ERROR(LOGGER, "No end-effector specified");
2154  else
2155  {
2156  moveit::core::RobotStatePtr current_state;
2157  if (impl_->getCurrentState(current_state))
2158  {
2159  const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
2160  if (lm)
2161  pose = current_state->getGlobalLinkTransform(lm);
2162  }
2163  }
2164  geometry_msgs::msg::PoseStamped pose_msg;
2165  pose_msg.header.stamp = impl_->getClock()->now();
2166  pose_msg.header.frame_id = impl_->getRobotModel()->getModelFrame();
2167  pose_msg.pose = tf2::toMsg(pose);
2168  return pose_msg;
2169 }
2170 
2171 std::vector<double> MoveGroupInterface::getCurrentRPY(const std::string& end_effector_link) const
2172 {
2173  std::vector<double> result;
2174  const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
2175  if (eef.empty())
2176  RCLCPP_ERROR(LOGGER, "No end-effector specified");
2177  else
2178  {
2179  moveit::core::RobotStatePtr current_state;
2180  if (impl_->getCurrentState(current_state))
2181  {
2182  const moveit::core::LinkModel* lm = current_state->getLinkModel(eef);
2183  if (lm)
2184  {
2185  result.resize(3);
2186  geometry_msgs::msg::TransformStamped tfs = tf2::eigenToTransform(current_state->getGlobalLinkTransform(lm));
2187  double pitch, roll, yaw;
2188  tf2::getEulerYPR<geometry_msgs::msg::Quaternion>(tfs.transform.rotation, yaw, pitch, roll);
2189  result[0] = roll;
2190  result[1] = pitch;
2191  result[2] = yaw;
2192  }
2193  }
2194  }
2195  return result;
2196 }
2197 
2198 const std::vector<std::string>& MoveGroupInterface::getActiveJoints() const
2199 {
2200  return impl_->getJointModelGroup()->getActiveJointModelNames();
2201 }
2202 
2203 const std::vector<std::string>& MoveGroupInterface::getJoints() const
2204 {
2205  return impl_->getJointModelGroup()->getJointModelNames();
2206 }
2207 
2209 {
2210  return impl_->getJointModelGroup()->getVariableCount();
2211 }
2212 
2213 moveit::core::RobotStatePtr MoveGroupInterface::getCurrentState(double wait) const
2214 {
2215  moveit::core::RobotStatePtr current_state;
2216  impl_->getCurrentState(current_state, wait);
2217  return current_state;
2218 }
2219 
2220 void MoveGroupInterface::rememberJointValues(const std::string& name, const std::vector<double>& values)
2221 {
2222  remembered_joint_values_[name] = values;
2223 }
2224 
2226 {
2227  remembered_joint_values_.erase(name);
2228 }
2229 
2231 {
2232  impl_->can_look_ = flag;
2233  RCLCPP_DEBUG(LOGGER, "Looking around: %s", flag ? "yes" : "no");
2234 }
2235 
2237 {
2238  if (attempts < 0)
2239  {
2240  RCLCPP_ERROR(LOGGER, "Tried to set negative number of look-around attempts");
2241  }
2242  else
2243  {
2244  RCLCPP_DEBUG_STREAM(LOGGER, "Look around attempts: " << attempts);
2245  impl_->look_around_attempts_ = attempts;
2246  }
2247 }
2248 
2250 {
2251  impl_->can_replan_ = flag;
2252  RCLCPP_DEBUG(LOGGER, "Replanning: %s", flag ? "yes" : "no");
2253 }
2254 
2256 {
2257  if (attempts < 0)
2258  {
2259  RCLCPP_ERROR(LOGGER, "Tried to set negative number of replan attempts");
2260  }
2261  else
2262  {
2263  RCLCPP_DEBUG_STREAM(LOGGER, "Replan Attempts: " << attempts);
2264  impl_->replan_attempts_ = attempts;
2265  }
2266 }
2267 
2269 {
2270  if (delay < 0.0)
2271  {
2272  RCLCPP_ERROR(LOGGER, "Tried to set negative replan delay");
2273  }
2274  else
2275  {
2276  RCLCPP_DEBUG_STREAM(LOGGER, "Replan Delay: " << delay);
2277  impl_->replan_delay_ = delay;
2278  }
2279 }
2280 
2281 std::vector<std::string> MoveGroupInterface::getKnownConstraints() const
2282 {
2283  return impl_->getKnownConstraints();
2284 }
2285 
2286 moveit_msgs::msg::Constraints MoveGroupInterface::getPathConstraints() const
2287 {
2288  return impl_->getPathConstraints();
2289 }
2290 
2291 bool MoveGroupInterface::setPathConstraints(const std::string& constraint)
2292 {
2293  return impl_->setPathConstraints(constraint);
2294 }
2295 
2296 void MoveGroupInterface::setPathConstraints(const moveit_msgs::msg::Constraints& constraint)
2297 {
2298  impl_->setPathConstraints(constraint);
2299 }
2300 
2302 {
2303  impl_->clearPathConstraints();
2304 }
2305 
2306 moveit_msgs::msg::TrajectoryConstraints MoveGroupInterface::getTrajectoryConstraints() const
2307 {
2308  return impl_->getTrajectoryConstraints();
2309 }
2310 
2311 void MoveGroupInterface::setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint)
2312 {
2313  impl_->setTrajectoryConstraints(constraint);
2314 }
2315 
2317 {
2318  impl_->clearTrajectoryConstraints();
2319 }
2320 
2321 void MoveGroupInterface::setConstraintsDatabase(const std::string& host, unsigned int port)
2322 {
2323  impl_->initializeConstraintsStorage(host, port);
2324 }
2325 
2326 void MoveGroupInterface::setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
2327 {
2328  impl_->setWorkspace(minx, miny, minz, maxx, maxy, maxz);
2329 }
2330 
2333 {
2334  impl_->setPlanningTime(seconds);
2335 }
2336 
2339 {
2340  return impl_->getPlanningTime();
2341 }
2342 
2344 {
2345  impl_->setSupportSurfaceName(name);
2346 }
2347 
2348 const std::string& MoveGroupInterface::getPlanningFrame() const
2349 {
2350  return impl_->getRobotModel()->getModelFrame();
2351 }
2352 
2353 const std::vector<std::string>& MoveGroupInterface::getJointModelGroupNames() const
2354 {
2355  return impl_->getRobotModel()->getJointModelGroupNames();
2356 }
2357 
2358 bool MoveGroupInterface::attachObject(const std::string& object, const std::string& link)
2359 {
2360  return attachObject(object, link, std::vector<std::string>());
2361 }
2362 
2363 bool MoveGroupInterface::attachObject(const std::string& object, const std::string& link,
2364  const std::vector<std::string>& touch_links)
2365 {
2366  return impl_->attachObject(object, link, touch_links);
2367 }
2368 
2369 bool MoveGroupInterface::detachObject(const std::string& name)
2370 {
2371  return impl_->detachObject(name);
2372 }
2373 
2375 {
2376  impl_->constructMotionPlanRequest(goal_out);
2377 }
2378 
2379 } // namespace planning_interface
2380 } // namespace moveit
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool isChain() const
Check if this group is a linear chain.
const std::string & getName() const
Get the name of the joint group.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
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...
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 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 > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
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)
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...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
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.
Definition: robot_state.h:90
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...
Definition: robot_state.h:605
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...
Definition: robot_state.h:691
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.
Definition: robot_state.h:1711
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)
Definition: robot_state.h:515
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...
Definition: transforms.cpp:64
void constructGoal(moveit_msgs::action::MoveGroup::Goal &goal) const
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double step, double jump_threshold, moveit_msgs::msg::RobotTrajectory &msg, const moveit_msgs::msg::Constraints &path_constraints, bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes &error_code)
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)
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() const
moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory &trajectory, bool wait)
bool attachObject(const std::string &object, const std::string &link, const std::vector< std::string > &touch_links)
void initializeConstraintsStorage(const std::string &host, unsigned int port)
void setPathConstraints(const moveit_msgs::msg::Constraints &constraint)
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="")
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link) const
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request) const
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() 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)
bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription &desc)
bool setJointValueTarget(const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link, const std::string &frame, bool approx)
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link) const
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)
moveit::core::MoveItErrorCode plan(Plan &plan)
Convert a vector of PoseStamped to a vector of PlaceLocation.
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.
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double eef_step, double jump_threshold, 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...
std::vector< double > getRandomJointValues() const
Get random joint values for the joints planned for by this instance (see getJoints())
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)
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).
void setSupportSurfaceName(const std::string &name)
For pick/place operations, the name of the support surface is used to specify the fact that attached ...
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="")
Pick up an object.
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 ...
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
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.
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.
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.
moveit::core::MoveItErrorCode execute(const Plan &plan)
Given a plan, execute it while waiting for completion.
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.
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.
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::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link="") const
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
const std::vector< std::string > & getLinkNames() const
Get vector of names of links available in move group.
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.
const moveit::core::RobotState & getJointValueTarget() const
Get the currently set joint state goal, replaced by private getTargetRobotState()
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 ...
moveit::core::MoveItErrorCode asyncExecute(const Plan &plan)
Given a plan, execute it without waiting for completion.
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 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:144
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:56
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_...
Definition: robot_state.h:70
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.
Definition: exceptions.h:43
frame_id
Definition: pick.py:63
w
Definition: pick.py:67
p
Definition: pick.py:62
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
Definition: plan.py:1
r
Definition: plan.py:56
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
std::string append(const std::string &left, const std::string &right)
d
Definition: setup.py:4
name
Definition: setup.py:7
A set of options for the kinematics solver.
Specification of options to use when constructing the MoveGroupInterface class.
std::string group_name_
The group to construct the class instance for.
std::string move_group_namespace_
The namespace for the move group node.
The representation of a motion plan (as ROS messasges)