35 from geometry_msgs.msg
import Pose, PoseStamped
36 from moveit_msgs.msg
import RobotTrajectory, Grasp, PlaceLocation, Constraints, RobotState
37 from moveit_msgs.msg
import MoveItErrorCodes, TrajectoryConstraints, PlannerInterfaceDescription
38 from sensor_msgs.msg
import JointState
41 from moveit_ros_planning_interface
import _moveit_move_group_interface
42 from .exception
import MoveItCommanderException
47 Execution of simple commands for a particular group 50 def __init__(self, name, robot_description="robot_description", ns=""):
51 """ Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error. """ 52 self.
_g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description, ns)
55 """ Get the name of the group this instance was initialized for """ 56 return self._g.get_name()
59 """ Stop the current execution, if any """ 63 """ Get the active joints of this group """ 64 return self._g.get_active_joints()
67 """ Get the joints of this group """ 68 return self._g.get_joints()
71 """ Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)""" 72 return self._g.get_variable_count()
75 """ Check if this group has a link that is considered to be an end effector """ 76 return len(self._g.get_end_effector_link()) > 0
79 """ Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector. """ 80 return self._g.get_end_effector_link()
83 """ Set the name of the link to be considered as an end effector """ 84 if not self._g.set_end_effector_link(link_name):
85 raise MoveItCommanderException(
"Unable to set end efector link")
88 """ Get the description of the planner interface (list of planner ids) """ 89 desc = PlannerInterfaceDescription()
90 conversions.msg_from_string(desc, self._g.get_interface_description())
94 """ Get the reference frame assumed for poses of end-effectors """ 95 return self._g.get_pose_reference_frame()
98 """ Set the reference frame to assume for poses of end-effectors """ 99 self._g.set_pose_reference_frame(reference_frame)
102 """ Get the name of the frame where all planning is performed """ 103 return self._g.get_planning_frame()
106 """ Get the current configuration of the group as a list (these are values published on /joint_states) """ 107 return self._g.get_current_joint_values()
110 """ Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector. """ 112 return conversions.list_to_pose_stamped(self._g.get_current_pose(end_effector_link), self.
get_planning_frame())
114 raise MoveItCommanderException(
"There is no end effector to get the pose of")
117 """ Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector. """ 119 return self._g.get_current_rpy(end_effector_link)
121 raise MoveItCommanderException(
"There is no end effector to get the rpy of")
124 return self._g.get_random_joint_values()
128 return conversions.list_to_pose_stamped(self._g.get_random_pose(end_effector_link), self.
get_planning_frame())
130 raise MoveItCommanderException(
"There is no end effector to get the pose of")
133 self._g.set_start_state_to_current_state()
137 Specify a start state for the group. 141 msg : moveit_msgs/RobotState 145 >>> from moveit_msgs.msg import RobotState 146 >>> from sensor_msgs.msg import JointState 147 >>> joint_state = JointState() 148 >>> joint_state.header = Header() 149 >>> joint_state.header.stamp = rospy.Time.now() 150 >>> joint_state.name = ['joint_a', 'joint_b'] 151 >>> joint_state.position = [0.17, 0.34] 152 >>> moveit_robot_state = RobotState() 153 >>> moveit_robot_state.joint_state = joint_state 154 >>> group.set_start_state(moveit_robot_state) 156 self._g.set_start_state(conversions.msg_to_string(msg))
159 return self._g.get_joint_value_target()
163 Specify a target joint configuration for the group. 164 - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided. 165 The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values 166 for the group. The JointState message specifies the positions of some single-dof joints. 167 - 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 168 interpreted as setting a particular joint to a particular value. 169 - 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 170 be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use 171 the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation 172 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. 173 Instead, one IK solution will be computed first, and that will be sent to the planner. 175 if isinstance(arg1, RobotState):
176 if not self._g.set_state_value_target(conversions.msg_to_string(arg1)):
177 raise MoveItCommanderException(
"Error setting state target. Is the target state within bounds?")
179 elif isinstance(arg1, JointState):
180 if (arg2
is not None or arg3
is not None):
181 raise MoveItCommanderException(
"Too many arguments specified")
182 if not self._g.set_joint_value_target_from_joint_state_message(conversions.msg_to_string(arg1)):
183 raise MoveItCommanderException(
"Error setting joint target. Is the target within bounds?")
185 elif isinstance(arg1, str):
187 raise MoveItCommanderException(
"Joint value expected when joint name specified")
188 if (arg3
is not None):
189 raise MoveItCommanderException(
"Too many arguments specified")
190 if not self._g.set_joint_value_target(arg1, arg2):
191 raise MoveItCommanderException(
"Error setting joint target. Is the target within bounds?")
193 elif isinstance(arg1, (Pose, PoseStamped)):
196 if (arg2
is not None):
197 if type(arg2)
is str:
200 if type(arg2)
is bool:
203 raise MoveItCommanderException(
"Unexpected type")
204 if (arg3
is not None):
205 if type(arg3)
is str:
208 if type(arg3)
is bool:
211 raise MoveItCommanderException(
"Unexpected type")
213 if type(arg1)
is PoseStamped:
214 r = self._g.set_joint_value_target_from_pose_stamped(conversions.msg_to_string(arg1), eef, approx)
216 r = self._g.set_joint_value_target_from_pose(conversions.msg_to_string(arg1), eef, approx)
219 raise MoveItCommanderException(
"Error setting joint target. Does your IK solver support approximate IK?")
221 raise MoveItCommanderException(
"Error setting joint target. Is IK running?")
223 elif (hasattr(arg1,
'__iter__')):
224 if (arg2
is not None or arg3
is not None):
225 raise MoveItCommanderException(
"Too many arguments specified")
226 if not self._g.set_joint_value_target(arg1):
227 raise MoveItCommanderException(
"Error setting joint target. Is the target within bounds?")
230 raise MoveItCommanderException(
"Unsupported argument of type %s" %
type(arg1))
234 """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.""" 237 if not self._g.set_rpy_target(rpy[0], rpy[1], rpy[2], end_effector_link):
238 raise MoveItCommanderException(
"Unable to set orientation target")
240 raise MoveItCommanderException(
"Expected [roll, pitch, yaw]")
242 raise MoveItCommanderException(
"There is no end effector to set the pose for")
245 """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.""" 248 if not self._g.set_orientation_target(q[0], q[1], q[2], q[3], end_effector_link):
249 raise MoveItCommanderException(
"Unable to set orientation target")
251 raise MoveItCommanderException(
"Expected [qx, qy, qz, qw]")
253 raise MoveItCommanderException(
"There is no end effector to set the pose for")
256 """ Specify a target position for the end-effector. Any orientation of the end-effector is acceptable.""" 258 if not self._g.set_position_target(xyz[0], xyz[1], xyz[2], end_effector_link):
259 raise MoveItCommanderException(
"Unable to set position target")
261 raise MoveItCommanderException(
"There is no end effector to set the pose for")
264 """ 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:""" 265 """ [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] """ 268 if type(pose)
is PoseStamped:
271 ok = self._g.set_pose_target(conversions.pose_to_list(pose.pose), end_effector_link)
273 elif type(pose)
is Pose:
274 ok = self._g.set_pose_target(conversions.pose_to_list(pose), end_effector_link)
276 ok = self._g.set_pose_target(pose, end_effector_link)
278 raise MoveItCommanderException(
"Unable to set target pose")
280 raise MoveItCommanderException(
"There is no end effector to set the pose for")
283 """ 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] """ 285 if not self._g.set_pose_targets([conversions.pose_to_list(p)
if type(p)
is Pose
else p
for p
in poses], end_effector_link):
286 raise MoveItCommanderException(
"Unable to set target poses")
288 raise MoveItCommanderException(
"There is no end effector to set poses for")
291 """ 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 """ 293 pose = self._g.get_current_pose(end_effector_link)
297 (r, p, y) = tf.transformations.euler_from_quaternion(pose[3:])
298 pose = [pose[0], pose[1], pose[2], r, p, y]
299 if axis >= 0
and axis < 6:
300 pose[axis] = pose[axis] + value
303 raise MoveItCommanderException(
"An axis value between 0 and 5 expected")
305 raise MoveItCommanderException(
"There is no end effector to set poses for")
308 """ Clear the pose target for a particular end-effector """ 309 self._g.clear_pose_target(end_effector_link)
312 """ Clear all known pose targets """ 313 self._g.clear_pose_targets()
316 """ Set a random joint configuration target """ 317 self._g.set_random_target()
320 """ Get a list of all the names of joint configurations.""" 321 return self._g.get_named_targets()
324 """ 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. """ 325 if not self._g.set_named_target(name):
326 raise MoveItCommanderException(
"Unable to set target %s. Is the target within bounds?" % name)
329 """Get a dictionary of joint values of a named target""" 330 return self._g.get_named_target_values(target)
333 """ 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. """ 336 self._g.remember_joint_values(name, values)
339 """ Get a dictionary that maps names to joint configurations for the group """ 340 return self._g.get_remembered_joint_values()
343 """ Forget a stored joint configuration """ 344 self._g.forget_joint_values(name)
347 """ Return a tuple of goal tolerances: joint, position and orientation. """ 351 """ Get the tolerance for achieving a joint goal (distance for each joint variable) """ 352 return self._g.get_goal_joint_tolerance()
355 """ 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 """ 356 return self._g.get_goal_position_tolerance()
359 """ 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 """ 360 return self._g.get_goal_orientation_tolerance()
363 """ Set the joint, position and orientation goal tolerances simultaneously """ 364 self._g.set_goal_tolerance(value)
367 """ Set the tolerance for a target joint configuration """ 368 self._g.set_goal_joint_tolerance(value)
371 """ Set the tolerance for a target end-effector position """ 372 self._g.set_goal_position_tolerance(value)
375 """ Set the tolerance for a target end-effector orientation """ 376 self._g.set_goal_orientation_tolerance(value)
379 """ Enable/disable looking around for motion planning """ 380 self._g.allow_looking(value)
383 """ Enable/disable replanning """ 384 self._g.allow_replanning(value)
387 """ Get a list of names for the constraints specific for this group, as read from the warehouse """ 388 return self._g.get_known_constraints()
391 """ Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints """ 393 c_str = self._g.get_path_constraints()
394 conversions.msg_from_string(c,c_str)
398 """ Specify the path constraints to be used (as read from the database) """ 402 if type(value)
is Constraints:
403 self._g.set_path_constraints_from_msg(conversions.msg_to_string(value))
404 elif not self._g.set_path_constraints(value):
405 raise MoveItCommanderException(
"Unable to set path constraints " + value)
408 """ Specify that no path constraints are to be used during motion planning """ 409 self._g.clear_path_constraints()
412 """ Get the actual trajectory constraints in form of a moveit_msgs.msgs.Constraints """ 414 c_str = self._g.get_trajectory_constraints()
415 conversions.msg_from_string(c, c_str)
419 """ Specify the trajectory constraints to be used """ 423 if type(value)
is TrajectoryConstraints:
424 self._g.set_trajectory_constraints_from_msg(conversions.msg_to_string(value))
425 elif not self._g.set_trajectory_constraints(value):
426 raise MoveItCommanderException(
"Unable to set trajectory constraints " + value)
429 """ Specify that no trajectory constraints are to be used during motion planning """ 430 self._g.clear_trajectory_constraints()
433 """ Specify which database to connect to for loading possible path constraints """ 434 self._g.set_constraints_database(host, port)
437 """ Specify the amount of time to be used for motion planning. """ 438 self._g.set_planning_time(seconds)
441 """ Specify the amount of time to be used for motion planning. """ 442 return self._g.get_planning_time()
445 """ Specify which planner to use when motion planning """ 446 self._g.set_planner_id(planner_id)
449 """ Get the current planner_id """ 450 self._g.get_planner_id()
453 """ 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. """ 454 self._g.set_num_planning_attempts(num_planning_attempts)
457 """ Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ] """ 459 self._g.set_workspace(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)
462 self._g.set_workspace(ws[0], ws[1], 0.0, ws[2], ws[3], 0.0)
465 self._g.set_workspace(ws[0], ws[1], ws[2], ws[3], ws[4], ws[5])
467 raise MoveItCommanderException(
"Expected 0, 4 or 6 values in list specifying workspace")
470 """ Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1]. """ 471 if value > 0
and value <= 1:
472 self._g.set_max_velocity_scaling_factor(value)
474 raise MoveItCommanderException(
"Expected value in the range from 0 to 1 for scaling factor" )
477 """ Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1]. """ 478 if value > 0
and value <= 1:
479 self._g.set_max_acceleration_scaling_factor(value)
481 raise MoveItCommanderException(
"Expected value in the range from 0 to 1 for scaling factor" )
483 def go(self, joints = None, wait = True):
484 """ Set the target of the group and then move the group to the specified target """ 485 if type(joints)
is bool:
489 elif type(joints)
is JointState:
492 elif type(joints)
is Pose:
495 elif not joints
is None:
501 return self._g.move()
503 return self._g.async_move()
506 """ Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument) """ 507 if type(joints)
is JointState:
510 elif type(joints)
is Pose:
513 elif not joints
is None:
518 plan = RobotTrajectory()
519 plan.deserialize(self._g.compute_plan())
523 """ 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. """ 525 if type(path_constraints)
is Constraints:
526 constraints_str = conversions.msg_to_string(path_constraints)
528 raise MoveItCommanderException(
"Unable to set path constraints, unknown constraint type " +
type(path_constraints))
529 (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p)
for p
in waypoints], eef_step, jump_threshold, avoid_collisions, constraints_str)
531 (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p)
for p
in waypoints], eef_step, jump_threshold, avoid_collisions)
533 path = RobotTrajectory()
534 path.deserialize(ser_path)
535 return (path, fraction)
538 """Execute a previously planned path""" 540 return self._g.execute(conversions.msg_to_string(plan_msg))
542 return self._g.async_execute(conversions.msg_to_string(plan_msg))
545 """ 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.""" 546 return self._g.attach_object(object_name, link_name, touch_links)
549 """ 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.""" 550 return self._g.detach_object(name)
552 def pick(self, object_name, grasp = [], plan_only=False):
553 """Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument.""" 554 if type(grasp)
is Grasp:
555 return self._g.pick(object_name, conversions.msg_to_string(grasp), plan_only)
557 return self._g.pick(object_name, [conversions.msg_to_string(x)
for x
in grasp], plan_only)
559 def place(self, object_name, location=None, plan_only=False):
560 """Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided""" 563 result = self._g.place(object_name, plan_only)
564 elif type(location)
is PoseStamped:
567 result = self._g.place(object_name, conversions.pose_to_list(location.pose), plan_only)
569 elif type(location)
is Pose:
570 result = self._g.place(object_name, conversions.pose_to_list(location), plan_only)
571 elif type(location)
is PlaceLocation:
572 result = self._g.place(object_name, conversions.msg_to_string(location), plan_only)
574 raise MoveItCommanderException(
"Parameter location must be a Pose, PoseStamped or PlaceLocation object")
578 """ Set the support surface name for a place operation """ 579 self._g.set_support_surface_name(value)
582 ser_ref_state_in = conversions.msg_to_string(ref_state_in)
583 ser_traj_in = conversions.msg_to_string(traj_in)
584 ser_traj_out = self._g.retime_trajectory(ser_ref_state_in, ser_traj_in, velocity_scaling_factor)
585 traj_out = RobotTrajectory()
586 traj_out.deserialize(ser_traj_out)
590 """ Get the jacobian matrix of the group as a list""" 591 return self._g.get_jacobian_matrix(joint_values)
def shift_pose_target(self, axis, value, end_effector_link="")
def get_random_joint_values(self)
def get_active_joints(self)
def set_end_effector_link(self, link_name)
def set_named_target(self, name)
def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None)
def get_variable_count(self)
def clear_path_constraints(self)
def get_pose_reference_frame(self)
def set_max_velocity_scaling_factor(self, value)
def get_goal_position_tolerance(self)
def set_start_state_to_current_state(self)
def set_goal_orientation_tolerance(self, value)
def get_current_joint_values(self)
def allow_replanning(self, value)
def get_named_targets(self)
def set_trajectory_constraints(self, value)
def get_jacobian_matrix(self, joint_values)
def set_start_state(self, msg)
def get_goal_tolerance(self)
def set_max_acceleration_scaling_factor(self, value)
def execute(self, plan_msg, wait=True)
def set_random_target(self)
def set_goal_joint_tolerance(self, value)
def set_support_surface_name(self, value)
def set_goal_position_tolerance(self, value)
def get_goal_joint_tolerance(self)
def set_pose_reference_frame(self, reference_frame)
def get_interface_description(self)
def clear_pose_targets(self)
def get_remembered_joint_values(self)
def has_end_effector_link(self)
def remember_joint_values(self, name, values=None)
def __init__(self, name, robot_description="robot_description", ns="")
def pick(self, object_name, grasp=[], plan_only=False)
def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor)
def get_current_rpy(self, end_effector_link="")
def get_goal_orientation_tolerance(self)
def clear_pose_target(self, end_effector_link)
def get_random_pose(self, end_effector_link="")
def clear_trajectory_constraints(self)
def get_current_pose(self, end_effector_link="")
def set_goal_tolerance(self, value)
def set_rpy_target(self, rpy, end_effector_link="")
def set_pose_target(self, pose, end_effector_link="")
def detach_object(self, name="")
def get_joint_value_target(self)
def set_orientation_target(self, q, end_effector_link="")
def set_position_target(self, xyz, end_effector_link="")
def set_num_planning_attempts(self, num_planning_attempts)
def go(self, joints=None, wait=True)
def set_planning_time(self, seconds)
def place(self, object_name, location=None, plan_only=False)
def plan(self, joints=None)
def set_planner_id(self, planner_id)
def set_joint_value_target(self, arg1, arg2=None, arg3=None)
def get_end_effector_link(self)
def set_workspace(self, ws)
def get_planning_time(self)
def get_planning_frame(self)
def get_trajectory_constraints(self)
def set_constraints_database(self, host, port)
def forget_joint_values(self, name)
def allow_looking(self, value)
def get_path_constraints(self)
def set_pose_targets(self, poses, end_effector_link="")
def get_named_target_values(self, target)
def set_path_constraints(self, value)
def get_known_constraints(self)
def attach_object(self, object_name, link_name="", touch_links=[])