Deprecated Client interface to access interfaces of the move_group node. More...
#include <move_group.h>
Additional Inherited Members | |
Public Member Functions inherited from moveit::planning_interface::MoveGroupInterface | |
const std::vector< std::string > & | getActiveJoints () const |
Get only the active (actuated) joints this instance operates on. More... | |
std::string | getDefaultPlannerId (const std::string &group="") const |
Get the default planner for a given group (or global default) More... | |
double | getGoalJointTolerance () const |
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configuration space. More... | |
double | getGoalOrientationTolerance () const |
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll, pitch and yaw, in radians. More... | |
double | getGoalPositionTolerance () const |
Get the tolerance that is used for reaching a position goal. This is be the radius of a sphere where the end-effector must reach. More... | |
bool | getInterfaceDescription (moveit_msgs::PlannerInterfaceDescription &desc) |
Get the description of the planning plugin loaded by the action server. More... | |
const std::vector< std::string > & | getJointNames () |
Get vector of names of joints available in move group. More... | |
const std::vector< std::string > & | getJoints () const |
Get all the joints this instance operates on (including fixed joints) More... | |
const std::vector< std::string > & | getLinkNames () |
Get vector of names of links available in move group. More... | |
const std::string & | getName () const |
Get the name of the group this instance operates on. More... | |
const std::vector< std::string > | getNamedTargets () |
Get the names of the named robot states available as targets, both either remembered states or default states from srdf. More... | |
std::map< std::string, double > | getNamedTargetValues (const std::string &name) |
Get the joint angles for targets specified by name. More... | |
const ros::NodeHandle & | getNodeHandle () const |
Get the ROS node handle of this instance operates on. More... | |
const std::string & | getPlannerId () const |
Get the current planner_id. More... | |
std::map< std::string, std::string > | getPlannerParams (const std::string &planner_id, const std::string &group="") |
Get the planner parameters for given group and planner_id. More... | |
const std::string & | getPlanningFrame () const |
Get the name of the frame in which the robot is planning. More... | |
double | getPlanningTime () const |
Get the number of seconds set by setPlanningTime() More... | |
robot_model::RobotModelConstPtr | getRobotModel () const |
Get the RobotModel object. More... | |
unsigned int | getVariableCount () const |
Get the number of variables used to describe the state of this group. This is larger or equal to the number of DOF. More... | |
MoveGroupInterface (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration()) | |
Construct a MoveGroupInterface instance call using a specified set of options opt. More... | |
MOVEIT_DEPRECATED | MoveGroupInterface (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf, const ros::Duration &wait_for_servers) |
MoveGroupInterface (const std::string &group, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration()) | |
Construct a client for the MoveGroup action for a particular group. More... | |
MOVEIT_DEPRECATED | MoveGroupInterface (const std::string &group, const boost::shared_ptr< tf::Transformer > &tf, const ros::Duration &wait_for_servers) |
MoveGroupInterface (const MoveGroupInterface &)=delete | |
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy. Pass by references, move it, or simply create multiple instances where required. More... | |
MoveGroupInterface (MoveGroupInterface &&other) | |
MOVEIT_STRUCT_FORWARD (Plan) | |
MoveGroupInterface & | operator= (const MoveGroupInterface &)=delete |
MoveGroupInterface & | operator= (MoveGroupInterface &&other) |
void | setGoalJointTolerance (double tolerance) |
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint value target. More... | |
void | setGoalOrientationTolerance (double tolerance) |
Set the orientation tolerance that is used for reaching the goal when moving to a pose. More... | |
void | setGoalPositionTolerance (double tolerance) |
Set the position tolerance that is used for reaching the goal when moving to a pose. More... | |
void | setGoalTolerance (double tolerance) |
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance for each joint, in the configuration space (radians or meters depending on joint type). For pose goals this will be the radius of a sphere where the end-effector must reach. This function simply triggers calls to setGoalPositionTolerance(), setGoalOrientationTolerance() and setGoalJointTolerance(). More... | |
void | setMaxAccelerationScalingFactor (double max_acceleration_scaling_factor) |
Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1]. The maximum joint acceleration specified in the robot model is multiplied by the factor. If outside valid range (imporantly, this includes it being set to 0.0), the factor is set to a default value of 1.0 internally (i.e. maximum joint acceleration) More... | |
void | setMaxVelocityScalingFactor (double max_velocity_scaling_factor) |
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1]. The maximum joint velocity specified in the robot model is multiplied by the factor. If outside valid range (imporantly, this includes it being set to 0.0), the factor is set to a default value of 1.0 internally (i.e. maximum joint velocity) More... | |
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 is returned. The default value is 1. More... | |
void | setPlannerId (const std::string &planner_id) |
Specify a planner to be used for further planning. More... | |
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. More... | |
void | setPlanningTime (double seconds) |
Specify the maximum amount of time to use when planning. More... | |
void | setStartState (const moveit_msgs::RobotState &start_state) |
If a different start state should be considered instead of the current state of the robot, this function sets that state. More... | |
void | setStartState (const robot_state::RobotState &start_state) |
If a different start state should be considered instead of the current state of the robot, this function sets that state. More... | |
void | setStartStateToCurrentState () |
Set the starting state for planning to be that reported by the robot's joint state publication. More... | |
void | setSupportSurfaceName (const std::string &name) |
For pick/place operations, the name of the support surface is used to specify the fact that attached objects are allowed to touch the support surface. More... | |
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.e. relative to the robot root link start position). This is useful when the planning group contains the root joint of the robot – i.e. when planning motion for the robot relative to the world. More... | |
~MoveGroupInterface () | |
bool | setJointValueTarget (const std::vector< double > &group_variable_values) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const std::map< std::string, double > &variable_values) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const robot_state::RobotState &robot_state) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const std::string &joint_name, const std::vector< double > &values) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const std::string &joint_name, double value) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const sensor_msgs::JointState &state) |
Set the JointValueTarget and use it for future planning requests. More... | |
bool | setJointValueTarget (const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link="") |
Set the joint state goal for a particular joint by computing IK. More... | |
bool | setJointValueTarget (const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link="") |
Set the joint state goal for a particular joint by computing IK. More... | |
bool | setJointValueTarget (const Eigen::Affine3d &eef_pose, const std::string &end_effector_link="") |
Set the joint state goal for a particular joint by computing IK. More... | |
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. More... | |
bool | setApproximateJointValueTarget (const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link="") |
Set the joint state goal for a particular joint by computing IK. More... | |
bool | setApproximateJointValueTarget (const Eigen::Affine3d &eef_pose, const std::string &end_effector_link="") |
Set the joint state goal for a particular joint by computing IK. More... | |
void | setRandomTarget () |
Set the joint state goal to a random joint configuration. More... | |
bool | setNamedTarget (const std::string &name) |
Set the current joint values to be ones previously remembered by rememberJointValues() or, if not found, that are specified in the SRDF under the name name as a group state. More... | |
const robot_state::RobotState & | getJointValueTarget () const |
Get the currently set joint state goal. More... | |
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). More... | |
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. More... | |
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,y,z,w). More... | |
bool | setPoseTarget (const Eigen::Affine3d &end_effector_pose, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. More... | |
bool | setPoseTarget (const geometry_msgs::Pose &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. More... | |
bool | setPoseTarget (const geometry_msgs::PoseStamped &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. More... | |
bool | setPoseTargets (const EigenSTL::vector_Affine3d &end_effector_pose, const std::string &end_effector_link="") |
Set goal poses for end_effector_link. More... | |
bool | setPoseTargets (const std::vector< geometry_msgs::Pose > &target, const std::string &end_effector_link="") |
Set goal poses for end_effector_link. More... | |
bool | setPoseTargets (const std::vector< geometry_msgs::PoseStamped > &target, const std::string &end_effector_link="") |
Set goal poses for end_effector_link. More... | |
void | setPoseReferenceFrame (const std::string &pose_reference_frame) |
Specify which reference frame to assume for poses specified without a reference frame. More... | |
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 target functions when end_effector_link is not explicitly specified. More... | |
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 parent link of this end effector. More... | |
void | clearPoseTarget (const std::string &end_effector_link="") |
Forget pose(s) specified for end_effector_link. More... | |
void | clearPoseTargets () |
Forget any poses specified for all end-effectors. More... | |
const geometry_msgs::PoseStamped & | getPoseTarget (const std::string &end_effector_link="") const |
const std::vector< geometry_msgs::PoseStamped > & | getPoseTargets (const std::string &end_effector_link="") const |
const std::string & | getEndEffectorLink () const |
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly by setEndEffector()). If setEndEffectorLink() was not called, this function reports the link name that serves as parent of an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no such link is known, the empty string is returned. More... | |
const std::string & | getEndEffector () const |
Get the current end-effector name. This returns the value set by setEndEffector() (or indirectly by setEndEffectorLink()). If setEndEffector() was not called, this function reports an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no end-effector is known, the empty string is returned. More... | |
const std::string & | getPoseReferenceFrame () const |
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the robot model. More... | |
MoveItErrorCode | asyncMove () |
Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target. This call is not blocking (does not wait for the execution of the trajectory to complete). More... | |
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > & | getMoveGroupClient () const |
Get the move_group action client used by the MoveGroupInterface. The client can be used for querying the execution state of the trajectory and abort trajectory execution during asynchronous execution. More... | |
MoveItErrorCode | move () |
Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified target. This call is always blocking (waits for the execution of the trajectory to complete) and requires an asynchronous spinner to be started. More... | |
MoveItErrorCode | plan (Plan &plan) |
Compute a motion plan that takes the group declared in the constructor from the current state to the specified target. No execution is performed. The resulting plan is stored in plan. More... | |
MoveItErrorCode | asyncExecute (const Plan &plan) |
Given a plan, execute it without waiting for completion. Return true on success. More... | |
MoveItErrorCode | execute (const Plan &plan) |
Given a plan, execute it while waiting for completion. Return true on success. More... | |
double | computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=NULL) |
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters between end effector configurations of consecutive points in the result trajectory. The reference frame for the waypoints is that specified by setPoseReferenceFrame(). No more than jump_threshold is allowed as change in distance in the configuration space of the robot (this is to prevent 'jumps' in IK solutions). Collisions are avoided if avoid_collisions is set to true. If collisions cannot be avoided, the function fails. Return a value that is between 0.0 and 1.0 indicating the fraction of the path achieved as described by the waypoints. Return -1.0 in case of error. More... | |
double | computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=NULL) |
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters between end effector configurations of consecutive points in the result trajectory. The reference frame for the waypoints is that specified by setPoseReferenceFrame(). No more than jump_threshold is allowed as change in distance in the configuration space of the robot (this is to prevent 'jumps' in IK solutions). Kinematic constraints for the path given by path_constraints will be met for every point along the trajectory, if they are not met, a partial solution will be returned. Constraints are checked (collision and kinematic) if avoid_collisions is set to true. If constraints cannot be met, the function fails. Return a value that is between 0.0 and 1.0 indicating the fraction of the path achieved as described by the waypoints. Return -1.0 in case of error. More... | |
void | stop () |
Stop any trajectory execution, if one is active. More... | |
void | allowLooking (bool flag) |
Specify whether the robot is allowed to look around before moving if it determines it should (default is true) More... | |
void | allowReplanning (bool flag) |
Specify whether the robot is allowed to replan if it detects changes in the environment. More... | |
void | constructMotionPlanRequest (moveit_msgs::MotionPlanRequest &request) |
Build the MotionPlanRequest that would be sent to the move_group action with plan() or move() and store it in request. More... | |
MoveItErrorCode | pick (const std::string &object, bool plan_only=false) |
Pick up an object. More... | |
MoveItErrorCode | pick (const std::string &object, const moveit_msgs::Grasp &grasp, bool plan_only=false) |
Pick up an object given a grasp pose. More... | |
MoveItErrorCode | pick (const std::string &object, const std::vector< moveit_msgs::Grasp > &grasps, bool plan_only=false) |
Pick up an object given possible grasp poses. More... | |
MoveItErrorCode | planGraspsAndPick (const std::string &object="", bool plan_only=false) |
Pick up an object. More... | |
MoveItErrorCode | planGraspsAndPick (const moveit_msgs::CollisionObject &object, bool plan_only=false) |
Pick up an object. More... | |
MoveItErrorCode | place (const std::string &object, bool plan_only=false) |
Place an object somewhere safe in the world (a safe location will be detected) More... | |
MoveItErrorCode | place (const std::string &object, const std::vector< moveit_msgs::PlaceLocation > &locations, bool plan_only=false) |
Place an object at one of the specified possible locations. More... | |
MoveItErrorCode | place (const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses, bool plan_only=false) |
Place an object at one of the specified possible locations. More... | |
MoveItErrorCode | place (const std::string &object, const geometry_msgs::PoseStamped &pose, bool plan_only=false) |
Place an object at one of the specified possible location. More... | |
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. If no link name is specified, the end-effector is used. If there is no end-effector, the first link in the group is used. If the object name does not exist an error will be produced in move_group, but the request made by this interface will succeed. More... | |
bool | attachObject (const std::string &object, const std::string &link, const std::vector< std::string > &touch_links) |
Given the name of an object in the planning scene, make the object attached to a link of the robot. The set of links the object is allowed to touch without considering that a collision is specified by touch_links. If link is empty, the end-effector link is used. If there is no end-effector, the first link in the group is used. If the object name does not exist an error will be produced in move_group, but the request made by this interface will succeed. More... | |
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 link the object is attached to. If there is no name specified, and there is only one attached object, that object is detached. An error is produced if no object to detach is identified. More... | |
bool | startStateMonitor (double wait=1.0) |
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically constructed. This function allows triggering the construction of that object from the beginning, so that future calls to functions such as getCurrentState() will not take so long and are less likely to fail. More... | |
std::vector< double > | getCurrentJointValues () |
Get the current joint values for the joints planned for by this instance (see getJoints()) More... | |
robot_state::RobotStatePtr | getCurrentState (double wait=1) |
Get the current state of the robot within the duration specified by wait. More... | |
geometry_msgs::PoseStamped | getCurrentPose (const std::string &end_effector_link="") |
Get the pose for the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. More... | |
std::vector< double > | getCurrentRPY (const std::string &end_effector_link="") |
Get the roll-pitch-yaw (XYZ) for the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. More... | |
std::vector< double > | getRandomJointValues () |
Get random joint values for the joints planned for by this instance (see getJoints()) More... | |
geometry_msgs::PoseStamped | getRandomPose (const std::string &end_effector_link="") |
Get a random reachable pose for the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. More... | |
void | rememberJointValues (const std::string &name) |
Remember the current joint values (of the robot being monitored) under name. These can be used by setNamedTarget(). These values are remembered locally in the client. Other clients will not have access to them. More... | |
void | rememberJointValues (const std::string &name, const std::vector< double > &values) |
Remember the specified joint values under name. These can be used by setNamedTarget(). These values are remembered locally in the client. Other clients will not have access to them. More... | |
const std::map< std::string, std::vector< double > > & | getRememberedJointValues () const |
Get the currently remembered map of names to joint values. More... | |
void | forgetJointValues (const std::string &name) |
Forget the joint values remebered under name. More... | |
void | setConstraintsDatabase (const std::string &host, unsigned int port) |
Specify where the database server that holds known constraints resides. More... | |
std::vector< std::string > | getKnownConstraints () const |
Get the names of the known constraints as read from the Mongo database, if a connection was achieved. More... | |
moveit_msgs::Constraints | getPathConstraints () const |
Get the actual set of constraints in use with this MoveGroupInterface. More... | |
bool | setPathConstraints (const std::string &constraint) |
Specify a set of path constraints to use. The constraints are looked up by name from the Mongo database server. This replaces any path constraints set in previous calls to setPathConstraints(). More... | |
void | setPathConstraints (const moveit_msgs::Constraints &constraint) |
Specify a set of path constraints to use. This version does not require a database server. This replaces any path constraints set in previous calls to setPathConstraints(). More... | |
void | clearPathConstraints () |
Specify that no path constraints are to be used. This removes any path constraints set in previous calls to setPathConstraints(). More... | |
moveit_msgs::TrajectoryConstraints | getTrajectoryConstraints () const |
void | setTrajectoryConstraints (const moveit_msgs::TrajectoryConstraints &constraint) |
void | clearTrajectoryConstraints () |
Static Public Attributes inherited from moveit::planning_interface::MoveGroupInterface | |
static const std::string | ROBOT_DESCRIPTION |
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'. More... | |
Deprecated Client interface to access interfaces of the move_group node.
Use MoveGroupInterface instead
Definition at line 56 of file move_group.h.