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>
51 #include <moveit_msgs/msg/motion_plan_request.hpp>
52 #include <geometry_msgs/msg/pose_stamped.hpp>
54 #include <rclcpp_action/rclcpp_action.hpp>
58 #include <tf2_ros/buffer.h>
60 #include <moveit_move_group_interface_export.h>
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))
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));
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));
158 const std::string& getName()
const;
162 const std::vector<std::string>& getNamedTargets()
const;
165 moveit::core::RobotModelConstPtr getRobotModel()
const;
171 const std::string& getPlanningFrame()
const;
174 const std::vector<std::string>& getJointModelGroupNames()
const;
177 const std::vector<std::string>& getJointNames()
const;
180 const std::vector<std::string>& getLinkNames()
const;
183 std::map<std::string, double> getNamedTargetValues(
const std::string&
name)
const;
186 const std::vector<std::string>& getActiveJoints()
const;
189 const std::vector<std::string>& getJoints()
const;
193 unsigned int getVariableCount()
const;
196 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
const;
199 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc)
const;
202 std::map<std::string, std::string> getPlannerParams(
const std::string& planner_id,
203 const std::string&
group =
"")
const;
206 void setPlannerParams(
const std::string& planner_id,
const std::string&
group,
207 const std::map<std::string, std::string>& params,
bool bReplace =
false);
209 std::string getDefaultPlanningPipelineId()
const;
212 void setPlanningPipelineId(
const std::string& pipeline_id);
215 const std::string& getPlanningPipelineId()
const;
218 std::string getDefaultPlannerId(
const std::string&
group =
"")
const;
221 void setPlannerId(
const std::string& planner_id);
224 const std::string& getPlannerId()
const;
227 void setPlanningTime(
double seconds);
231 void setNumPlanningAttempts(
unsigned int num_planning_attempts);
238 void setMaxVelocityScalingFactor(
double max_velocity_scaling_factor);
245 void setMaxAccelerationScalingFactor(
double max_acceleration_scaling_factor);
248 double getPlanningTime()
const;
252 double getGoalJointTolerance()
const;
256 double getGoalPositionTolerance()
const;
260 double getGoalOrientationTolerance()
const;
268 void setGoalTolerance(
double tolerance);
272 void setGoalJointTolerance(
double tolerance);
275 void setGoalPositionTolerance(
double tolerance);
278 void setGoalOrientationTolerance(
double tolerance);
284 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz);
288 void setStartState(
const moveit_msgs::msg::RobotState& start_state);
295 void setStartStateToCurrentState();
299 void setSupportSurfaceName(
const std::string&
name);
330 bool setJointValueTarget(
const std::vector<double>& group_variable_values);
347 bool setJointValueTarget(
const std::map<std::string, double>& variable_values);
364 bool setJointValueTarget(
const std::vector<std::string>& variable_names,
const std::vector<double>& variable_values);
388 bool setJointValueTarget(
const std::string& joint_name,
const std::vector<double>& values);
401 bool setJointValueTarget(
const std::string& joint_name,
double value);
413 bool setJointValueTarget(
const sensor_msgs::msg::JointState& state);
426 bool setJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
const std::string& end_effector_link =
"");
439 bool setJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
const std::string& end_effector_link =
"");
452 bool setJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
464 bool setApproximateJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
465 const std::string& end_effector_link =
"");
477 bool setApproximateJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
478 const std::string& end_effector_link =
"");
490 bool setApproximateJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
496 void setRandomTarget();
500 bool setNamedTarget(
const std::string&
name);
503 void getJointValueTarget(std::vector<double>& group_variable_values)
const;
529 bool setPositionTarget(
double x,
double y,
double z,
const std::string& end_effector_link =
"");
538 bool setRPYTarget(
double roll,
double pitch,
double yaw,
const std::string& end_effector_link =
"");
548 bool setOrientationTarget(
double x,
double y,
double z,
double w,
const std::string& end_effector_link =
"");
557 bool setPoseTarget(
const Eigen::Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
566 bool setPoseTarget(
const geometry_msgs::msg::Pose& target,
const std::string& end_effector_link =
"");
575 bool setPoseTarget(
const geometry_msgs::msg::PoseStamped& target,
const std::string& end_effector_link =
"");
595 bool setPoseTargets(
const EigenSTL::vector_Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
615 bool setPoseTargets(
const std::vector<geometry_msgs::msg::Pose>& target,
const std::string& end_effector_link =
"");
635 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& target,
636 const std::string& end_effector_link =
"");
639 void setPoseReferenceFrame(
const std::string& pose_reference_frame);
644 bool setEndEffectorLink(
const std::string& end_effector_link);
648 bool setEndEffector(
const std::string& eef_name);
651 void clearPoseTarget(
const std::string& end_effector_link =
"");
654 void clearPoseTargets();
662 const geometry_msgs::msg::PoseStamped& getPoseTarget(
const std::string& end_effector_link =
"")
const;
669 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(
const std::string& end_effector_link =
"")
const;
676 const std::string& getEndEffectorLink()
const;
683 const std::string& getEndEffector()
const;
687 const std::string& getPoseReferenceFrame()
const;
705 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient()
const;
725 const std::vector<std::string>& controllers = std::vector<std::string>());
734 const std::vector<std::string>& controllers = std::vector<std::string>());
743 const std::vector<std::string>& controllers = std::vector<std::string>());
752 const std::vector<std::string>& controllers = std::vector<std::string>());
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);
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);
788 void allowReplanning(
bool flag);
791 void setReplanAttempts(int32_t attempts);
794 void setReplanDelay(
double delay);
798 void allowLooking(
bool flag);
801 void setLookAroundAttempts(int32_t attempts);
820 bool attachObject(
const std::string&
object,
const std::string& link =
"");
830 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links);
837 bool detachObject(
const std::string&
name =
"");
851 bool startStateMonitor(
double wait = 1.0);
854 std::vector<double> getCurrentJointValues()
const;
857 moveit::core::RobotStatePtr getCurrentState(
double wait = 1)
const;
862 geometry_msgs::msg::PoseStamped getCurrentPose(
const std::string& end_effector_link =
"")
const;
867 std::vector<double> getCurrentRPY(
const std::string& end_effector_link =
"")
const;
870 std::vector<double> getRandomJointValues()
const;
875 geometry_msgs::msg::PoseStamped getRandomPose(
const std::string& end_effector_link =
"")
const;
888 void rememberJointValues(
const std::string&
name);
894 void rememberJointValues(
const std::string&
name,
const std::vector<double>& values);
899 return remembered_joint_values_;
903 void forgetJointValues(
const std::string&
name);
913 void setConstraintsDatabase(
const std::string& host,
unsigned int port);
916 std::vector<std::string> getKnownConstraints()
const;
921 moveit_msgs::msg::Constraints getPathConstraints()
const;
926 bool setPathConstraints(
const std::string& constraint);
931 void setPathConstraints(
const moveit_msgs::msg::Constraints& constraint);
935 void clearPathConstraints();
937 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints()
const;
938 void setTrajectoryConstraints(
const moveit_msgs::msg::TrajectoryConstraints& constraint);
939 void clearTrajectoryConstraints();
948 std::map<std::string, std::vector<double> > remembered_joint_values_;
949 class MoveGroupInterfaceImpl;
950 MoveGroupInterfaceImpl* impl_;
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.
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
MOVEIT_STRUCT_FORWARD(Plan)
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.
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
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.