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))
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));
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));
164 const std::string& getName()
const;
168 const std::vector<std::string>& getNamedTargets()
const;
171 const std::shared_ptr<tf2_ros::Buffer>& getTF()
const;
174 moveit::core::RobotModelConstPtr getRobotModel()
const;
177 const rclcpp::Node::SharedPtr& getNode()
const;
180 const std::string& getPlanningFrame()
const;
183 const std::vector<std::string>& getJointModelGroupNames()
const;
186 const std::vector<std::string>& getJointNames()
const;
189 const std::vector<std::string>& getLinkNames()
const;
192 std::map<std::string, double> getNamedTargetValues(
const std::string& name)
const;
195 const std::vector<std::string>& getActiveJoints()
const;
198 const std::vector<std::string>& getJoints()
const;
202 unsigned int getVariableCount()
const;
205 bool getInterfaceDescriptions(std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
const;
208 bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc)
const;
211 std::map<std::string, std::string> getPlannerParams(
const std::string& planner_id,
212 const std::string& group =
"")
const;
215 void setPlannerParams(
const std::string& planner_id,
const std::string& group,
216 const std::map<std::string, std::string>& params,
bool bReplace =
false);
218 std::string getDefaultPlanningPipelineId()
const;
221 void setPlanningPipelineId(
const std::string& pipeline_id);
224 const std::string& getPlanningPipelineId()
const;
227 std::string getDefaultPlannerId(
const std::string& group =
"")
const;
230 void setPlannerId(
const std::string& planner_id);
233 const std::string& getPlannerId()
const;
236 void setPlanningTime(
double seconds);
240 void setNumPlanningAttempts(
unsigned int num_planning_attempts);
247 void setMaxVelocityScalingFactor(
double max_velocity_scaling_factor);
250 double getMaxVelocityScalingFactor()
const;
257 void setMaxAccelerationScalingFactor(
double max_acceleration_scaling_factor);
260 double getMaxAccelerationScalingFactor()
const;
263 double getPlanningTime()
const;
267 double getGoalJointTolerance()
const;
271 double getGoalPositionTolerance()
const;
275 double getGoalOrientationTolerance()
const;
283 void setGoalTolerance(
double tolerance);
287 void setGoalJointTolerance(
double tolerance);
290 void setGoalPositionTolerance(
double tolerance);
293 void setGoalOrientationTolerance(
double tolerance);
299 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz);
303 void setStartState(
const moveit_msgs::msg::RobotState& start_state);
310 void setStartStateToCurrentState();
341 bool setJointValueTarget(
const std::vector<double>& group_variable_values);
358 bool setJointValueTarget(
const std::map<std::string, double>& variable_values);
375 bool setJointValueTarget(
const std::vector<std::string>& variable_names,
const std::vector<double>& variable_values);
399 bool setJointValueTarget(
const std::string& joint_name,
const std::vector<double>& values);
412 bool setJointValueTarget(
const std::string& joint_name,
double value);
424 bool setJointValueTarget(
const sensor_msgs::msg::JointState& state);
437 bool setJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
const std::string& end_effector_link =
"");
450 bool setJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
const std::string& end_effector_link =
"");
463 bool setJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
475 bool setApproximateJointValueTarget(
const geometry_msgs::msg::Pose& eef_pose,
476 const std::string& end_effector_link =
"");
488 bool setApproximateJointValueTarget(
const geometry_msgs::msg::PoseStamped& eef_pose,
489 const std::string& end_effector_link =
"");
501 bool setApproximateJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
507 void setRandomTarget();
511 bool setNamedTarget(
const std::string& name);
514 void getJointValueTarget(std::vector<double>& group_variable_values)
const;
537 bool setPositionTarget(
double x,
double y,
double z,
const std::string& end_effector_link =
"");
546 bool setRPYTarget(
double roll,
double pitch,
double yaw,
const std::string& end_effector_link =
"");
556 bool setOrientationTarget(
double x,
double y,
double z,
double w,
const std::string& end_effector_link =
"");
565 bool setPoseTarget(
const Eigen::Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
574 bool setPoseTarget(
const geometry_msgs::msg::Pose& target,
const std::string& end_effector_link =
"");
583 bool setPoseTarget(
const geometry_msgs::msg::PoseStamped& target,
const std::string& end_effector_link =
"");
603 bool setPoseTargets(
const EigenSTL::vector_Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
623 bool setPoseTargets(
const std::vector<geometry_msgs::msg::Pose>& target,
const std::string& end_effector_link =
"");
643 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& target,
644 const std::string& end_effector_link =
"");
647 void setPoseReferenceFrame(
const std::string& pose_reference_frame);
652 bool setEndEffectorLink(
const std::string& end_effector_link);
656 bool setEndEffector(
const std::string& eef_name);
659 void clearPoseTarget(
const std::string& end_effector_link =
"");
662 void clearPoseTargets();
670 const geometry_msgs::msg::PoseStamped& getPoseTarget(
const std::string& end_effector_link =
"")
const;
677 const std::vector<geometry_msgs::msg::PoseStamped>& getPoseTargets(
const std::string& end_effector_link =
"")
const;
684 const std::string& getEndEffectorLink()
const;
691 const std::string& getEndEffector()
const;
695 const std::string& getPoseReferenceFrame()
const;
713 rclcpp_action::Client<moveit_msgs::action::MoveGroup>& getMoveGroupClient()
const;
733 const std::vector<std::string>& controllers = std::vector<std::string>());
742 const std::vector<std::string>& controllers = std::vector<std::string>());
751 const std::vector<std::string>& controllers = std::vector<std::string>());
760 const std::vector<std::string>& controllers = std::vector<std::string>());
771 [[deprecated(
"Drop jump_threshold")]]
double
773 double , moveit_msgs::msg::RobotTrajectory& trajectory,
774 bool avoid_collisions =
true, moveit_msgs::msg::MoveItErrorCodes* error_code =
nullptr)
776 return computeCartesianPath(waypoints, eef_step, trajectory, avoid_collisions, error_code);
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);
794 [[deprecated(
"Drop jump_threshold")]]
double
796 double , 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)
800 return computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, error_code);
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);
811 void allowReplanning(
bool flag);
814 void setReplanAttempts(int32_t attempts);
817 void setReplanDelay(
double delay);
821 void allowLooking(
bool flag);
824 void setLookAroundAttempts(int32_t attempts);
832 void constructRobotState(moveit_msgs::msg::RobotState& state);
836 void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest& request);
851 bool attachObject(
const std::string&
object,
const std::string& link =
"");
861 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links);
868 bool detachObject(
const std::string& name =
"");
882 bool startStateMonitor(
double wait = 1.0);
885 std::vector<double> getCurrentJointValues()
const;
888 moveit::core::RobotStatePtr getCurrentState(
double wait = 1)
const;
893 geometry_msgs::msg::PoseStamped getCurrentPose(
const std::string& end_effector_link =
"")
const;
898 std::vector<double> getCurrentRPY(
const std::string& end_effector_link =
"")
const;
901 std::vector<double> getRandomJointValues()
const;
906 geometry_msgs::msg::PoseStamped getRandomPose(
const std::string& end_effector_link =
"")
const;
919 void rememberJointValues(
const std::string& name);
925 void rememberJointValues(
const std::string& name,
const std::vector<double>& values);
930 return remembered_joint_values_;
934 void forgetJointValues(
const std::string& name);
944 void setConstraintsDatabase(
const std::string& host,
unsigned int port);
947 std::vector<std::string> getKnownConstraints()
const;
952 moveit_msgs::msg::Constraints getPathConstraints()
const;
957 bool setPathConstraints(
const std::string& constraint);
962 void setPathConstraints(
const moveit_msgs::msg::Constraints& constraint);
966 void clearPathConstraints();
968 moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints()
const;
969 void setTrajectoryConstraints(
const moveit_msgs::msg::TrajectoryConstraints& constraint);
970 void clearTrajectoryConstraints();
979 std::map<std::string, std::vector<double> > remembered_joint_values_;
980 class MoveGroupInterfaceImpl;
981 MoveGroupInterfaceImpl* impl_;
982 rclcpp::Logger logger_;