35 from geometry_msgs.msg
import Pose, PoseStamped
45 TrajectoryConstraints,
46 PlannerInterfaceDescription,
49 from sensor_msgs.msg
import JointState
52 from moveit_ros_planning_interface
import _moveit_move_group_interface
53 from .exception
import MoveItCommanderException
59 Execution of simple commands for a particular group
63 self, name, robot_description="robot_description", ns="", wait_for_servers=5.0
65 """Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error."""
66 self.
_g_g = _moveit_move_group_interface.MoveGroupInterface(
67 name, robot_description, ns, wait_for_servers
71 """Get the name of the group this instance was initialized for"""
75 """Stop the current execution, if any"""
79 """Get the active joints of this group"""
83 """Get the joints of this group"""
87 """Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)"""
91 """Check if this group has a link that is considered to be an end effector"""
95 """Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector."""
99 """Set the name of the link to be considered as an end effector"""
104 """Get the description of the planner interface (list of planner ids)"""
105 desc = PlannerInterfaceDescription()
110 """Get the reference frame assumed for poses of end-effectors"""
114 """Set the reference frame to assume for poses of end-effectors"""
118 """Get the name of the frame where all planning is performed"""
122 """Get the current configuration of the group as a list (these are values published on /joint_states)"""
126 """Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector."""
128 return conversions.list_to_pose_stamped(
133 "There is no end effector to get the pose of"
137 """Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector."""
148 return conversions.list_to_pose_stamped(
153 "There is no end effector to get the pose of"
161 Specify a start state for the group.
165 msg : moveit_msgs/RobotState
169 >>> from moveit_msgs.msg import RobotState
170 >>> from sensor_msgs.msg import JointState
171 >>> joint_state = JointState()
172 >>> joint_state.header = Header()
173 >>> joint_state.header.stamp = rospy.Time.now()
174 >>> joint_state.name = ['joint_a', 'joint_b']
175 >>> joint_state.position = [0.17, 0.34]
176 >>> moveit_robot_state = RobotState()
177 >>> moveit_robot_state.joint_state = joint_state
178 >>> group.set_start_state(moveit_robot_state)
183 """Get the current state of the robot bounded."""
186 conversions.msg_from_string(s, c_str)
190 """Get the current state of the robot."""
193 conversions.msg_from_string(s, c_str)
201 Specify a target joint configuration for the group.
202 - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided.
203 The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values
204 for the group. The JointState message specifies the positions of some single-dof joints.
205 - 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
206 interpreted as setting a particular joint to a particular value.
207 - 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
208 be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use
209 the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation
210 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.
211 Instead, one IK solution will be computed first, and that will be sent to the planner.
213 if isinstance(arg1, JointState):
214 if arg2
is not None or arg3
is not None:
216 if not self.
_g_g.set_joint_value_target_from_joint_state_message(
217 conversions.msg_to_string(arg1)
220 "Error setting joint target. Is the target within bounds?"
223 elif isinstance(arg1, str):
226 "Joint value expected when joint name specified"
232 "Error setting joint target. Is the target within bounds?"
235 elif isinstance(arg1, (Pose, PoseStamped)):
239 if type(arg2)
is str:
242 if type(arg2)
is bool:
247 if type(arg3)
is str:
250 if type(arg3)
is bool:
255 if type(arg1)
is PoseStamped:
256 r = self.
_g_g.set_joint_value_target_from_pose_stamped(
257 conversions.msg_to_string(arg1), eef, approx
260 r = self.
_g_g.set_joint_value_target_from_pose(
261 conversions.msg_to_string(arg1), eef, approx
266 "Error setting joint target. Does your IK solver support approximate IK?"
270 "Error setting joint target. Is the IK solver functional?"
273 elif hasattr(arg1,
"__iter__"):
274 if arg2
is not None or arg3
is not None:
278 "Error setting joint target. Is the target within bounds?"
283 "Unsupported argument of type %s" %
type(arg1)
287 """Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
291 rpy[0], rpy[1], rpy[2], end_effector_link
298 "There is no end effector to set the pose for"
302 """Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
306 q[0], q[1], q[2], q[3], end_effector_link
313 "There is no end effector to set the pose for"
317 """Specify a target position for the end-effector. Any orientation of the end-effector is acceptable."""
320 xyz[0], xyz[1], xyz[2], end_effector_link
325 "There is no end effector to set the pose for"
329 """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:"""
330 """ [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] """
333 if type(pose)
is PoseStamped:
337 conversions.pose_to_list(pose.pose), end_effector_link
340 elif type(pose)
is Pose:
342 conversions.pose_to_list(pose), end_effector_link
350 "There is no end effector to set the pose for"
354 """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]"""
357 [conversions.pose_to_list(p)
if type(p)
is Pose
else p
for p
in poses],
365 """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"""
371 (r, p, y) = tf.transformations.euler_from_quaternion(pose[3:])
372 pose = [pose[0], pose[1], pose[2], r, p, y]
373 if axis >= 0
and axis < 6:
374 pose[axis] = pose[axis] + value
382 """Clear the pose target for a particular end-effector"""
386 """Clear all known pose targets"""
390 """Set a random joint configuration target"""
394 """Get a list of all the names of joint configurations."""
398 """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."""
401 "Unable to set target %s. Is the target within bounds?" % name
405 """Get a dictionary of joint values of a named target"""
409 """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."""
415 """Get a dictionary that maps names to joint configurations for the group"""
419 """Forget a stored joint configuration"""
423 """Return a tuple of goal tolerances: joint, position and orientation."""
431 """Get the tolerance for achieving a joint goal (distance for each joint variable)"""
435 """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"""
439 """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"""
443 """Set the joint, position and orientation goal tolerances simultaneously"""
447 """Set the tolerance for a target joint configuration"""
451 """Set the tolerance for a target end-effector position"""
455 """Set the tolerance for a target end-effector orientation"""
459 """Enable/disable looking around for motion planning"""
463 """Enable/disable replanning"""
467 """Get a list of names for the constraints specific for this group, as read from the warehouse"""
471 """Get the actual path constraints in form of a moveit_msgs.msgs.Constraints"""
474 conversions.msg_from_string(c, c_str)
478 """Specify the path constraints to be used (as read from the database)"""
482 if type(value)
is Constraints:
483 self.
_g_g.set_path_constraints_from_msg(conversions.msg_to_string(value))
486 "Unable to set path constraints " + value
490 """Specify that no path constraints are to be used during motion planning"""
494 """Get the actual trajectory constraints in form of a moveit_msgs.msgs.TrajectoryConstraints"""
495 c = TrajectoryConstraints()
497 conversions.msg_from_string(c, c_str)
501 """Specify the trajectory constraints to be used (setting from database is not implemented yet)"""
505 if type(value)
is TrajectoryConstraints:
506 self.
_g_g.set_trajectory_constraints_from_msg(
507 conversions.msg_to_string(value)
511 "Unable to set trajectory constraints " + value
515 """Specify that no trajectory constraints are to be used during motion planning"""
519 """Specify which database to connect to for loading possible path constraints"""
523 """Specify the amount of time to be used for motion planning."""
527 """Specify the amount of time to be used for motion planning."""
531 """Specify which planning pipeline to use when motion planning (e.g. ompl, pilz_industrial_motion_planner)"""
535 """Get the current planning_pipeline_id (e.g. ompl, pilz_industrial_motion_planner)"""
539 """Specify which planner of the currently selected pipeline to use when motion planning (e.g. RRTConnect, LIN)"""
543 """Get the current planner_id (e.g. RRTConnect, LIN) of the currently selected pipeline"""
547 """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."""
551 """Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ]"""
562 "Expected 0, 4 or 6 values in list specifying workspace"
566 """Set a scaling factor to reduce the maximum joint velocities. Allowed values are in (0,1].
567 The default value is set in the joint_limits.yaml of the moveit_config package."""
568 if value > 0
and value <= 1:
572 "Expected value in the range from 0 to 1 for scaling factor"
576 """Set a scaling factor to reduce the maximum joint accelerations. Allowed values are in (0,1].
577 The default value is set in the joint_limits.yaml of the moveit_config package."""
578 if value > 0
and value <= 1:
582 "Expected value in the range from 0 to 1 for scaling factor"
585 def go(self, joints=None, wait=True):
586 """Set the target of the group and then move the group to the specified target"""
587 if type(joints)
is bool:
591 elif type(joints)
is JointState:
594 elif type(joints)
is Pose:
597 elif joints
is not None:
600 except (KeyError, TypeError):
603 return self.
_g_g.move()
605 return self.
_g_g.async_move()
608 """Return a tuple of the motion planning results such as
609 (success flag : boolean, trajectory message : RobotTrajectory,
610 planning time : float, error code : MoveitErrorCodes)"""
611 if type(joints)
is JointState:
614 elif type(joints)
is Pose:
617 elif joints
is not None:
620 except MoveItCommanderException:
623 (error_code_msg, trajectory_msg, planning_time) = self.
_g_g.
plan()
625 error_code = MoveItErrorCodes()
626 error_code.deserialize(error_code_msg)
627 plan = RobotTrajectory()
629 error_code.val == MoveItErrorCodes.SUCCESS,
630 plan.deserialize(trajectory_msg),
636 """Returns a MotionPlanRequest filled with the current goals of the move_group_interface"""
645 avoid_collisions=True,
646 path_constraints=None,
648 """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."""
650 if type(path_constraints)
is Constraints:
651 constraints_str = conversions.msg_to_string(path_constraints)
654 "Unable to set path constraints, unknown constraint type "
655 +
type(path_constraints)
658 [conversions.pose_to_list(p)
for p
in waypoints],
666 [conversions.pose_to_list(p)
for p
in waypoints],
672 path = RobotTrajectory()
673 path.deserialize(ser_path)
674 return (path, fraction)
677 """Execute a previously planned path"""
679 return self.
_g_g.
execute(conversions.msg_to_string(plan_msg))
681 return self.
_g_g.async_execute(conversions.msg_to_string(plan_msg))
684 """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 successfully sent to the move_group node. This does not verify that the attach request also was successfully applied by move_group."""
688 """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."""
691 def pick(self, object_name, grasp=[], plan_only=False):
692 """Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument."""
693 if type(grasp)
is Grasp:
695 object_name, conversions.msg_to_string(grasp), plan_only
699 object_name, [conversions.msg_to_string(x)
for x
in grasp], plan_only
702 def place(self, object_name, location=None, plan_only=False):
703 """Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided"""
706 result = self.
_g_g.
place(object_name, plan_only)
707 elif type(location)
is PoseStamped:
711 object_name, conversions.pose_to_list(location.pose), plan_only
714 elif type(location)
is Pose:
716 object_name, conversions.pose_to_list(location), plan_only
718 elif type(location)
is PlaceLocation:
720 object_name, conversions.msg_to_string(location), plan_only
722 elif type(location)
is list:
724 if type(location[0])
is PlaceLocation:
725 result = self.
_g_g.place_locations_list(
727 [conversions.msg_to_string(x)
for x
in location],
730 elif type(location[0])
is PoseStamped:
731 result = self.
_g_g.place_poses_list(
733 [conversions.msg_to_string(x)
for x
in location],
738 "Parameter location must be a Pose, PoseStamped, PlaceLocation, list of PoseStamped or list of PlaceLocation object"
742 "Parameter location must be a Pose, PoseStamped, PlaceLocation, list of PoseStamped or list of PlaceLocation object"
747 """Set the support surface name for a place operation"""
754 velocity_scaling_factor=1.0,
755 acceleration_scaling_factor=1.0,
756 algorithm="iterative_time_parameterization",
758 ser_ref_state_in = conversions.msg_to_string(ref_state_in)
759 ser_traj_in = conversions.msg_to_string(traj_in)
763 velocity_scaling_factor,
764 acceleration_scaling_factor,
767 traj_out = RobotTrajectory()
768 traj_out.deserialize(ser_traj_out)
772 """Get the jacobian matrix of the group as a list"""
775 [0.0, 0.0, 0.0]
if reference_point
is None else reference_point,
779 """Takes a moveit_msgs RobotState and enforces the state bounds, based on the C++ RobotState enforceBounds()"""
781 c_str = self.
_g_g.
enforce_bounds(conversions.msg_to_string(robot_state_msg))
782 conversions.msg_from_string(s, c_str)
def set_orientation_target(self, q, end_effector_link="")
def set_planning_time(self, seconds)
def allow_replanning(self, value)
def set_max_acceleration_scaling_factor(self, value)
def attach_object(self, object_name, link_name="", touch_links=[])
def get_known_constraints(self)
def has_end_effector_link(self)
def get_planning_pipeline_id(self)
def set_constraints_database(self, host, port)
def remember_joint_values(self, name, values=None)
def allow_looking(self, value)
def set_planning_pipeline_id(self, planning_pipeline)
def get_jacobian_matrix(self, joint_values, reference_point=None)
def set_goal_joint_tolerance(self, value)
def clear_path_constraints(self)
def set_planner_id(self, planner_id)
def clear_pose_targets(self)
def get_active_joints(self)
def get_goal_orientation_tolerance(self)
def clear_pose_target(self, end_effector_link)
def set_goal_orientation_tolerance(self, value)
def set_goal_tolerance(self, value)
def get_current_state(self)
def get_end_effector_link(self)
def set_trajectory_constraints(self, value)
def set_joint_value_target(self, arg1, arg2=None, arg3=None)
def get_trajectory_constraints(self)
def set_goal_position_tolerance(self, value)
def set_end_effector_link(self, link_name)
def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor=1.0, acceleration_scaling_factor=1.0, algorithm="iterative_time_parameterization")
def execute(self, plan_msg, wait=True)
def get_goal_tolerance(self)
def set_max_velocity_scaling_factor(self, value)
def forget_joint_values(self, name)
def plan(self, joints=None)
def get_current_pose(self, end_effector_link="")
def detach_object(self, name="")
def pick(self, object_name, grasp=[], plan_only=False)
def set_random_target(self)
def set_num_planning_attempts(self, num_planning_attempts)
def get_pose_reference_frame(self)
def get_random_pose(self, end_effector_link="")
def get_planning_time(self)
def set_named_target(self, name)
def set_support_surface_name(self, value)
def set_pose_target(self, pose, end_effector_link="")
def set_path_constraints(self, value)
def set_rpy_target(self, rpy, end_effector_link="")
def get_planning_frame(self)
def get_remembered_joint_values(self)
def enforce_bounds(self, robot_state_msg)
def set_pose_reference_frame(self, reference_frame)
def get_goal_position_tolerance(self)
def get_interface_description(self)
def get_joint_value_target(self)
def set_start_state_to_current_state(self)
def get_current_joint_values(self)
def set_start_state(self, msg)
def get_random_joint_values(self)
def get_path_constraints(self)
def set_pose_targets(self, poses, end_effector_link="")
def __init__(self, name, robot_description="robot_description", ns="", wait_for_servers=5.0)
def get_variable_count(self)
def set_position_target(self, xyz, end_effector_link="")
def construct_motion_plan_request(self)
def place(self, object_name, location=None, plan_only=False)
def clear_trajectory_constraints(self)
def get_current_rpy(self, end_effector_link="")
def get_named_targets(self)
def get_current_state_bounded(self)
def get_goal_joint_tolerance(self)
def get_named_target_values(self, target)
def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None)
def shift_pose_target(self, axis, value, end_effector_link="")
def set_workspace(self, ws)
def go(self, joints=None, wait=True)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest