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>
52 #include <moveit_msgs/msg/motion_plan_request.hpp>
53 #include <geometry_msgs/msg/pose_stamped.hpp>
55 #include <rclcpp_action/rclcpp_action.hpp>
59 #include <tf2_ros/buffer.h>
61 #include <moveit_move_group_interface_export.h>
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))
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));
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));
157 const std::string& getName()
const;
161 const std::vector<std::string>& getNamedTargets()
const;
164 const std::shared_ptr<tf2_ros::Buffer>& getTF()
const;
167 moveit::core::RobotModelConstPtr getRobotModel()
const;
170 const rclcpp::Node::SharedPtr& getNode()
const;
173 const std::string& getPlanningFrame()
const;
176 const std::vector<std::string>& getJointModelGroupNames()
const;
179 const std::vector<std::string>& getJointNames()
const;
182 const std::vector<std::string>& getLinkNames()
const;
185 std::map<std::string, double> getNamedTargetValues(
const std::string&
name)
const;
188 const std::vector<std::string>& getActiveJoints()
const;
191 const std::vector<std::string>& getJoints()
const;
195 unsigned int getVariableCount()
const;
198 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
const;
201 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc)
const;
204 std::map<std::string, std::string> getPlannerParams(
const std::string& planner_id,
205 const std::string& group =
"")
const;
208 void setPlannerParams(
const std::string& planner_id,
const std::string& group,
209 const std::map<std::string, std::string>& params,
bool bReplace =
false);
211 std::string getDefaultPlanningPipelineId()
const;
214 void setPlanningPipelineId(
const std::string& pipeline_id);
217 const std::string& getPlanningPipelineId()
const;
220 std::string getDefaultPlannerId(
const std::string& group =
"")
const;
223 void setPlannerId(
const std::string& planner_id);
226 const std::string& getPlannerId()
const;
229 void setPlanningTime(
double seconds);
233 void setNumPlanningAttempts(
unsigned int num_planning_attempts);
240 void setMaxVelocityScalingFactor(
double max_velocity_scaling_factor);
243 double getMaxVelocityScalingFactor()
const;
250 void setMaxAccelerationScalingFactor(
double max_acceleration_scaling_factor);
253 double getMaxAccelerationScalingFactor()
const;
256 double getPlanningTime()
const;
260 double getGoalJointTolerance()
const;
264 double getGoalPositionTolerance()
const;
268 double getGoalOrientationTolerance()
const;
276 void setGoalTolerance(
double tolerance);
280 void setGoalJointTolerance(
double tolerance);
283 void setGoalPositionTolerance(
double tolerance);
286 void setGoalOrientationTolerance(
double tolerance);
292 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz);
296 void setStartState(
const moveit_msgs::msg::RobotState& start_state);
303 void setStartStateToCurrentState();
334 bool setJointValueTarget(
const std::vector<double>& group_variable_values);
351 bool setJointValueTarget(
const std::map<std::string, double>& variable_values);
368 bool setJointValueTarget(
const std::vector<std::string>& variable_names,
const std::vector<double>& variable_values);
392 bool setJointValueTarget(
const std::string& joint_name,
const std::vector<double>& values);
405 bool setJointValueTarget(
const std::string& joint_name,
double value);
417 bool setJointValueTarget(
const sensor_msgs::msg::JointState& state);
430 bool setJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
const std::string& end_effector_link =
"");
443 bool setJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
const std::string& end_effector_link =
"");
456 bool setJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
468 bool setApproximateJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
469 const std::string& end_effector_link =
"");
481 bool setApproximateJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
482 const std::string& end_effector_link =
"");
494 bool setApproximateJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
500 void setRandomTarget();
504 bool setNamedTarget(
const std::string&
name);
507 void getJointValueTarget(std::vector<double>& group_variable_values)
const;
530 bool setPositionTarget(
double x,
double y,
double z,
const std::string& end_effector_link =
"");
539 bool setRPYTarget(
double roll,
double pitch,
double yaw,
const std::string& end_effector_link =
"");
549 bool setOrientationTarget(
double x,
double y,
double z,
double w,
const std::string& end_effector_link =
"");
558 bool setPoseTarget(
const Eigen::Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
567 bool setPoseTarget(
const geometry_msgs::msg::Pose& target,
const std::string& end_effector_link =
"");
576 bool setPoseTarget(
const geometry_msgs::msg::PoseStamped& target,
const std::string& end_effector_link =
"");
596 bool setPoseTargets(
const EigenSTL::vector_Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
616 bool setPoseTargets(
const std::vector<geometry_msgs::msg::Pose>& target,
const std::string& end_effector_link =
"");
636 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& target,
637 const std::string& end_effector_link =
"");
640 void setPoseReferenceFrame(
const std::string& pose_reference_frame);
645 bool setEndEffectorLink(
const std::string& end_effector_link);
649 bool setEndEffector(
const std::string& eef_name);
652 void clearPoseTarget(
const std::string& end_effector_link =
"");
655 void clearPoseTargets();
663 const geometry_msgs::msg::PoseStamped& getPoseTarget(
const std::string& end_effector_link =
"")
const;
670 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(
const std::string& end_effector_link =
"")
const;
677 const std::string& getEndEffectorLink()
const;
684 const std::string& getEndEffector()
const;
688 const std::string& getPoseReferenceFrame()
const;
706 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient()
const;
726 const std::vector<std::string>& controllers = std::vector<std::string>());
735 const std::vector<std::string>& controllers = std::vector<std::string>());
744 const std::vector<std::string>& controllers = std::vector<std::string>());
753 const std::vector<std::string>& controllers = std::vector<std::string>());
764 [[deprecated(
"Drop jump_threshold")]]
double
766 double , moveit_msgs::msg::RobotTrajectory& trajectory,
767 bool avoid_collisions =
true, moveit_msgs::msg::MoveItErrorCodes* error_code =
nullptr)
769 return computeCartesianPath(waypoints, eef_step, trajectory, avoid_collisions, error_code);
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);
787 [[deprecated(
"Drop jump_threshold")]]
double
789 double , 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)
793 return computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, error_code);
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);
804 void allowReplanning(
bool flag);
807 void setReplanAttempts(int32_t attempts);
810 void setReplanDelay(
double delay);
814 void allowLooking(
bool flag);
817 void setLookAroundAttempts(int32_t attempts);
825 void constructRobotState(moveit_msgs::msg::RobotState& state);
844 bool attachObject(
const std::string&
object,
const std::string& link =
"");
854 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links);
861 bool detachObject(
const std::string&
name =
"");
875 bool startStateMonitor(
double wait = 1.0);
878 std::vector<double> getCurrentJointValues()
const;
881 moveit::core::RobotStatePtr getCurrentState(
double wait = 1)
const;
886 geometry_msgs::msg::PoseStamped getCurrentPose(
const std::string& end_effector_link =
"")
const;
891 std::vector<double> getCurrentRPY(
const std::string& end_effector_link =
"")
const;
894 std::vector<double> getRandomJointValues()
const;
899 geometry_msgs::msg::PoseStamped getRandomPose(
const std::string& end_effector_link =
"")
const;
912 void rememberJointValues(
const std::string&
name);
918 void rememberJointValues(
const std::string&
name,
const std::vector<double>& values);
923 return remembered_joint_values_;
927 void forgetJointValues(
const std::string&
name);
937 void setConstraintsDatabase(
const std::string& host,
unsigned int port);
940 std::vector<std::string> getKnownConstraints()
const;
945 moveit_msgs::msg::Constraints getPathConstraints()
const;
950 bool setPathConstraints(
const std::string& constraint);
955 void setPathConstraints(
const moveit_msgs::msg::Constraints& constraint);
959 void clearPathConstraints();
961 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints()
const;
962 void setTrajectoryConstraints(
const moveit_msgs::msg::TrajectoryConstraints& constraint);
963 void clearTrajectoryConstraints();
972 std::map<std::string, std::vector<double> > remembered_joint_values_;
973 class MoveGroupInterfaceImpl;
974 MoveGroupInterfaceImpl* impl_;
975 rclcpp::Logger logger_;
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'.
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
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.
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.
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 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.