class documentation

Execution of simple commands for a particular group

Method __init__ Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error.
Method allow_looking Enable/disable looking around for motion planning
Method allow_replanning Enable/disable replanning
Method attach_object Given the name of an object existing in the planning scene, attach it to a link. The link used is specified by the second argument. If left unspecified, the end-effector link is used, if one is known. ...
Method clear_max_cartesian_link_speed Clear the maximum cartesian link speed.
Method clear_path_constraints Specify that no path constraints are to be used during motion planning
Method clear_pose_target Clear the pose target for a particular end-effector
Method clear_pose_targets Clear all known pose targets
Method clear_trajectory_constraints Specify that no trajectory constraints are to be used during motion planning
Method compute_cartesian_path Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the poses specified as waypoints. Configurations are computed for every eef_step meters; The jump_threshold specifies the maximum distance in configuration space between consecutive points in the resultingpath; 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...
Method construct_motion_plan_request Returns a MotionPlanRequest filled with the current goals of the move_group_interface
Method detach_object Given the name of a link, detach the object(s) from that link. If no such link exists, the name is interpreted as an object name. If there is no name specified, an attempt is made to detach all objects attached to any link in the group.
Method enforce_bounds Takes a moveit_msgs RobotState and enforces the state bounds, based on the C++ RobotState enforceBounds()
Method execute Execute a previously planned path
Method forget_joint_values Forget a stored joint configuration
Method get_active_joints Get the active joints of this group
Method get_current_joint_values Get the current configuration of the group as a list (these are values published on /joint_states)
Method get_current_pose Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector.
Method get_current_rpy Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector.
Method get_current_state Get the current state of the robot.
Method get_current_state_bounded Get the current state of the robot bounded.
Method get_end_effector_link Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector.
Method get_goal_joint_tolerance Get the tolerance for achieving a joint goal (distance for each joint variable)
Method get_goal_orientation_tolerance When moving to an orientation goal or to a pose goal, the tolerance for the goal orientation is specified as the distance (roll, pitch, yaw) to the target origin of the end-effector
Method get_goal_position_tolerance When moving to a position goal or to a pose goal, the tolerance for the goal position is specified as the radius a sphere around the target origin of the end-effector
Method get_goal_tolerance Return a tuple of goal tolerances: joint, position and orientation.
Method get_interface_description Get the description of the planner interface (list of planner ids)
Method get_jacobian_matrix Get the jacobian matrix of the group as a list
Method get_joint_value_target Undocumented
Method get_joints Get the joints of this group
Method get_known_constraints Get a list of names for the constraints specific for this group, as read from the warehouse
Method get_name Get the name of the group this instance was initialized for
Method get_named_target_values Get a dictionary of joint values of a named target
Method get_named_targets Get a list of all the names of joint configurations.
Method get_path_constraints Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints
Method get_planner_id Get the current planner_id (e.g. RRTConnect, LIN) of the currently selected pipeline
Method get_planning_frame Get the name of the frame where all planning is performed
Method get_planning_pipeline_id Get the current planning_pipeline_id (e.g. ompl, pilz_industrial_motion_planner)
Method get_planning_time Specify the amount of time to be used for motion planning.
Method get_pose_reference_frame Get the reference frame assumed for poses of end-effectors
Method get_random_joint_values Undocumented
Method get_random_pose Undocumented
Method get_remembered_joint_values Get a dictionary that maps names to joint configurations for the group
Method get_trajectory_constraints Get the actual trajectory constraints in form of a moveit_msgs.msgs.TrajectoryConstraints
Method get_variable_count Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)
Method go Set the target of the group and then move the group to the specified target
Method has_end_effector_link Check if this group has a link that is considered to be an end effector
Method limit_max_cartesian_link_speed Set the maximum Cartesian link speed. Only positive real values are allowed. The unit is meter per second.
Method pick Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument.
Method place Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided
Method plan Return a tuple of the motion planning results such as (success flag : boolean, trajectory message : RobotTrajectory,
Method remember_joint_values Record the specified joint configuration of the group under the specified name. If no values are specified, the current state of the group is recorded.
Method retime_trajectory Undocumented
Method set_constraints_database Specify which database to connect to for loading possible path constraints
Method set_end_effector_link Set the name of the link to be considered as an end effector
Method set_goal_joint_tolerance Set the tolerance for a target joint configuration
Method set_goal_orientation_tolerance Set the tolerance for a target end-effector orientation
Method set_goal_position_tolerance Set the tolerance for a target end-effector position
Method set_goal_tolerance Set the joint, position and orientation goal tolerances simultaneously
Method set_joint_value_target Specify a target joint configuration for the group. - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided. The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values for the group...
Method set_max_acceleration_scaling_factor Set a scaling factor to reduce the maximum joint accelerations. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.
Method set_max_velocity_scaling_factor Set a scaling factor to reduce the maximum joint velocities. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.
Method set_named_target Set a joint configuration by name. The name can be a name previlusy remembered with remember_joint_values() or a configuration specified in the SRDF.
Method set_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.
Method set_orientation_target Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.
Method set_path_constraints Specify the path constraints to be used (as read from the database)
Method set_planner_id Specify which planner of the currently selected pipeline to use when motion planning (e.g. RRTConnect, LIN)
Method set_planning_pipeline_id Specify which planning pipeline to use when motion planning (e.g. ompl, pilz_industrial_motion_planner)
Method set_planning_time Specify the amount of time to be used for motion planning.
Method set_pose_reference_frame Set the reference frame to assume for poses of end-effectors
Method set_pose_target Set the pose of the end-effector, if one is available. The expected input is a Pose message, a PoseStamped message or a list of 6 floats:
Method set_pose_targets Set the pose of the end-effector, if one is available. The expected input is a list of poses. Each pose can be a Pose message, a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw]...
Method set_position_target Specify a target position for the end-effector. Any orientation of the end-effector is acceptable.
Method set_random_target Set a random joint configuration target
Method set_rpy_target Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.
Method set_start_state Specify a start state for the group.
Method set_start_state_to_current_state Undocumented
Method set_support_surface_name Set the support surface name for a place operation
Method set_trajectory_constraints Specify the trajectory constraints to be used (setting from database is not implemented yet)
Method set_workspace Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ]
Method shift_pose_target Get the current pose of the end effector, add value to the corresponding axis (0..5: X, Y, Z, R, P, Y) and set the new pose as the pose target
Method stop Stop the current execution, if any
Instance Variable _g Undocumented
def __init__(self, name, robot_description='robot_description', ns='', wait_for_servers=5.0):

Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error.

def allow_looking(self, value):

Enable/disable looking around for motion planning

def allow_replanning(self, value):

Enable/disable replanning

def attach_object(self, object_name, link_name='', touch_links=[]):

Given the name of an object existing in the planning scene, attach it to a link. The link used is specified by the second argument. If left unspecified, the end-effector link is used, if one is known. If there is no end-effector link, the first link in the group is used. If no link is identified, failure is reported. True is returned if an attach request was succesfully sent to the move_group node. This does not verify that the attach request also was successfuly applied by move_group.

def clear_max_cartesian_link_speed(self):

Clear the maximum cartesian link speed.

def clear_path_constraints(self):

Specify that no path constraints are to be used during motion planning

def clear_pose_target(self, end_effector_link):

Clear the pose target for a particular end-effector

def clear_pose_targets(self):

Clear all known pose targets

def clear_trajectory_constraints(self):

Specify that no trajectory constraints are to be used during motion planning

def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None):

Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the poses specified as waypoints. Configurations are computed for every eef_step meters; The jump_threshold specifies the maximum distance in configuration space between consecutive points in the resultingpath; 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. The return value is a tuple: a fraction of how much of the path was followed, the actual RobotTrajectory.

def construct_motion_plan_request(self):

Returns a MotionPlanRequest filled with the current goals of the move_group_interface

def detach_object(self, name=''):

Given the name of a link, detach the object(s) from that link. If no such link exists, the name is interpreted as an object name. If there is no name specified, an attempt is made to detach all objects attached to any link in the group.

def enforce_bounds(self, robot_state_msg):

Takes a moveit_msgs RobotState and enforces the state bounds, based on the C++ RobotState enforceBounds()

def execute(self, plan_msg, wait=True):

Execute a previously planned path

def forget_joint_values(self, name):

Forget a stored joint configuration

def get_active_joints(self):

Get the active joints of this group

def get_current_joint_values(self):

Get the current configuration of the group as a list (these are values published on /joint_states)

def get_current_pose(self, end_effector_link=''):

Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector.

def get_current_rpy(self, end_effector_link=''):

Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector.

def get_current_state(self):

Get the current state of the robot.

def get_current_state_bounded(self):

Get the current state of the robot bounded.

def get_end_effector_link(self):

Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector.

def get_goal_joint_tolerance(self):

Get the tolerance for achieving a joint goal (distance for each joint variable)

def get_goal_orientation_tolerance(self):

When moving to an orientation goal or to a pose goal, the tolerance for the goal orientation is specified as the distance (roll, pitch, yaw) to the target origin of the end-effector

def get_goal_position_tolerance(self):

When moving to a position goal or to a pose goal, the tolerance for the goal position is specified as the radius a sphere around the target origin of the end-effector

def get_goal_tolerance(self):

Return a tuple of goal tolerances: joint, position and orientation.

def get_interface_description(self):

Get the description of the planner interface (list of planner ids)

def get_jacobian_matrix(self, joint_values, reference_point=None):

Get the jacobian matrix of the group as a list

def get_joint_value_target(self):

Undocumented

def get_joints(self):

Get the joints of this group

def get_known_constraints(self):

Get a list of names for the constraints specific for this group, as read from the warehouse

def get_name(self):

Get the name of the group this instance was initialized for

def get_named_target_values(self, target):

Get a dictionary of joint values of a named target

def get_named_targets(self):

Get a list of all the names of joint configurations.

def get_path_constraints(self):

Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints

def get_planner_id(self):

Get the current planner_id (e.g. RRTConnect, LIN) of the currently selected pipeline

def get_planning_frame(self):

Get the name of the frame where all planning is performed

def get_planning_pipeline_id(self):

Get the current planning_pipeline_id (e.g. ompl, pilz_industrial_motion_planner)

def get_planning_time(self):

Specify the amount of time to be used for motion planning.

def get_pose_reference_frame(self):

Get the reference frame assumed for poses of end-effectors

def get_random_joint_values(self):

Undocumented

def get_random_pose(self, end_effector_link=''):

Undocumented

def get_remembered_joint_values(self):

Get a dictionary that maps names to joint configurations for the group

def get_trajectory_constraints(self):

Get the actual trajectory constraints in form of a moveit_msgs.msgs.TrajectoryConstraints

def get_variable_count(self):

Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)

def go(self, joints=None, wait=True):

Set the target of the group and then move the group to the specified target

def has_end_effector_link(self):

Check if this group has a link that is considered to be an end effector

def limit_max_cartesian_link_speed(self, speed, link_name=''):

Set the maximum Cartesian link speed. Only positive real values are allowed. The unit is meter per second.

def pick(self, object_name, grasp=[], plan_only=False):

Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument.

def place(self, object_name, location=None, plan_only=False):

Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided

def plan(self, joints=None):

Return a tuple of the motion planning results such as (success flag : boolean, trajectory message : RobotTrajectory,

planning time : float, error code : MoveitErrorCodes)
def remember_joint_values(self, name, values=None):

Record the specified joint configuration of the group under the specified name. If no values are specified, the current state of the group is recorded.

def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor=1.0, acceleration_scaling_factor=1.0, algorithm='iterative_time_parameterization'):

Undocumented

def set_constraints_database(self, host, port):

Specify which database to connect to for loading possible path constraints

def set_end_effector_link(self, link_name):

Set the name of the link to be considered as an end effector

def set_goal_joint_tolerance(self, value):

Set the tolerance for a target joint configuration

def set_goal_orientation_tolerance(self, value):

Set the tolerance for a target end-effector orientation

def set_goal_position_tolerance(self, value):

Set the tolerance for a target end-effector position

def set_goal_tolerance(self, value):

Set the joint, position and orientation goal tolerances simultaneously

def set_joint_value_target(self, arg1, arg2=None, arg3=None):

Specify a target joint configuration for the group. - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided. The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values for the group. The JointState message specifies the positions of some single-dof joints. - if the type of arg1 is string, then arg2 is expected to be defined and be either a real value or a list of real values. This is interpreted as setting a particular joint to a particular value. - if the type of arg1 is Pose or PoseStamped, both arg2 and arg3 could be defined. If arg2 or arg3 are defined, their types must be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation allows setting the joint target of the group by calling IK. This does not send a pose to the planner and the planner will do no IK. Instead, one IK solution will be computed first, and that will be sent to the planner.

def set_max_acceleration_scaling_factor(self, value):

Set a scaling factor to reduce the maximum joint accelerations. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.

def set_max_velocity_scaling_factor(self, value):

Set a scaling factor to reduce the maximum joint velocities. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.

def set_named_target(self, name):

Set a joint configuration by name. The name can be a name previlusy remembered with remember_joint_values() or a configuration specified in the SRDF.

def set_num_planning_attempts(self, 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.

def set_orientation_target(self, q, end_effector_link=''):

Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.

def set_path_constraints(self, value):

Specify the path constraints to be used (as read from the database)

def set_planner_id(self, planner_id):

Specify which planner of the currently selected pipeline to use when motion planning (e.g. RRTConnect, LIN)

def set_planning_pipeline_id(self, planning_pipeline):

Specify which planning pipeline to use when motion planning (e.g. ompl, pilz_industrial_motion_planner)

def set_planning_time(self, seconds):

Specify the amount of time to be used for motion planning.

def set_pose_reference_frame(self, reference_frame):

Set the reference frame to assume for poses of end-effectors

def set_pose_target(self, pose, end_effector_link=''):

Set the pose of the end-effector, if one is available. The expected input is a Pose message, a PoseStamped message or a list of 6 floats:

def set_pose_targets(self, poses, end_effector_link=''):

Set the pose of the end-effector, if one is available. The expected input is a list of poses. Each pose can be a Pose message, a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw]

def set_position_target(self, xyz, end_effector_link=''):

Specify a target position for the end-effector. Any orientation of the end-effector is acceptable.

def set_random_target(self):

Set a random joint configuration target

def set_rpy_target(self, rpy, end_effector_link=''):

Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.

def set_start_state(self, msg):

Specify a start state for the group.

Parameters

msg : moveit_msgs/RobotState

Examples

>>> from moveit_msgs.msg import RobotState
>>> from sensor_msgs.msg import JointState
>>> joint_state = JointState()
>>> joint_state.header = Header()
>>> joint_state.header.stamp = rospy.Time.now()
>>> joint_state.name = ['joint_a', 'joint_b']
>>> joint_state.position = [0.17, 0.34]
>>> moveit_robot_state = RobotState()
>>> moveit_robot_state.joint_state = joint_state
>>> group.set_start_state(moveit_robot_state)
def set_start_state_to_current_state(self):

Undocumented

def set_support_surface_name(self, value):

Set the support surface name for a place operation

def set_trajectory_constraints(self, value):

Specify the trajectory constraints to be used (setting from database is not implemented yet)

def set_workspace(self, ws):

Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ]

def shift_pose_target(self, axis, value, end_effector_link=''):

Get the current pose of the end effector, add value to the corresponding axis (0..5: X, Y, Z, R, P, Y) and set the new pose as the pose target

def stop(self):

Stop the current execution, if any

_g =

Undocumented