Client class for the MoveGroup action. This class includes many default settings to make things easy to use. More...
#include <move_group.h>
Classes | |
class | MoveGroupImpl |
struct | Options |
Specification of options to use when constructing the MoveGroup client class. More... | |
struct | Plan |
The representation of a motion plan (as ROS messasges) More... | |
Public Member Functions | |
void | allowLooking (bool flag) |
Specify whether the robot is allowed to look around before moving if it determines it should (default is true) | |
void | allowReplanning (bool flag) |
Specify whether the robot is allowed to replan if it detects changes in the environment. | |
bool | asyncExecute (const Plan &plan) |
Given a plan, execute it without waiting for completion. Return true on success. | |
bool | 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). | |
void | clearPathConstraints () |
Specify that no path constraints are to be used. | |
void | clearPoseTarget (const std::string &end_effector_link="") |
Forget pose specified for the end-effector end_effector_link. | |
void | clearPoseTargets () |
Forget any poses specified for any end-effector. | |
double | computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true) |
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. | |
bool | execute (const Plan &plan) |
Given a plan, execute it while waiting for completion. Return true on success. | |
void | forgetJointValues (const std::string &name) |
Forget the joint values remebered under name. | |
std::vector< double > | getCurrentJointValues () |
Get the current joint values for the joints planned for by this instance (see getJoints()) | |
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. | |
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. | |
robot_state::RobotStatePtr | getCurrentState () |
Get the current state of the robot. | |
const std::string & | getEndEffector () const |
Get the current end-effector name. This returns the value set by setEndEffector(). 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. | |
const std::string & | getEndEffectorLink () const |
Get the current end-effector link. This returns the value set by setEndEffectorLink(). 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. | |
double | getGoalJointTolerance () const |
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configuration space. | |
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. | |
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. | |
bool | getInterfaceDescription (moveit_msgs::PlannerInterfaceDescription &desc) |
Get the description of the planning plugin loaded by the action server. | |
const std::vector< std::string > & | getJoints () const |
Get the joints this instance operates on. | |
const robot_state::JointStateGroup & | getJointValueTarget () const |
Get the currently set joint state goal. | |
std::vector< std::string > | getKnownConstraints () const |
Get the names of the constraints known (as read from the warehouse, if a connection was achieved) | |
const std::string & | getName () const |
Get the name of the group this instance operates on. | |
const std::string & | getPlanningFrame () const |
Get the name of the frame in which the robot is planning. | |
double | getPlanningTime () const |
Get the number of seconds set by setPlanningTime() | |
const std::string & | getPoseReferenceFrame () const |
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the robot model. | |
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 |
std::vector< double > | getRandomJointValues () |
Get random joint values for the joints planned for by this instance (see getJoints()) | |
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. | |
const std::map< std::string, std::vector< double > > & | getRememberedJointValues () const |
Get the currently remembered map of names to joint values. | |
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. | |
bool | 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). | |
MoveGroup (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::Duration &wait_for_server=ros::Duration(0, 0)) | |
Construct a client for the MoveGroup action using a specified set of options opt. Optionally, specify a TF instance to use. If not specified, one will be constructed internally. A timeout for connecting to the action server can also be specified. If it is not specified, the wait time is unlimited. | |
MoveGroup (const std::string &group, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::Duration &wait_for_server=ros::Duration(0, 0)) | |
Construct a client for the MoveGroup action for a particular group. Optionally, specify a TF instance to use. If not specified, one will be constructed internally. A timeout for connecting to the action server can also be specified. If it is not specified, the wait time is unlimited. | |
bool | pick (const std::string &object) |
Pick up an object. | |
bool | pick (const std::string &object, const manipulation_msgs::Grasp &grasp) |
Pick up an object given a grasp pose. | |
bool | pick (const std::string &object, const std::vector< manipulation_msgs::Grasp > &grasps) |
Pick up an object given possible grasp poses. | |
bool | place (const std::string &object) |
Place an object somewhere safe in the world (a safe location will be detected) | |
bool | place (const std::string &object, const std::vector< manipulation_msgs::PlaceLocation > &locations) |
Place an object at one of the specified possible locations. | |
bool | place (const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses) |
Place an object at one of the specified possible locations. | |
bool | place (const std::string &object, const geometry_msgs::PoseStamped &pose) |
Place an object at one of the specified possible location. | |
bool | 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. | |
void | rememberJointValues (const std::string &name) |
Remember the current joint values (of the robot being monitored) under name. These can be used by setNamedTarget() | |
void | rememberJointValues (const std::string &name, const std::vector< double > &values) |
Remember the specified joint values under name. These can be used by setNamedTarget() | |
void | setConstraintsDatabase (const std::string &host, unsigned int port) |
Specify where the MongoDB server that holds known constraints resides. | |
bool | setEndEffector (const std::string &eef_name) |
Specify the name of the end-effector to use. | |
bool | setEndEffectorLink (const std::string &link_name) |
Specify the link the end-effector to be considered is attached to. | |
void | setGoalJointTolerance (double tolerance) |
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint configuration. | |
void | setGoalOrientationTolerance (double tolerance) |
Set the orientation tolerance that is used for reaching the goal when moving to a pose. | |
void | setGoalPositionTolerance (double tolerance) |
Set the position tolerance that is used for reaching the goal when moving to a pose. | |
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. 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(). | |
bool | setJointValueTarget (const std::vector< double > &group_variable_values) |
Given a vector of real values in the same order as expected by the group, set those as the joint state goal. | |
bool | setJointValueTarget (const std::map< std::string, double > &variable_values) |
Given a map of joint names to real values, set those as the joint state goal. | |
bool | setJointValueTarget (const robot_state::RobotState &robot_state) |
Set the joint state goal from corresponding joint values from the specified state. Values from state for joints not in this MoveGroup's group are ignored. | |
bool | setJointValueTarget (const robot_state::JointStateGroup &joint_state_group) |
Set the joint state goal from corresponding joint values from the specified group. joint_state_group must represent the same group as this MoveGroup. | |
bool | setJointValueTarget (const robot_state::JointState &joint_state) |
Set the joint state goal for a particular joint. | |
bool | setJointValueTarget (const std::string &joint_name, const std::vector< double > &values) |
Set the joint state goal for a particular joint. | |
bool | setJointValueTarget (const std::string &joint_name, double value) |
Set the joint state goal for a particular joint. | |
bool | setJointValueTarget (const sensor_msgs::JointState &state) |
Set the joint state goal for a particular joint. | |
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. | |
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). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPathConstraints (const std::string &constraint) |
Specify a set of path constraints to use. | |
void | setPathConstraints (const moveit_msgs::Constraints &constraint) |
Specify a set of path constraints to use. | |
void | setPlannerId (const std::string &planner_id) |
Specify a planner to be used for further planning. | |
void | setPlanningTime (double seconds) |
Specify the maximum amount of time to use when planning. | |
void | setPoseReferenceFrame (const std::string &pose_reference_frame) |
Specify which reference frame to assume for poses specified without a reference frame. | |
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. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPoseTarget (const geometry_msgs::Pose &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPoseTarget (const geometry_msgs::PoseStamped &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPoseTargets (const EigenSTL::vector_Affine3d &end_effector_pose, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPoseTargets (const std::vector< geometry_msgs::Pose > &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | setPoseTargets (const std::vector< geometry_msgs::PoseStamped > &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
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). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
void | setRandomTarget () |
Set the joint state goal to a random joint configuration. | |
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. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
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. | |
void | setStartStateToCurrentState () |
Set the starting state for planning to be that reported by the robot's joint state publication. | |
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. | |
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 MoveGroup's group contains the root joint of the robot -- i.e. when planning motion for the robot relative to the world. | |
void | stop () |
Stop any trajectory execution, if one is active. | |
~MoveGroup () | |
Static Public Attributes | |
static const std::string | ROBOT_DESCRIPTION = "robot_description" |
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'. | |
Private Attributes | |
MoveGroupImpl * | impl_ |
std::map< std::string, std::vector< double > > | remembered_joint_values_ |
Client class for the MoveGroup action. This class includes many default settings to make things easy to use.
Definition at line 59 of file move_group.h.
moveit::planning_interface::MoveGroup::MoveGroup | ( | const Options & | opt, |
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const ros::Duration & | wait_for_server = ros::Duration(0, 0) |
||
) |
Construct a client for the MoveGroup action using a specified set of options opt. Optionally, specify a TF instance to use. If not specified, one will be constructed internally. A timeout for connecting to the action server can also be specified. If it is not specified, the wait time is unlimited.
Definition at line 851 of file move_group.cpp.
moveit::planning_interface::MoveGroup::MoveGroup | ( | const std::string & | group, |
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const ros::Duration & | wait_for_server = ros::Duration(0, 0) |
||
) |
Construct a client for the MoveGroup action for a particular group. Optionally, specify a TF instance to use. If not specified, one will be constructed internally. A timeout for connecting to the action server can also be specified. If it is not specified, the wait time is unlimited.
Definition at line 844 of file move_group.cpp.
Definition at line 856 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::getGoalJointTolerance | ( | ) | const |
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configuration space.
Definition at line 1255 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::getGoalOrientationTolerance | ( | ) | const |
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll, pitch and yaw, in radians.
Definition at line 1265 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::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.
Definition at line 1260 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::getInterfaceDescription | ( | moveit_msgs::PlannerInterfaceDescription & | desc | ) |
Get the description of the planning plugin loaded by the action server.
Definition at line 866 of file move_group.cpp.
const std::vector< std::string > & moveit::planning_interface::MoveGroup::getJoints | ( | ) | const |
Get the joints this instance operates on.
Definition at line 1396 of file move_group.cpp.
const std::string & moveit::planning_interface::MoveGroup::getName | ( | void | ) | const |
Get the name of the group this instance operates on.
Definition at line 861 of file move_group.cpp.
const std::string & moveit::planning_interface::MoveGroup::getPlanningFrame | ( | ) | const |
Get the name of the frame in which the robot is planning.
Definition at line 1478 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::getPlanningTime | ( | ) | const |
Get the number of seconds set by setPlanningTime()
Definition at line 1468 of file move_group.cpp.
unsigned int moveit::planning_interface::MoveGroup::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.
Definition at line 1401 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setGoalJointTolerance | ( | double | tolerance | ) |
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint configuration.
Definition at line 1277 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setGoalOrientationTolerance | ( | double | tolerance | ) |
Set the orientation tolerance that is used for reaching the goal when moving to a pose.
Definition at line 1287 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setGoalPositionTolerance | ( | double | tolerance | ) |
Set the position tolerance that is used for reaching the goal when moving to a pose.
Definition at line 1282 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::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. 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().
Definition at line 1270 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setPlannerId | ( | const std::string & | planner_id | ) |
Specify a planner to be used for further planning.
Definition at line 871 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setPlanningTime | ( | double | seconds | ) |
Specify the maximum amount of time to use when planning.
Definition at line 1463 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::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.
Definition at line 947 of file move_group.cpp.
Set the starting state for planning to be that reported by the robot's joint state publication.
Definition at line 952 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::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.
Definition at line 1473 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::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 MoveGroup's group contains the root joint of the robot -- i.e. when planning motion for the robot relative to the world.
Definition at line 1458 of file move_group.cpp.
Definition at line 445 of file move_group.h.
std::map<std::string, std::vector<double> > moveit::planning_interface::MoveGroup::remembered_joint_values_ [private] |
Definition at line 444 of file move_group.h.
const std::string moveit::planning_interface::MoveGroup::ROBOT_DESCRIPTION = "robot_description" [static] |
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
Definition at line 64 of file move_group.h.