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 
51 #include <moveit_msgs/msg/motion_plan_request.hpp>
52 #include <geometry_msgs/msg/pose_stamped.hpp>
53 
54 #include <rclcpp_action/rclcpp_action.hpp>
55 
56 #include <memory>
57 #include <utility>
58 #include <tf2_ros/buffer.h>
59 
60 #include <moveit_move_group_interface_export.h>
61 
62 namespace moveit
63 {
65 namespace planning_interface
66 {
67 using MoveItErrorCode [[deprecated("Use moveit::core::MoveItErrorCode")]] = moveit::core::MoveItErrorCode;
68 
69 MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
70 
76 class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface
77 {
78 public:
80  static const std::string ROBOT_DESCRIPTION;
81 
83  struct Options
84  {
85  Options(std::string group_name, std::string desc = ROBOT_DESCRIPTION, std::string move_group_namespace = "")
86  : group_name(std::move(group_name))
87  , robot_description(std::move(desc))
88  , move_group_namespace(std::move(move_group_namespace))
89  {
90  }
91 
93  std::string group_name;
94 
96  std::string robot_description;
97 
99  moveit::core::RobotModelConstPtr robot_model;
100 
102  std::string move_group_namespace;
103  };
104 
106 
108  struct Plan
109  {
111  moveit_msgs::msg::RobotState start_state;
112 
114  moveit_msgs::msg::RobotTrajectory trajectory;
115 
118  };
119 
130  MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
131  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
132  const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
133 
141  MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group,
142  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
143  const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
144 
146 
154 
155  MoveGroupInterface(MoveGroupInterface&& other) noexcept;
156  MoveGroupInterface& operator=(MoveGroupInterface&& other) noexcept;
158  const std::string& getName() const;
159 
162  const std::vector<std::string>& getNamedTargets() const;
163 
165  moveit::core::RobotModelConstPtr getRobotModel() const;
166 
168  rclcpp::Node::SharedPtr getNodeHandle();
169 
171  const std::string& getPlanningFrame() const;
172 
174  const std::vector<std::string>& getJointModelGroupNames() const;
175 
177  const std::vector<std::string>& getJointNames() const;
178 
180  const std::vector<std::string>& getLinkNames() const;
181 
183  std::map<std::string, double> getNamedTargetValues(const std::string& name) const;
184 
186  const std::vector<std::string>& getActiveJoints() const;
187 
189  const std::vector<std::string>& getJoints() const;
190 
193  unsigned int getVariableCount() const;
194 
196  bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const;
197 
199  bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const;
200 
202  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id,
203  const std::string& group = "") const;
204 
206  void setPlannerParams(const std::string& planner_id, const std::string& group,
207  const std::map<std::string, std::string>& params, bool bReplace = false);
208 
209  std::string getDefaultPlanningPipelineId() const;
210 
212  void setPlanningPipelineId(const std::string& pipeline_id);
213 
215  const std::string& getPlanningPipelineId() const;
216 
218  std::string getDefaultPlannerId(const std::string& group = "") const;
219 
221  void setPlannerId(const std::string& planner_id);
222 
224  const std::string& getPlannerId() const;
225 
227  void setPlanningTime(double seconds);
228 
231  void setNumPlanningAttempts(unsigned int num_planning_attempts);
232 
238  void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
239 
245  void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
246 
248  double getPlanningTime() const;
249 
252  double getGoalJointTolerance() const;
253 
256  double getGoalPositionTolerance() const;
257 
260  double getGoalOrientationTolerance() const;
261 
268  void setGoalTolerance(double tolerance);
269 
272  void setGoalJointTolerance(double tolerance);
273 
275  void setGoalPositionTolerance(double tolerance);
276 
278  void setGoalOrientationTolerance(double tolerance);
279 
284  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
285 
288  void setStartState(const moveit_msgs::msg::RobotState& start_state);
289 
292  void setStartState(const moveit::core::RobotState& start_state);
293 
295  void setStartStateToCurrentState();
296 
299  void setSupportSurfaceName(const std::string& name);
300 
330  bool setJointValueTarget(const std::vector<double>& group_variable_values);
331 
347  bool setJointValueTarget(const std::map<std::string, double>& variable_values);
348 
364  bool setJointValueTarget(const std::vector<std::string>& variable_names, const std::vector<double>& variable_values);
365 
375  bool setJointValueTarget(const moveit::core::RobotState& robot_state);
376 
388  bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
389 
401  bool setJointValueTarget(const std::string& joint_name, double value);
402 
413  bool setJointValueTarget(const sensor_msgs::msg::JointState& state);
414 
426  bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link = "");
427 
439  bool setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose, const std::string& end_effector_link = "");
440 
452  bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
453 
464  bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
465  const std::string& end_effector_link = "");
466 
477  bool setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
478  const std::string& end_effector_link = "");
479 
490  bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
491 
496  void setRandomTarget();
497 
500  bool setNamedTarget(const std::string& name);
501 
503  void getJointValueTarget(std::vector<double>& group_variable_values) const;
504 
506  [[deprecated]] const moveit::core::RobotState& getJointValueTarget() const;
507 
529  bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
530 
538  bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
539 
548  bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
549 
557  bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
558 
566  bool setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link = "");
567 
575  bool setPoseTarget(const geometry_msgs::msg::PoseStamped& target, const std::string& end_effector_link = "");
576 
595  bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
596 
615  bool setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target, const std::string& end_effector_link = "");
616 
635  bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
636  const std::string& end_effector_link = "");
637 
639  void setPoseReferenceFrame(const std::string& pose_reference_frame);
640 
644  bool setEndEffectorLink(const std::string& end_effector_link);
645 
648  bool setEndEffector(const std::string& eef_name);
649 
651  void clearPoseTarget(const std::string& end_effector_link = "");
652 
654  void clearPoseTargets();
655 
662  const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
663 
669  const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
670 
676  const std::string& getEndEffectorLink() const;
677 
683  const std::string& getEndEffector() const;
684 
687  const std::string& getPoseReferenceFrame() const;
688 
699  moveit::core::MoveItErrorCode asyncMove();
700 
705  rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const;
706 
712 
717 
724  moveit::core::MoveItErrorCode asyncExecute(const Plan& plan,
725  const std::vector<std::string>& controllers = std::vector<std::string>());
726 
733  moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
734  const std::vector<std::string>& controllers = std::vector<std::string>());
735 
742  moveit::core::MoveItErrorCode execute(const Plan& plan,
743  const std::vector<std::string>& controllers = std::vector<std::string>());
744 
751  moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory,
752  const std::vector<std::string>& controllers = std::vector<std::string>());
753 
763  double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
764  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
765  bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
766 
779  double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
780  double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory,
781  const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true,
782  moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
783 
785  void stop();
786 
788  void allowReplanning(bool flag);
789 
791  void setReplanAttempts(int32_t attempts);
792 
794  void setReplanDelay(double delay);
795 
798  void allowLooking(bool flag);
799 
801  void setLookAroundAttempts(int32_t attempts);
802 
805  void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request);
806 
820  bool attachObject(const std::string& object, const std::string& link = "");
821 
830  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
831 
837  bool detachObject(const std::string& name = "");
838 
851  bool startStateMonitor(double wait = 1.0);
852 
854  std::vector<double> getCurrentJointValues() const;
855 
857  moveit::core::RobotStatePtr getCurrentState(double wait = 1) const;
858 
862  geometry_msgs::msg::PoseStamped getCurrentPose(const std::string& end_effector_link = "") const;
863 
867  std::vector<double> getCurrentRPY(const std::string& end_effector_link = "") const;
868 
870  std::vector<double> getRandomJointValues() const;
871 
875  geometry_msgs::msg::PoseStamped getRandomPose(const std::string& end_effector_link = "") const;
876 
888  void rememberJointValues(const std::string& name);
889 
894  void rememberJointValues(const std::string& name, const std::vector<double>& values);
895 
897  const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
898  {
899  return remembered_joint_values_;
900  }
901 
903  void forgetJointValues(const std::string& name);
904 
913  void setConstraintsDatabase(const std::string& host, unsigned int port);
914 
916  std::vector<std::string> getKnownConstraints() const;
917 
921  moveit_msgs::msg::Constraints getPathConstraints() const;
922 
926  bool setPathConstraints(const std::string& constraint);
927 
931  void setPathConstraints(const moveit_msgs::msg::Constraints& constraint);
932 
935  void clearPathConstraints();
936 
937  moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const;
938  void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint);
939  void clearTrajectoryConstraints();
940 
943 protected:
945  const moveit::core::RobotState& getTargetRobotState() const;
946 
947 private:
948  std::map<std::string, std::vector<double> > remembered_joint_values_;
949  class MoveGroupInterfaceImpl;
950  MoveGroupInterfaceImpl* impl_;
951 };
952 } // namespace planning_interface
953 } // 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)
moveit::core::MoveItErrorCode MoveItErrorCode
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::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.