moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
move_group_interface.hpp
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#include <rclcpp/version.h>
52
53#include <moveit_msgs/msg/motion_plan_request.hpp>
54#include <geometry_msgs/msg/pose_stamped.hpp>
55
56#include <rclcpp_action/rclcpp_action.hpp>
57
58#include <memory>
59#include <utility>
60// For Rolling, Kilted, and newer
61#if RCLCPP_VERSION_GTE(29, 6, 0)
62#include <tf2_ros/buffer.hpp>
63// For Jazzy and older
64#else
65#include <tf2_ros/buffer.h>
66#endif
67
68#include <moveit_move_group_interface_export.h>
69
70namespace moveit
71{
73namespace planning_interface
74{
75MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
76
82class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface
83{
84public:
86 static const std::string ROBOT_DESCRIPTION;
87
89 struct Options
90 {
91 Options(std::string group_name, std::string desc = ROBOT_DESCRIPTION, std::string move_group_namespace = "")
92 : group_name(std::move(group_name))
93 , robot_description(std::move(desc))
94 , move_group_namespace(std::move(move_group_namespace))
95 {
96 }
97
99 std::string group_name;
100
102 std::string robot_description;
103
105 moveit::core::RobotModelConstPtr robot_model;
106
109 };
110
112
114 struct Plan
115 {
117 moveit_msgs::msg::RobotState start_state;
118
120 moveit_msgs::msg::RobotTrajectory trajectory;
121
124 };
125
136 MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
137 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
138 const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
139
147 MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group,
148 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
149 const rclcpp::Duration& wait_for_servers = rclcpp::Duration::from_seconds(-1));
150
152
160
161 MoveGroupInterface(MoveGroupInterface&& other) noexcept;
162 MoveGroupInterface& operator=(MoveGroupInterface&& other) noexcept;
164 const std::string& getName() const;
165
168 const std::vector<std::string>& getNamedTargets() const;
169
171 const std::shared_ptr<tf2_ros::Buffer>& getTF() const;
172
174 moveit::core::RobotModelConstPtr getRobotModel() const;
175
177 const rclcpp::Node::SharedPtr& getNode() const;
178
180 const std::string& getPlanningFrame() const;
181
183 const std::vector<std::string>& getJointModelGroupNames() const;
184
186 const std::vector<std::string>& getJointNames() const;
187
189 const std::vector<std::string>& getLinkNames() const;
190
192 std::map<std::string, double> getNamedTargetValues(const std::string& name) const;
193
195 const std::vector<std::string>& getActiveJoints() const;
196
198 const std::vector<std::string>& getJoints() const;
199
202 unsigned int getVariableCount() const;
203
205 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const;
206
208 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const;
209
211 std::map<std::string, std::string> getPlannerParams(const std::string& planner_id,
212 const std::string& group = "") const;
213
215 void setPlannerParams(const std::string& planner_id, const std::string& group,
216 const std::map<std::string, std::string>& params, bool bReplace = false);
217
218 std::string getDefaultPlanningPipelineId() const;
219
221 void setPlanningPipelineId(const std::string& pipeline_id);
222
224 const std::string& getPlanningPipelineId() const;
225
227 std::string getDefaultPlannerId(const std::string& group = "") const;
228
230 void setPlannerId(const std::string& planner_id);
231
233 const std::string& getPlannerId() const;
234
236 void setPlanningTime(double seconds);
237
240 void setNumPlanningAttempts(unsigned int num_planning_attempts);
241
247 void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
248
250 double getMaxVelocityScalingFactor() const;
251
257 void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
258
260 double getMaxAccelerationScalingFactor() const;
261
263 double getPlanningTime() const;
264
267 double getGoalJointTolerance() const;
268
271 double getGoalPositionTolerance() const;
272
275 double getGoalOrientationTolerance() const;
276
283 void setGoalTolerance(double tolerance);
284
287 void setGoalJointTolerance(double tolerance);
288
290 void setGoalPositionTolerance(double tolerance);
291
293 void setGoalOrientationTolerance(double tolerance);
294
299 void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
300
303 void setStartState(const moveit_msgs::msg::RobotState& start_state);
304
307 void setStartState(const moveit::core::RobotState& start_state);
308
310 void setStartStateToCurrentState();
311
341 bool setJointValueTarget(const std::vector<double>& group_variable_values);
342
358 bool setJointValueTarget(const std::map<std::string, double>& variable_values);
359
375 bool setJointValueTarget(const std::vector<std::string>& variable_names, const std::vector<double>& variable_values);
376
386 bool setJointValueTarget(const moveit::core::RobotState& robot_state);
387
399 bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
400
412 bool setJointValueTarget(const std::string& joint_name, double value);
413
424 bool setJointValueTarget(const sensor_msgs::msg::JointState& state);
425
437 bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link = "");
438
450 bool setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose, const std::string& end_effector_link = "");
451
463 bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
464
475 bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
476 const std::string& end_effector_link = "");
477
488 bool setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
489 const std::string& end_effector_link = "");
490
501 bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
502
507 void setRandomTarget();
508
511 bool setNamedTarget(const std::string& name);
512
514 void getJointValueTarget(std::vector<double>& group_variable_values) const;
515
537 bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
538
546 bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
547
556 bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
557
565 bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
566
574 bool setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link = "");
575
583 bool setPoseTarget(const geometry_msgs::msg::PoseStamped& target, const std::string& end_effector_link = "");
584
603 bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
604
623 bool setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target, const std::string& end_effector_link = "");
624
643 bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
644 const std::string& end_effector_link = "");
645
647 void setPoseReferenceFrame(const std::string& pose_reference_frame);
648
652 bool setEndEffectorLink(const std::string& end_effector_link);
653
656 bool setEndEffector(const std::string& eef_name);
657
659 void clearPoseTarget(const std::string& end_effector_link = "");
660
662 void clearPoseTargets();
663
670 const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
671
677 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
678
684 const std::string& getEndEffectorLink() const;
685
691 const std::string& getEndEffector() const;
692
695 const std::string& getPoseReferenceFrame() const;
696
708
713 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const;
714
720
725
732 moveit::core::MoveItErrorCode asyncExecute(const Plan& plan,
733 const std::vector<std::string>& controllers = std::vector<std::string>());
734
741 moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
742 const std::vector<std::string>& controllers = std::vector<std::string>());
743
750 moveit::core::MoveItErrorCode execute(const Plan& plan,
751 const std::vector<std::string>& controllers = std::vector<std::string>());
752
759 moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory,
760 const std::vector<std::string>& controllers = std::vector<std::string>());
761
771 [[deprecated("Drop jump_threshold")]] double //
772 computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
773 double /*jump_threshold*/, moveit_msgs::msg::RobotTrajectory& trajectory,
774 bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr)
775 {
776 return computeCartesianPath(waypoints, eef_step, trajectory, avoid_collisions, error_code);
777 }
778 double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
779 moveit_msgs::msg::RobotTrajectory& trajectory, bool avoid_collisions = true,
780 moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
781
794 [[deprecated("Drop jump_threshold")]] double //
795 computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
796 double /*jump_threshold*/, moveit_msgs::msg::RobotTrajectory& trajectory,
797 const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true,
798 moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr)
799 {
800 return computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, error_code);
801 }
802 double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
803 moveit_msgs::msg::RobotTrajectory& trajectory,
804 const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true,
805 moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
806
808 void stop();
809
811 void allowReplanning(bool flag);
812
814 void setReplanAttempts(int32_t attempts);
815
817 void setReplanDelay(double delay);
818
821 void allowLooking(bool flag);
822
824 void setLookAroundAttempts(int32_t attempts);
825
832 void constructRobotState(moveit_msgs::msg::RobotState& state);
833
836 void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request);
837
851 bool attachObject(const std::string& object, const std::string& link = "");
852
861 bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
862
868 bool detachObject(const std::string& name = "");
869
882 bool startStateMonitor(double wait = 1.0);
883
885 std::vector<double> getCurrentJointValues() const;
886
888 moveit::core::RobotStatePtr getCurrentState(double wait = 1) const;
889
893 geometry_msgs::msg::PoseStamped getCurrentPose(const std::string& end_effector_link = "") const;
894
898 std::vector<double> getCurrentRPY(const std::string& end_effector_link = "") const;
899
901 std::vector<double> getRandomJointValues() const;
902
906 geometry_msgs::msg::PoseStamped getRandomPose(const std::string& end_effector_link = "") const;
907
919 void rememberJointValues(const std::string& name);
920
925 void rememberJointValues(const std::string& name, const std::vector<double>& values);
926
928 const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
929 {
930 return remembered_joint_values_;
931 }
932
934 void forgetJointValues(const std::string& name);
935
944 void setConstraintsDatabase(const std::string& host, unsigned int port);
945
947 std::vector<std::string> getKnownConstraints() const;
948
952 moveit_msgs::msg::Constraints getPathConstraints() const;
953
957 bool setPathConstraints(const std::string& constraint);
958
962 void setPathConstraints(const moveit_msgs::msg::Constraints& constraint);
963
966 void clearPathConstraints();
967
968 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const;
969 void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint);
970 void clearTrajectoryConstraints();
971
974protected:
976 const moveit::core::RobotState& getTargetRobotState() const;
977
978private:
979 std::map<std::string, std::vector<double> > remembered_joint_values_;
980 class MoveGroupInterfaceImpl;
981 MoveGroupInterfaceImpl* impl_;
982 rclcpp::Logger logger_;
983};
984} // namespace planning_interface
985} // namespace moveit
#define MOVEIT_CLASS_FORWARD(C)
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.
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, 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...
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
MoveGroupInterface(const MoveGroupInterface &)=delete
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy....
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double eef_step, double, moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, 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...
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
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 messages)
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.