Go to the documentation of this file.
43 #include <moveit_msgs/RobotTrajectory.h>
44 #include <moveit_msgs/RobotState.h>
45 #include <moveit_msgs/PlannerInterfaceDescription.h>
46 #include <moveit_msgs/Constraints.h>
47 #include <moveit_msgs/Grasp.h>
48 #include <moveit_msgs/PlaceLocation.h>
49 #include <moveit_msgs/PickupGoal.h>
50 #include <moveit_msgs/PlaceGoal.h>
51 #include <moveit_msgs/MotionPlanRequest.h>
52 #include <moveit_msgs/MoveGroupAction.h>
53 #include <geometry_msgs/PoseStamped.h>
73 class MoveGroupInterface
144 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
157 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
175 const std::string&
getName()
const;
203 const std::vector<std::string>&
getJoints()
const;
205 [[deprecated(
"use getVariableNames")]]
const std::vector<std::string>&
getJointNames()
const
239 std::map<std::string, std::string>
getPlannerParams(
const std::string& planner_id,
240 const std::string&
group =
"")
const;
244 const std::map<std::string, std::string>& params,
bool bReplace =
false);
330 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz);
334 void setStartState(
const moveit_msgs::RobotState& start_state);
410 bool setJointValueTarget(
const std::vector<std::string>& variable_names,
const std::vector<double>& variable_values);
434 bool setJointValueTarget(
const std::string& joint_name,
const std::vector<double>& values);
472 bool setJointValueTarget(
const geometry_msgs::Pose& eef_pose,
const std::string& end_effector_link =
"");
485 bool setJointValueTarget(
const geometry_msgs::PoseStamped& eef_pose,
const std::string& end_effector_link =
"");
498 bool setJointValueTarget(
const Eigen::Isometry3d& eef_pose,
const std::string& end_effector_link =
"");
523 const std::string& end_effector_link =
"");
574 bool setPositionTarget(
double x,
double y,
double z,
const std::string& end_effector_link =
"");
583 bool setRPYTarget(
double roll,
double pitch,
double yaw,
const std::string& end_effector_link =
"");
593 bool setOrientationTarget(
double x,
double y,
double z,
double w,
const std::string& end_effector_link =
"");
602 bool setPoseTarget(
const Eigen::Isometry3d& end_effector_pose,
const std::string& end_effector_link =
"");
611 bool setPoseTarget(
const geometry_msgs::Pose& target,
const std::string& end_effector_link =
"");
620 bool setPoseTarget(
const geometry_msgs::PoseStamped& target,
const std::string& end_effector_link =
"");
660 bool setPoseTargets(
const std::vector<geometry_msgs::Pose>& target,
const std::string& end_effector_link =
"");
680 bool setPoseTargets(
const std::vector<geometry_msgs::PoseStamped>& target,
const std::string& end_effector_link =
"");
706 const geometry_msgs::PoseStamped&
getPoseTarget(
const std::string& end_effector_link =
"")
const;
713 const std::vector<geometry_msgs::PoseStamped>&
getPoseTargets(
const std::string& end_effector_link =
"")
const;
782 [[deprecated(
"Drop jump_threshold")]]
double
783 computeCartesianPath(
const std::vector<geometry_msgs::Pose>& waypoints,
double eef_step,
double ,
784 moveit_msgs::RobotTrajectory& trajectory,
bool avoid_collisions =
true,
785 moveit_msgs::MoveItErrorCodes* error_code =
nullptr)
790 moveit_msgs::RobotTrajectory& trajectory,
bool avoid_collisions =
true,
791 moveit_msgs::MoveItErrorCodes* error_code =
nullptr);
805 [[deprecated(
"Drop jump_threshold")]]
double
806 computeCartesianPath(
const std::vector<geometry_msgs::Pose>& waypoints,
double eef_step,
double ,
807 moveit_msgs::RobotTrajectory& trajectory,
const moveit_msgs::Constraints& path_constraints,
808 bool avoid_collisions =
true, moveit_msgs::MoveItErrorCodes* error_code =
nullptr)
810 return computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, error_code);
813 moveit_msgs::RobotTrajectory& trajectory,
814 const moveit_msgs::Constraints& path_constraints,
bool avoid_collisions =
true,
815 moveit_msgs::MoveItErrorCodes* error_code =
nullptr);
841 moveit_msgs::PickupGoal
constructPickupGoal(
const std::string&
object, std::vector<moveit_msgs::Grasp> grasps,
842 bool plan_only)
const;
846 std::vector<moveit_msgs::PlaceLocation> locations,
bool plan_only)
const;
849 std::vector<moveit_msgs::PlaceLocation>
875 bool plan_only =
false)
904 bool plan_only =
false)
911 bool plan_only =
false)
918 bool plan_only =
false)
935 bool attachObject(
const std::string&
object,
const std::string& link =
"");
945 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links);
977 geometry_msgs::PoseStamped
getCurrentPose(
const std::string& end_effector_link =
"")
const;
982 std::vector<double>
getCurrentRPY(
const std::string& end_effector_link =
"")
const;
990 geometry_msgs::PoseStamped
getRandomPose(
const std::string& end_effector_link =
"")
const;
1064 class MoveGroupInterfaceImpl;
1065 MoveGroupInterfaceImpl*
impl_;
const std::string & getEndEffector() const
Get the current end-effector name. This returns the value set by setEndEffector() (or indirectly by s...
void setStartState(const moveit_msgs::RobotState &start_state)
If a different start state should be considered instead of the current state of the robot,...
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="") const
Get the planner parameters for given group and planner_id.
bool setPoseTarget(const Eigen::Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set the goal pose of the end-effector end_effector_link.
bool setJointValueTarget(const std::vector< double > &group_variable_values)
Set the JointValueTarget and use it for future planning requests.
std::vector< std::string > getKnownConstraints() const
Get the names of the known constraints as read from the Mongo database, if a connection was achieved.
std::string getDefaultPlanningPipelineId() const
moveit_msgs::TrajectoryConstraints getTrajectoryConstraints() const
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
const std::vector< std::string > & getJoints() const
Get names of all the joints in this group.
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > & getMoveGroupClient() const
Get the move_group action client used by the MoveGroupInterface. The client can be used for querying ...
bool startStateMonitor(double wait=1.0)
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically co...
void setGoalOrientationTolerance(double tolerance)
Set the orientation tolerance that is used for reaching the goal when moving to a pose.
bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,...
The representation of a motion plan (as ROS messasges)
void setStartStateToCurrentState()
Set the starting state for planning to be that reported by the robot's joint state publication.
moveit::core::RobotStatePtr getCurrentState(double wait=1) const
Get the current state of the robot within the duration specified by wait.
Client class to conveniently use the ROS interfaces provided by the move_group node.
void allowReplanning(bool flag)
Specify whether the robot is allowed to replan if it detects changes in the environment.
unsigned int getVariableCount() const
Get the number of variables used to describe the state of this group. This is larger or equal to the ...
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
moveit::core::MoveItErrorCode asyncExecute(const Plan &plan)
Given a plan, execute it without waiting for completion.
void forgetJointValues(const std::string &name)
Forget the joint values remembered under name.
const std::string & getPlanningFrame() const
Get the name of the frame in which the robot is planning.
void setLookAroundAttempts(int32_t attempts)
How often is the system allowed to move the camera to update environment model when looking.
void setPlannerId(const std::string &planner_id)
Specify a planner to be used for further planning.
void setGoalJointTolerance(double tolerance)
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint va...
std::vector< double > getCurrentRPY(const std::string &end_effector_link="") const
Get the roll-pitch-yaw (XYZ) for the end-effector end_effector_link. If end_effector_link is empty (t...
const std::vector< std::string > & getJointModelGroupNames() const
Get the available planning group names.
void setReplanDelay(double delay)
Sleep this duration between replanning attempts (in walltime seconds)
moveit::core::MoveItErrorCode asyncMove()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
void setRandomTarget()
Set the joint state goal to a random joint configuration.
std::vector< double > getCurrentJointValues() const
Get the current joint values for the joints planned for by this instance (see getJoints())
void setPlanningTime(double seconds)
Specify the maximum amount of time to use when planning.
void clearPathConstraints()
Specify that no path constraints are to be used. This removes any path constraints set in previous ca...
const std::string & getEndEffectorLink() const
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly ...
moveit::core::MoveItErrorCode planGraspsAndPick(const std::string &object="", bool plan_only=false)
Pick up an object.
void clearPoseTargets()
Forget any poses specified for all end-effectors.
static constexpr double DEFAULT_GOAL_POSITION_TOLERANCE
Default goal position tolerance (0.1mm) if not specified with {robot description name}_kinematics/{jo...
const std::vector< geometry_msgs::PoseStamped > & getPoseTargets(const std::string &end_effector_link="") const
moveit::core::MoveItErrorCode move()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
const moveit::core::RobotState & getTargetRobotState() const
void rememberJointValues(const std::string &name)
Remember the current joint values (of the robot being monitored) under name. These can be used by set...
static constexpr double DEFAULT_GOAL_ORIENTATION_TOLERANCE
Default goal orientation tolerance (~0.1deg) if not specified with {robot description name}_kinematic...
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > ¶ms, bool bReplace=false)
Set the planner parameters for given group and planner_id.
Specification of options to use when constructing the MoveGroupInterface class.
MOVEIT_STRUCT_FORWARD(Plan)
void setGoalPositionTolerance(double tolerance)
Set the position tolerance that is used for reaching the goal when moving to a pose.
std::map< std::string, std::vector< double > > remembered_joint_values_
void limitMaxCartesianLinkSpeed(const double max_speed, const std::string &link_name="")
Limit the maximum Cartesian speed for a given link. The unit of the speed is meter per second and mus...
Options(std::string group_name, std::string desc=ROBOT_DESCRIPTION, const ros::NodeHandle &node_handle=ros::NodeHandle())
void allowLooking(bool flag)
Specify whether the robot is allowed to look around before moving if it determines it should (default...
void setReplanAttempts(int32_t attempts)
Maximum number of replanning attempts.
std::string getDefaultPlannerId(const std::string &group="") const
Get the default planner of the current planning pipeline for the given group (or the pipeline's defau...
MOVEIT_CLASS_FORWARD(MoveGroupInterface)
const std::string & getPoseReferenceFrame() const
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the...
void setConstraintsDatabase(const std::string &host, unsigned int port)
Specify where the database server that holds known constraints resides.
void setPoseReferenceFrame(const std::string &pose_reference_frame)
Specify which reference frame to assume for poses specified without a reference frame.
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
moveit::core::MoveItErrorCode place(const std::string &object, bool plan_only=false)
Place an object somewhere safe in the world (a safe location will be detected)
geometry_msgs::PoseStamped getRandomPose(const std::string &end_effector_link="") const
Get a random reachable pose for the end-effector end_effector_link. If end_effector_link is empty (th...
moveit::core::RobotModelConstPtr robot_model_
Optionally, an instance of the RobotModel to use can be also specified.
const ros::NodeHandle & getNodeHandle() const
Get the ROS node handle of this instance operates on.
void setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,...
moveit::core::MoveItErrorCode plan(Plan &plan)
Compute a motion plan that takes the group declared in the constructor from the current state to the ...
const std::string & getName() const
Get the name of the group this instance operates on.
double computeCartesianPath(const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=nullptr)
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters...
void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0...
ros::NodeHandle node_handle_
void setGoalTolerance(double tolerance)
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance fo...
bool setApproximateJointValueTarget(const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link="")
Set the joint state goal for a particular joint by computing IK.
bool setEndEffectorLink(const std::string &end_effector_link)
Specify the parent link of the end-effector. This end_effector_link will be used in calls to pose tar...
void setPlanningPipelineId(const std::string &pipeline_id)
Specify a planning pipeline to be used for further planning.
bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians.
moveit::core::MoveItErrorCode MoveItErrorCode
std::vector< moveit_msgs::PlaceLocation > posesToPlaceLocations(const std::vector< geometry_msgs::PoseStamped > &poses) const
Convert a vector of PoseStamped to a vector of PlaceLocation.
static constexpr double DEFAULT_ALLOWED_PLANNING_TIME
Default allowed planning time (seconds)
void setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints &constraint)
bool setPathConstraints(const std::string &constraint)
Specify a set of path constraints to use. The constraints are looked up by name from the Mongo databa...
void stop()
Stop any trajectory execution, if one is active.
std::string robot_description_
The robot description parameter name (if different from default)
const geometry_msgs::PoseStamped & getPoseTarget(const std::string &end_effector_link="") const
static constexpr double DEFAULT_GOAL_JOINT_TOLERANCE
Default goal joint tolerance (0.1mm) if not specified with {robot description name}_kinematics/{joint...
moveit::core::MoveItErrorCode execute(const Plan &plan)
Given a plan, execute it while waiting for completion.
double getGoalJointTolerance() const
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configur...
void clearMaxCartesianLinkSpeed()
Clear maximum Cartesian speed of the end effector.
std::vector< double > getRandomJointValues() const
Get random joint values for the joints planned for by this instance (see getJoints())
const std::string & getPlannerId() const
Get the current planner_id.
const moveit::core::RobotState & getJointValueTarget() const
Get the currently set joint state goal, replaced by private getTargetRobotState()
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
void clearTrajectoryConstraints()
moveit_msgs::PlaceGoal constructPlaceGoal(const std::string &object, std::vector< moveit_msgs::PlaceLocation > locations, bool plan_only) const
Build a PlaceGoal for an object named object and store it in goal_out.
const std::string & getPlanningPipelineId() const
Get the current planning_pipeline_id.
const std::vector< std::string > & getNamedTargets() const
Get the names of the named robot states available as targets, both either remembered states or defaul...
bool getInterfaceDescriptions(std::vector< moveit_msgs::PlannerInterfaceDescription > &desc) const
Get the descriptions of all planning plugins loaded by the action server.
void setSupportSurfaceName(const std::string &name)
For pick/place operations, the name of the support surface is used to specify the fact that attached ...
void clearPoseTarget(const std::string &end_effector_link="")
Forget pose(s) specified for end_effector_link.
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of times the motion plan is to be computed from scratch before the shortest solution i...
const std::vector< std::string > & getVariableNames() const
Get names of degrees of freedom in this group.
moveit::core::MoveItErrorCode pick(const std::string &object, bool plan_only=false)
Pick up an object.
bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link="")
Set the goal position of the end-effector end_effector_link to be (x, y, z).
bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription &desc) const
Get the description of the default planning plugin loaded by the action server.
moveit_msgs::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.
bool attachObject(const std::string &object, const std::string &link="")
Given the name of an object in the planning scene, make the object attached to a link of the robot....
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Specify the workspace bounding box. The box is specified in the planning frame (i....
MoveGroupInterfaceImpl * impl_
moveit_msgs::Constraints getPathConstraints() const
Get the actual set of constraints in use with this MoveGroupInterface.
double getPlanningTime() const
Get the number of seconds set by setPlanningTime()
MoveGroupInterface(const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration())
Construct a MoveGroupInterface instance call using a specified set of options opt.
static constexpr int DEFAULT_NUM_PLANNING_ATTEMPTS
Default number of planning attempts.
const std::vector< std::string > & getActiveJoints() const
Get names of joints with an active (actuated) DOF in this group.
const std::vector< std::string > & getLinkNames() const
Get vector of names of links available in move group.
bool setPoseTargets(const EigenSTL::vector_Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set goal poses for end_effector_link.
bool setNamedTarget(const std::string &name)
Set the current joint values to be ones previously remembered by rememberJointValues() or,...
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
double getGoalOrientationTolerance() const
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll,...
moveit_msgs::RobotState start_state_
The full starting state used for planning.
std::map< std::string, double > getNamedTargetValues(const std::string &name) const
Get the joint angles for targets specified by name.
void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest &request)
Build the MotionPlanRequest that would be sent to the move_group action with plan() or move() and sto...
geometry_msgs::PoseStamped getCurrentPose(const std::string &end_effector_link="") const
Get the pose for the end-effector end_effector_link. If end_effector_link is empty (the default value...
bool detachObject(const std::string &name="")
Detach an object. name specifies the name of the object attached to this group, or the name of the li...
bool setEndEffector(const std::string &eef_name)
Specify the name of the end-effector to use. This is equivalent to setting the EndEffectorLink to the...
std::string group_name_
The group to construct the class instance for.
moveit_msgs::PickupGoal constructPickupGoal(const std::string &object, std::vector< moveit_msgs::Grasp > grasps, bool plan_only) const
Build a PickupGoal for an object named object and store it in goal_out.
double getGoalPositionTolerance() const
Get the tolerance that is used for reaching a position goal. This is be the radius of a sphere where ...
const std::vector< std::string > & getJointNames() const