Execution of simple commands for a particular group
Definition at line 43 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.__init__ | ( | self, | |
name | |||
) |
Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error.
Definition at line 48 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.allow_looking | ( | self, | |
value | |||
) |
Enable/disable looking around for motion planning
Definition at line 267 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.allow_replanning | ( | self, | |
value | |||
) |
Enable/disable replanning
Definition at line 271 of file move_group.py.
Specify that no path constraints are to be used during motion planning
Definition at line 287 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.clear_pose_target | ( | self, | |
end_effector_link | |||
) |
Clear the pose target for a particular end-effector
Definition at line 204 of file move_group.py.
Clear all known pose targets
Definition at line 208 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path | ( | self, | |
waypoints, | |||
eef_step, | |||
jump_threshold, | |||
avoid_collisions = True |
|||
) |
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. The return value is a tuple: a fraction of how much of the path was followed, the actual RobotTrajectory.
Definition at line 358 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.execute | ( | self, | |
plan_msg | |||
) |
Execute a previously planned path
Definition at line 363 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.forget_joint_values | ( | self, | |
name | |||
) |
Forget a stored joint configuration
Definition at line 231 of file move_group.py.
Get the current configuration of the group (as published on JointState)
Definition at line 93 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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.
Definition at line 97 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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.
Definition at line 104 of file move_group.py.
Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector.
Definition at line 72 of file move_group.py.
Get the tolerance for achieving a joint goal (distance for each joint variable)
Definition at line 239 of file move_group.py.
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
Definition at line 247 of file move_group.py.
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
Definition at line 243 of file move_group.py.
Return a tuple of goal tolerances: joint, position and orientation.
Definition at line 235 of file move_group.py.
Get the joints of this group
Definition at line 60 of file move_group.py.
Get a list of names for the constraints specific for this group, as read from the warehouse
Definition at line 275 of file move_group.py.
Get the name of the group this instance was initialized for
Definition at line 52 of file move_group.py.
Get the name of the frame where all planning is performed
Definition at line 89 of file move_group.py.
Specify the amount of time to be used for motion planning.
Definition at line 299 of file move_group.py.
Get the reference frame assumed for poses of end-effectors
Definition at line 81 of file move_group.py.
Definition at line 111 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.get_random_pose | ( | self, | |
end_effector_link = "" |
|||
) |
Definition at line 114 of file move_group.py.
Get a dictionary that maps names to joint configurations for the group
Definition at line 227 of file move_group.py.
Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)
Definition at line 64 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.go | ( | self, | |
joints = None , |
|||
wait = True |
|||
) |
Set the target of the group and then move the group to the specified target
Definition at line 320 of file move_group.py.
Check if this group has a link that is considered to be an end effector
Definition at line 68 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.pick | ( | self, | |
object_name | |||
) |
Pick the named object
Definition at line 367 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.place | ( | self, | |
object_name, | |||
pose | |||
) |
Place the named object at a particular location in the environment
Definition at line 371 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.plan | ( | self, | |
joints = None |
|||
) |
Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument)
Definition at line 342 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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.
Definition at line 221 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_constraints_database | ( | self, | |
host, | |||
port | |||
) |
Specify which database to connect to for loading possible path constraints
Definition at line 291 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_end_effector_link | ( | self, | |
link_name | |||
) |
Set the name of the link to be considered as an end effector
Definition at line 76 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_goal_joint_tolerance | ( | self, | |
value | |||
) |
Set the tolerance for a target joint configuration
Definition at line 255 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_goal_orientation_tolerance | ( | self, | |
value | |||
) |
Set the tolerance for a target end-effector orientation
Definition at line 263 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_goal_position_tolerance | ( | self, | |
value | |||
) |
Set the tolerance for a target end-effector position
Definition at line 259 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_goal_tolerance | ( | self, | |
value | |||
) |
Set the joint, position and orientation goal tolerances simultaneously
Definition at line 251 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_joint_value_target | ( | self, | |
name, | |||
value = None |
|||
) |
Specify a target joint configuration for the group.
Definition at line 120 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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.
Definition at line 216 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_orientation_target | ( | self, | |
q, | |||
end_effector_link = "" |
|||
) |
Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.
Definition at line 141 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_path_constraints | ( | self, | |
value | |||
) |
Specify the path constraints to be used (as read from the database)
Definition at line 279 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_planner_id | ( | self, | |
planner_id | |||
) |
Specify which planner to use when motion planning
Definition at line 303 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_planning_time | ( | self, | |
seconds | |||
) |
Specify the amount of time to be used for motion planning.
Definition at line 295 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_pose_reference_frame | ( | self, | |
reference_frame | |||
) |
Set the reference frame to assume for poses of end-effectors
Definition at line 85 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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:
[x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw]
Definition at line 160 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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]
Definition at line 179 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_position_target | ( | self, | |
xyz, | |||
end_effector_link = "" |
|||
) |
Specify a target position for the end-effector. Any orientation of the end-effector is acceptable.
Definition at line 152 of file move_group.py.
Set a random joint configuration target
Definition at line 212 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_rpy_target | ( | self, | |
rpy, | |||
end_effector_link = "" |
|||
) |
Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.
Definition at line 130 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.set_workspace | ( | self, | |
ws | |||
) |
Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ]
Definition at line 307 of file move_group.py.
def moveit_commander.move_group.MoveGroupCommander.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
Definition at line 187 of file move_group.py.
Stop the current execution, if any
Definition at line 56 of file move_group.py.
Definition at line 48 of file move_group.py.