moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, SRI International
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan, Sachin Chitta */
37 
38 #pragma once
39 
43 #include <moveit_msgs/msg/robot_trajectory.hpp>
44 #include <moveit_msgs/msg/robot_state.hpp>
45 #include <moveit_msgs/msg/planner_interface_description.hpp>
46 #include <moveit_msgs/msg/constraints.hpp>
47 #include <moveit_msgs/msg/grasp.hpp>
48 #include <moveit_msgs/action/move_group.hpp>
49 #include <moveit_msgs/action/execute_trajectory.hpp>
50 #include <rclcpp/logger.hpp>
51 
52 #include <moveit_msgs/msg/motion_plan_request.hpp>
53 #include <geometry_msgs/msg/pose_stamped.hpp>
54 
55 #include <rclcpp_action/rclcpp_action.hpp>
56 
57 #include <memory>
58 #include <utility>
59 #include <tf2_ros/buffer.h>
60 
61 #include <moveit_move_group_interface_export.h>
62 
63 namespace moveit
64 {
66 namespace planning_interface
67 {
68 MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
69 
75 class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface
76 {
77 public:
79  static const std::string ROBOT_DESCRIPTION;
80 
82  struct Options
83  {
84  Options(std::string group_name, std::string desc = ROBOT_DESCRIPTION, std::string move_group_namespace = "")
85  : group_name(std::move(group_name))
86  , robot_description(std::move(desc))
87  , move_group_namespace(std::move(move_group_namespace))
88  {
89  }
90 
92  std::string group_name;
93 
95  std::string robot_description;
96 
98  moveit::core::RobotModelConstPtr robot_model;
99 
101  std::string move_group_namespace;
102  };
103 
105 
107  struct Plan
108  {
110  moveit_msgs::msg::RobotState start_state;
111 
113  moveit_msgs::msg::RobotTrajectory trajectory;
114 
117  };
118 
129  MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
130  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
131  const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
132 
140  MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group,
141  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
142  const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
143 
145 
153 
154  MoveGroupInterface(MoveGroupInterface&& other) noexcept;
155  MoveGroupInterface& operator=(MoveGroupInterface&& other) noexcept;
157  const std::string& getName() const;
158 
161  const std::vector<std::string>& getNamedTargets() const;
162 
164  moveit::core::RobotModelConstPtr getRobotModel() const;
165 
167  rclcpp::Node::SharedPtr getNodeHandle();
168 
170  const std::string& getPlanningFrame() const;
171 
173  const std::vector<std::string>& getJointModelGroupNames() const;
174 
176  const std::vector<std::string>& getJointNames() const;
177 
179  const std::vector<std::string>& getLinkNames() const;
180 
182  std::map<std::string, double> getNamedTargetValues(const std::string& name) const;
183 
185  const std::vector<std::string>& getActiveJoints() const;
186 
188  const std::vector<std::string>& getJoints() const;
189 
192  unsigned int getVariableCount() const;
193 
195  bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const;
196 
198  bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const;
199 
201  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id,
202  const std::string& group = "") const;
203 
205  void setPlannerParams(const std::string& planner_id, const std::string& group,
206  const std::map<std::string, std::string>& params, bool bReplace = false);
207 
208  std::string getDefaultPlanningPipelineId() const;
209 
211  void setPlanningPipelineId(const std::string& pipeline_id);
212 
214  const std::string& getPlanningPipelineId() const;
215 
217  std::string getDefaultPlannerId(const std::string& group = "") const;
218 
220  void setPlannerId(const std::string& planner_id);
221 
223  const std::string& getPlannerId() const;
224 
226  void setPlanningTime(double seconds);
227 
230  void setNumPlanningAttempts(unsigned int num_planning_attempts);
231 
237  void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
238 
244  void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
245 
247  double getPlanningTime() const;
248 
251  double getGoalJointTolerance() const;
252 
255  double getGoalPositionTolerance() const;
256 
259  double getGoalOrientationTolerance() const;
260 
267  void setGoalTolerance(double tolerance);
268 
271  void setGoalJointTolerance(double tolerance);
272 
274  void setGoalPositionTolerance(double tolerance);
275 
277  void setGoalOrientationTolerance(double tolerance);
278 
283  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
284 
287  void setStartState(const moveit_msgs::msg::RobotState& start_state);
288 
291  void setStartState(const moveit::core::RobotState& start_state);
292 
294  void setStartStateToCurrentState();
295 
298  void setSupportSurfaceName(const std::string& name);
299 
329  bool setJointValueTarget(const std::vector<double>& group_variable_values);
330 
346  bool setJointValueTarget(const std::map<std::string, double>& variable_values);
347 
363  bool setJointValueTarget(const std::vector<std::string>& variable_names, const std::vector<double>& variable_values);
364 
374  bool setJointValueTarget(const moveit::core::RobotState& robot_state);
375 
387  bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
388 
400  bool setJointValueTarget(const std::string& joint_name, double value);
401 
412  bool setJointValueTarget(const sensor_msgs::msg::JointState& state);
413 
425  bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link = "");
426 
438  bool setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose, const std::string& end_effector_link = "");
439 
451  bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
452 
463  bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
464  const std::string& end_effector_link = "");
465 
476  bool setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
477  const std::string& end_effector_link = "");
478 
489  bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
490 
495  void setRandomTarget();
496 
499  bool setNamedTarget(const std::string& name);
500 
502  void getJointValueTarget(std::vector<double>& group_variable_values) const;
503 
525  bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
526 
534  bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
535 
544  bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
545 
553  bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
554 
562  bool setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link = "");
563 
571  bool setPoseTarget(const geometry_msgs::msg::PoseStamped& target, const std::string& end_effector_link = "");
572 
591  bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
592 
611  bool setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target, const std::string& end_effector_link = "");
612 
631  bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
632  const std::string& end_effector_link = "");
633 
635  void setPoseReferenceFrame(const std::string& pose_reference_frame);
636 
640  bool setEndEffectorLink(const std::string& end_effector_link);
641 
644  bool setEndEffector(const std::string& eef_name);
645 
647  void clearPoseTarget(const std::string& end_effector_link = "");
648 
650  void clearPoseTargets();
651 
658  const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
659 
665  const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
666 
672  const std::string& getEndEffectorLink() const;
673 
679  const std::string& getEndEffector() const;
680 
683  const std::string& getPoseReferenceFrame() const;
684 
695  moveit::core::MoveItErrorCode asyncMove();
696 
701  rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const;
702 
708 
713 
720  moveit::core::MoveItErrorCode asyncExecute(const Plan& plan,
721  const std::vector<std::string>& controllers = std::vector<std::string>());
722 
729  moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
730  const std::vector<std::string>& controllers = std::vector<std::string>());
731 
738  moveit::core::MoveItErrorCode execute(const Plan& plan,
739  const std::vector<std::string>& controllers = std::vector<std::string>());
740 
747  moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory,
748  const std::vector<std::string>& controllers = std::vector<std::string>());
749 
759  double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
760  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
761  bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
762 
775  double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
776  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
777  const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true,
778  moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
779 
781  void stop();
782 
784  void allowReplanning(bool flag);
785 
787  void setReplanAttempts(int32_t attempts);
788 
790  void setReplanDelay(double delay);
791 
794  void allowLooking(bool flag);
795 
797  void setLookAroundAttempts(int32_t attempts);
798 
801  void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request);
802 
816  bool attachObject(const std::string& object, const std::string& link = "");
817 
826  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
827 
833  bool detachObject(const std::string& name = "");
834 
847  bool startStateMonitor(double wait = 1.0);
848 
850  std::vector<double> getCurrentJointValues() const;
851 
853  moveit::core::RobotStatePtr getCurrentState(double wait = 1) const;
854 
858  geometry_msgs::msg::PoseStamped getCurrentPose(const std::string& end_effector_link = "") const;
859 
863  std::vector<double> getCurrentRPY(const std::string& end_effector_link = "") const;
864 
866  std::vector<double> getRandomJointValues() const;
867 
871  geometry_msgs::msg::PoseStamped getRandomPose(const std::string& end_effector_link = "") const;
872 
884  void rememberJointValues(const std::string& name);
885 
890  void rememberJointValues(const std::string& name, const std::vector<double>& values);
891 
893  const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
894  {
895  return remembered_joint_values_;
896  }
897 
899  void forgetJointValues(const std::string& name);
900 
909  void setConstraintsDatabase(const std::string& host, unsigned int port);
910 
912  std::vector<std::string> getKnownConstraints() const;
913 
917  moveit_msgs::msg::Constraints getPathConstraints() const;
918 
922  bool setPathConstraints(const std::string& constraint);
923 
927  void setPathConstraints(const moveit_msgs::msg::Constraints& constraint);
928 
931  void clearPathConstraints();
932 
933  moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const;
934  void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint);
935  void clearTrajectoryConstraints();
936 
939 protected:
941  const moveit::core::RobotState& getTargetRobotState() const;
942 
943 private:
944  std::map<std::string, std::vector<double> > remembered_joint_values_;
945  class MoveGroupInterfaceImpl;
946  MoveGroupInterfaceImpl* impl_;
947  rclcpp::Logger logger_;
948 };
949 } // namespace planning_interface
950 } // namespace moveit
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
Client class to conveniently use the ROS interfaces provided by the move_group node.
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
MoveGroupInterface(const MoveGroupInterface &)=delete
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy....
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
rclcpp::Node::SharedPtr getNodeHandle()
Get the ROS node handle of this instance operates on.
MOVEIT_CLASS_FORWARD(MoveGroupInterface)
bool setStartState(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::optional< std::string > configuration_name, std::optional< moveit::core::RobotState > robot_state)
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
Main namespace for MoveIt.
Definition: exceptions.h:43
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
name
Definition: setup.py:7
Specification of options to use when constructing the MoveGroupInterface class.
std::string move_group_namespace
The namespace for the move group node.
Options(std::string group_name, std::string desc=ROBOT_DESCRIPTION, std::string move_group_namespace="")
std::string robot_description
The robot description parameter name (if different from default)
moveit::core::RobotModelConstPtr robot_model
Optionally, an instance of the RobotModel to use can be also specified.
std::string group_name
The group to construct the class instance for.
The representation of a motion plan (as ROS messasges)
moveit_msgs::msg::RobotTrajectory trajectory
The trajectory of the robot (may not contain joints that are the same as for the start_state_)
double planning_time
The amount of time it took to generate the plan.
moveit_msgs::msg::RobotState start_state
The full starting state used for planning.