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
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
63namespace moveit
64{
66namespace planning_interface
67{
68MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
69
75class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface
76{
77public:
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
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 const std::shared_ptr<tf2_ros::Buffer>& getTF() const;
165
167 moveit::core::RobotModelConstPtr getRobotModel() const;
168
170 const rclcpp::Node::SharedPtr& getNode() const;
171
173 const std::string& getPlanningFrame() const;
174
176 const std::vector<std::string>& getJointModelGroupNames() const;
177
179 const std::vector<std::string>& getJointNames() const;
180
182 const std::vector<std::string>& getLinkNames() const;
183
185 std::map<std::string, double> getNamedTargetValues(const std::string& name) const;
186
188 const std::vector<std::string>& getActiveJoints() const;
189
191 const std::vector<std::string>& getJoints() const;
192
195 unsigned int getVariableCount() const;
196
198 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc) const;
199
201 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const;
202
204 std::map<std::string, std::string> getPlannerParams(const std::string& planner_id,
205 const std::string& group = "") const;
206
208 void setPlannerParams(const std::string& planner_id, const std::string& group,
209 const std::map<std::string, std::string>& params, bool bReplace = false);
210
211 std::string getDefaultPlanningPipelineId() const;
212
214 void setPlanningPipelineId(const std::string& pipeline_id);
215
217 const std::string& getPlanningPipelineId() const;
218
220 std::string getDefaultPlannerId(const std::string& group = "") const;
221
223 void setPlannerId(const std::string& planner_id);
224
226 const std::string& getPlannerId() const;
227
229 void setPlanningTime(double seconds);
230
233 void setNumPlanningAttempts(unsigned int num_planning_attempts);
234
240 void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
241
243 double getMaxVelocityScalingFactor() const;
244
250 void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
251
253 double getMaxAccelerationScalingFactor() const;
254
256 double getPlanningTime() const;
257
260 double getGoalJointTolerance() const;
261
264 double getGoalPositionTolerance() const;
265
268 double getGoalOrientationTolerance() const;
269
276 void setGoalTolerance(double tolerance);
277
280 void setGoalJointTolerance(double tolerance);
281
283 void setGoalPositionTolerance(double tolerance);
284
286 void setGoalOrientationTolerance(double tolerance);
287
292 void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
293
296 void setStartState(const moveit_msgs::msg::RobotState& start_state);
297
300 void setStartState(const moveit::core::RobotState& start_state);
301
303 void setStartStateToCurrentState();
304
334 bool setJointValueTarget(const std::vector<double>& group_variable_values);
335
351 bool setJointValueTarget(const std::map<std::string, double>& variable_values);
352
368 bool setJointValueTarget(const std::vector<std::string>& variable_names, const std::vector<double>& variable_values);
369
379 bool setJointValueTarget(const moveit::core::RobotState& robot_state);
380
392 bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
393
405 bool setJointValueTarget(const std::string& joint_name, double value);
406
417 bool setJointValueTarget(const sensor_msgs::msg::JointState& state);
418
430 bool setJointValueTarget(const geometry_msgs::msg::Pose& eef_pose, const std::string& end_effector_link = "");
431
443 bool setJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose, const std::string& end_effector_link = "");
444
456 bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
457
468 bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose& eef_pose,
469 const std::string& end_effector_link = "");
470
481 bool setApproximateJointValueTarget(const geometry_msgs::msg::PoseStamped& eef_pose,
482 const std::string& end_effector_link = "");
483
494 bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
495
500 void setRandomTarget();
501
504 bool setNamedTarget(const std::string& name);
505
507 void getJointValueTarget(std::vector<double>& group_variable_values) const;
508
530 bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
531
539 bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
540
549 bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
550
558 bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
559
567 bool setPoseTarget(const geometry_msgs::msg::Pose& target, const std::string& end_effector_link = "");
568
576 bool setPoseTarget(const geometry_msgs::msg::PoseStamped& target, const std::string& end_effector_link = "");
577
596 bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
597
616 bool setPoseTargets(const std::vector<geometry_msgs::msg::Pose>& target, const std::string& end_effector_link = "");
617
636 bool setPoseTargets(const std::vector<geometry_msgs::msg::PoseStamped>& target,
637 const std::string& end_effector_link = "");
638
640 void setPoseReferenceFrame(const std::string& pose_reference_frame);
641
645 bool setEndEffectorLink(const std::string& end_effector_link);
646
649 bool setEndEffector(const std::string& eef_name);
650
652 void clearPoseTarget(const std::string& end_effector_link = "");
653
655 void clearPoseTargets();
656
663 const geometry_msgs::msg::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
664
670 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
671
677 const std::string& getEndEffectorLink() const;
678
684 const std::string& getEndEffector() const;
685
688 const std::string& getPoseReferenceFrame() const;
689
701
706 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient() const;
707
713
718
725 moveit::core::MoveItErrorCode asyncExecute(const Plan& plan,
726 const std::vector<std::string>& controllers = std::vector<std::string>());
727
734 moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
735 const std::vector<std::string>& controllers = std::vector<std::string>());
736
743 moveit::core::MoveItErrorCode execute(const Plan& plan,
744 const std::vector<std::string>& controllers = std::vector<std::string>());
745
752 moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory,
753 const std::vector<std::string>& controllers = std::vector<std::string>());
754
764 [[deprecated("Drop jump_threshold")]] double //
765 computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
766 double /*jump_threshold*/, moveit_msgs::msg::RobotTrajectory& trajectory,
767 bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr)
768 {
769 return computeCartesianPath(waypoints, eef_step, trajectory, avoid_collisions, error_code);
770 }
771 double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
772 moveit_msgs::msg::RobotTrajectory& trajectory, bool avoid_collisions = true,
773 moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr);
774
787 [[deprecated("Drop jump_threshold")]] double //
788 computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
789 double /*jump_threshold*/, moveit_msgs::msg::RobotTrajectory& trajectory,
790 const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true,
791 moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr)
792 {
793 return computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, error_code);
794 }
795 double computeCartesianPath(const std::vector<geometry_msgs::msg::Pose>& waypoints, double eef_step,
796 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
801 void stop();
802
804 void allowReplanning(bool flag);
805
807 void setReplanAttempts(int32_t attempts);
808
810 void setReplanDelay(double delay);
811
814 void allowLooking(bool flag);
815
817 void setLookAroundAttempts(int32_t attempts);
818
825 void constructRobotState(moveit_msgs::msg::RobotState& state);
826
829 void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request);
830
844 bool attachObject(const std::string& object, const std::string& link = "");
845
854 bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
855
861 bool detachObject(const std::string& name = "");
862
875 bool startStateMonitor(double wait = 1.0);
876
878 std::vector<double> getCurrentJointValues() const;
879
881 moveit::core::RobotStatePtr getCurrentState(double wait = 1) const;
882
886 geometry_msgs::msg::PoseStamped getCurrentPose(const std::string& end_effector_link = "") const;
887
891 std::vector<double> getCurrentRPY(const std::string& end_effector_link = "") const;
892
894 std::vector<double> getRandomJointValues() const;
895
899 geometry_msgs::msg::PoseStamped getRandomPose(const std::string& end_effector_link = "") const;
900
912 void rememberJointValues(const std::string& name);
913
918 void rememberJointValues(const std::string& name, const std::vector<double>& values);
919
921 const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
922 {
923 return remembered_joint_values_;
924 }
925
927 void forgetJointValues(const std::string& name);
928
937 void setConstraintsDatabase(const std::string& host, unsigned int port);
938
940 std::vector<std::string> getKnownConstraints() const;
941
945 moveit_msgs::msg::Constraints getPathConstraints() const;
946
950 bool setPathConstraints(const std::string& constraint);
951
955 void setPathConstraints(const moveit_msgs::msg::Constraints& constraint);
956
959 void clearPathConstraints();
960
961 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const;
962 void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& constraint);
963 void clearTrajectoryConstraints();
964
967protected:
969 const moveit::core::RobotState& getTargetRobotState() const;
970
971private:
972 std::map<std::string, std::vector<double> > remembered_joint_values_;
973 class MoveGroupInterfaceImpl;
974 MoveGroupInterfaceImpl* impl_;
975 rclcpp::Logger logger_;
976};
977} // namespace planning_interface
978} // 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.