Public Member Functions | Private Attributes | List of all members
moveit_commander.move_group.MoveGroupCommander Class Reference
Inheritance diagram for moveit_commander.move_group.MoveGroupCommander:
Inheritance graph
[legend]

Public Member Functions

def __init__ (self, name, robot_description="robot_description", ns="", wait_for_servers=5.0)
 
def allow_looking (self, value)
 
def allow_replanning (self, value)
 
def attach_object (self, object_name, link_name="", touch_links=[])
 
def clear_max_cartesian_link_speed (self)
 
def clear_path_constraints (self)
 
def clear_pose_target (self, end_effector_link)
 
def clear_pose_targets (self)
 
def clear_trajectory_constraints (self)
 
def compute_cartesian_path (self, waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None)
 
def construct_motion_plan_request (self)
 
def detach_object (self, name="")
 
def enforce_bounds (self, robot_state_msg)
 
def execute (self, trajectory, wait=True)
 
def forget_joint_values (self, name)
 
def get_active_joints (self)
 
def get_current_joint_values (self)
 
def get_current_pose (self, end_effector_link="")
 
def get_current_rpy (self, end_effector_link="")
 
def get_current_state (self)
 
def get_current_state_bounded (self)
 
def get_end_effector_link (self)
 
def get_goal_joint_tolerance (self)
 
def get_goal_orientation_tolerance (self)
 
def get_goal_position_tolerance (self)
 
def get_goal_tolerance (self)
 
def get_interface_description (self)
 
def get_jacobian_matrix (self, joint_values, reference_point=None)
 
def get_joint_value_target (self)
 
def get_joints (self)
 
def get_known_constraints (self)
 
def get_name (self)
 
def get_named_target_values (self, target)
 
def get_named_targets (self)
 
def get_path_constraints (self)
 
def get_planner_id (self)
 
def get_planning_frame (self)
 
def get_planning_pipeline_id (self)
 
def get_planning_time (self)
 
def get_pose_reference_frame (self)
 
def get_random_joint_values (self)
 
def get_random_pose (self, end_effector_link="")
 
def get_remembered_joint_values (self)
 
def get_trajectory_constraints (self)
 
def get_variable_count (self)
 
def go (self, joints=None, wait=True)
 
def has_end_effector_link (self)
 
def limit_max_cartesian_link_speed (self, speed, link_name="")
 
def pick (self, object_name, grasp=[], plan_only=False)
 
def place (self, object_name, location=None, plan_only=False)
 
def plan (self, joints=None)
 
def remember_joint_values (self, name, values=None)
 
def retime_trajectory (self, ref_state_in, traj_in, velocity_scaling_factor=1.0, acceleration_scaling_factor=1.0, algorithm="iterative_time_parameterization")
 
def set_constraints_database (self, host, port)
 
def set_end_effector_link (self, link_name)
 
def set_goal_joint_tolerance (self, value)
 
def set_goal_orientation_tolerance (self, value)
 
def set_goal_position_tolerance (self, value)
 
def set_goal_tolerance (self, value)
 
def set_joint_value_target (self, arg1, arg2=None, arg3=None)
 
def set_max_acceleration_scaling_factor (self, value)
 
def set_max_velocity_scaling_factor (self, value)
 
def set_named_target (self, name)
 
def set_num_planning_attempts (self, num_planning_attempts)
 
def set_orientation_target (self, q, end_effector_link="")
 
def set_path_constraints (self, value)
 
def set_planner_id (self, planner_id)
 
def set_planning_pipeline_id (self, planning_pipeline)
 
def set_planning_time (self, seconds)
 
def set_pose_reference_frame (self, reference_frame)
 
def set_pose_target (self, pose, end_effector_link="")
 
def set_pose_targets (self, poses, end_effector_link="")
 
def set_position_target (self, xyz, end_effector_link="")
 
def set_random_target (self)
 
def set_rpy_target (self, rpy, end_effector_link="")
 
def set_start_state (self, msg)
 
def set_start_state_to_current_state (self)
 
def set_support_surface_name (self, value)
 
def set_trajectory_constraints (self, value)
 
def set_workspace (self, ws)
 
def shift_pose_target (self, axis, value, end_effector_link="")
 
def stop (self)
 

Private Attributes

 _g
 

Detailed Description

Execution of simple commands for a particular group

Definition at line 57 of file move_group.py.

Constructor & Destructor Documentation

◆ __init__()

def moveit_commander.move_group.MoveGroupCommander.__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.

Definition at line 62 of file move_group.py.

Member Function Documentation

◆ allow_looking()

def moveit_commander.move_group.MoveGroupCommander.allow_looking (   self,
  value 
)
Enable/disable looking around for motion planning

Definition at line 458 of file move_group.py.

◆ allow_replanning()

def moveit_commander.move_group.MoveGroupCommander.allow_replanning (   self,
  value 
)
Enable/disable replanning

Definition at line 462 of file move_group.py.

◆ attach_object()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 699 of file move_group.py.

◆ clear_max_cartesian_link_speed()

def moveit_commander.move_group.MoveGroupCommander.clear_max_cartesian_link_speed (   self)
Clear the maximum cartesian link speed.

Definition at line 593 of file move_group.py.

◆ clear_path_constraints()

def moveit_commander.move_group.MoveGroupCommander.clear_path_constraints (   self)
Specify that no path constraints are to be used during motion planning

Definition at line 489 of file move_group.py.

◆ clear_pose_target()

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 381 of file move_group.py.

◆ clear_pose_targets()

def moveit_commander.move_group.MoveGroupCommander.clear_pose_targets (   self)
Clear all known pose targets

Definition at line 385 of file move_group.py.

◆ clear_trajectory_constraints()

def moveit_commander.move_group.MoveGroupCommander.clear_trajectory_constraints (   self)
Specify that no trajectory constraints are to be used during motion planning

Definition at line 514 of file move_group.py.

◆ compute_cartesian_path()

def moveit_commander.move_group.MoveGroupCommander.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 the Kinematic constraints are not met, a partial solution will be returned.
The return value is a tuple: the actual RobotTrajectory and the fraction of how much of the path was followed.

Definition at line 647 of file move_group.py.

◆ construct_motion_plan_request()

def moveit_commander.move_group.MoveGroupCommander.construct_motion_plan_request (   self)
Returns a MotionPlanRequest filled with the current goals of the move_group_interface

Definition at line 642 of file move_group.py.

◆ detach_object()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 703 of file move_group.py.

◆ enforce_bounds()

def moveit_commander.move_group.MoveGroupCommander.enforce_bounds (   self,
  robot_state_msg 
)
Takes a moveit_msgs RobotState and enforces the state bounds, based on the C++ RobotState enforceBounds()

Definition at line 794 of file move_group.py.

◆ execute()

def moveit_commander.move_group.MoveGroupCommander.execute (   self,
  trajectory,
  wait = True 
)
Execute a previously planned path

Definition at line 689 of file move_group.py.

◆ forget_joint_values()

def moveit_commander.move_group.MoveGroupCommander.forget_joint_values (   self,
  name 
)
Forget a stored joint configuration

Definition at line 418 of file move_group.py.

◆ get_active_joints()

def moveit_commander.move_group.MoveGroupCommander.get_active_joints (   self)
Get the active joints of this group

Definition at line 78 of file move_group.py.

◆ get_current_joint_values()

def moveit_commander.move_group.MoveGroupCommander.get_current_joint_values (   self)
Get the current configuration of the group as a list (these are values published on /joint_states)

Definition at line 121 of file move_group.py.

◆ get_current_pose()

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 125 of file move_group.py.

◆ get_current_rpy()

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 136 of file move_group.py.

◆ get_current_state()

def moveit_commander.move_group.MoveGroupCommander.get_current_state (   self)
Get the current state of the robot.

Definition at line 189 of file move_group.py.

◆ get_current_state_bounded()

def moveit_commander.move_group.MoveGroupCommander.get_current_state_bounded (   self)
Get the current state of the robot bounded.

Definition at line 182 of file move_group.py.

◆ get_end_effector_link()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 94 of file move_group.py.

◆ get_goal_joint_tolerance()

def moveit_commander.move_group.MoveGroupCommander.get_goal_joint_tolerance (   self)
Get the tolerance for achieving a joint goal (distance for each joint variable)

Definition at line 430 of file move_group.py.

◆ get_goal_orientation_tolerance()

def moveit_commander.move_group.MoveGroupCommander.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

Definition at line 438 of file move_group.py.

◆ get_goal_position_tolerance()

def moveit_commander.move_group.MoveGroupCommander.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

Definition at line 434 of file move_group.py.

◆ get_goal_tolerance()

def moveit_commander.move_group.MoveGroupCommander.get_goal_tolerance (   self)
Return a tuple of goal tolerances: joint, position and orientation.

Definition at line 422 of file move_group.py.

◆ get_interface_description()

def moveit_commander.move_group.MoveGroupCommander.get_interface_description (   self)
Get the description of the planner interface (list of planner ids)

Definition at line 103 of file move_group.py.

◆ get_jacobian_matrix()

def moveit_commander.move_group.MoveGroupCommander.get_jacobian_matrix (   self,
  joint_values,
  reference_point = None 
)
Get the jacobian matrix of the group as a list

Definition at line 787 of file move_group.py.

◆ get_joint_value_target()

def moveit_commander.move_group.MoveGroupCommander.get_joint_value_target (   self)

Definition at line 196 of file move_group.py.

◆ get_joints()

def moveit_commander.move_group.MoveGroupCommander.get_joints (   self)
Get the joints of this group

Definition at line 82 of file move_group.py.

◆ get_known_constraints()

def moveit_commander.move_group.MoveGroupCommander.get_known_constraints (   self)
Get a list of names for the constraints specific for this group, as read from the warehouse

Definition at line 466 of file move_group.py.

◆ get_name()

def moveit_commander.move_group.MoveGroupCommander.get_name (   self)
Get the name of the group this instance was initialized for

Definition at line 70 of file move_group.py.

◆ get_named_target_values()

def moveit_commander.move_group.MoveGroupCommander.get_named_target_values (   self,
  target 
)
Get a dictionary of joint values of a named target

Definition at line 404 of file move_group.py.

◆ get_named_targets()

def moveit_commander.move_group.MoveGroupCommander.get_named_targets (   self)
Get a list of all the names of joint configurations.

Definition at line 393 of file move_group.py.

◆ get_path_constraints()

def moveit_commander.move_group.MoveGroupCommander.get_path_constraints (   self)
Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints

Definition at line 470 of file move_group.py.

◆ get_planner_id()

def moveit_commander.move_group.MoveGroupCommander.get_planner_id (   self)
Get the current planner_id (e.g. RRTConnect, LIN) of the currently selected pipeline

Definition at line 542 of file move_group.py.

◆ get_planning_frame()

def moveit_commander.move_group.MoveGroupCommander.get_planning_frame (   self)
Get the name of the frame where all planning is performed

Definition at line 117 of file move_group.py.

◆ get_planning_pipeline_id()

def moveit_commander.move_group.MoveGroupCommander.get_planning_pipeline_id (   self)
Get the current planning_pipeline_id (e.g. ompl, pilz_industrial_motion_planner)

Definition at line 534 of file move_group.py.

◆ get_planning_time()

def moveit_commander.move_group.MoveGroupCommander.get_planning_time (   self)
Specify the amount of time to be used for motion planning.

Definition at line 526 of file move_group.py.

◆ get_pose_reference_frame()

def moveit_commander.move_group.MoveGroupCommander.get_pose_reference_frame (   self)
Get the reference frame assumed for poses of end-effectors

Definition at line 109 of file move_group.py.

◆ get_random_joint_values()

def moveit_commander.move_group.MoveGroupCommander.get_random_joint_values (   self)

Definition at line 143 of file move_group.py.

◆ get_random_pose()

def moveit_commander.move_group.MoveGroupCommander.get_random_pose (   self,
  end_effector_link = "" 
)

Definition at line 146 of file move_group.py.

◆ get_remembered_joint_values()

def moveit_commander.move_group.MoveGroupCommander.get_remembered_joint_values (   self)
Get a dictionary that maps names to joint configurations for the group

Definition at line 414 of file move_group.py.

◆ get_trajectory_constraints()

def moveit_commander.move_group.MoveGroupCommander.get_trajectory_constraints (   self)
Get the actual trajectory constraints in form of a moveit_msgs.msgs.TrajectoryConstraints

Definition at line 493 of file move_group.py.

◆ get_variable_count()

def moveit_commander.move_group.MoveGroupCommander.get_variable_count (   self)
Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)

Definition at line 86 of file move_group.py.

◆ go()

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 597 of file move_group.py.

◆ has_end_effector_link()

def moveit_commander.move_group.MoveGroupCommander.has_end_effector_link (   self)
Check if this group has a link that is considered to be an end effector

Definition at line 90 of file move_group.py.

◆ limit_max_cartesian_link_speed()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 585 of file move_group.py.

◆ pick()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 707 of file move_group.py.

◆ place()

def moveit_commander.move_group.MoveGroupCommander.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

Definition at line 718 of file move_group.py.

◆ plan()

def moveit_commander.move_group.MoveGroupCommander.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)

Definition at line 619 of file move_group.py.

◆ remember_joint_values()

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 408 of file move_group.py.

◆ retime_trajectory()

def moveit_commander.move_group.MoveGroupCommander.retime_trajectory (   self,
  ref_state_in,
  traj_in,
  velocity_scaling_factor = 1.0,
  acceleration_scaling_factor = 1.0,
  algorithm = "iterative_time_parameterization" 
)

Definition at line 766 of file move_group.py.

◆ set_constraints_database()

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 518 of file move_group.py.

◆ set_end_effector_link()

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 98 of file move_group.py.

◆ set_goal_joint_tolerance()

def moveit_commander.move_group.MoveGroupCommander.set_goal_joint_tolerance (   self,
  value 
)
Set the tolerance for a target joint configuration

Definition at line 446 of file move_group.py.

◆ set_goal_orientation_tolerance()

def moveit_commander.move_group.MoveGroupCommander.set_goal_orientation_tolerance (   self,
  value 
)
Set the tolerance for a target end-effector orientation

Definition at line 454 of file move_group.py.

◆ set_goal_position_tolerance()

def moveit_commander.move_group.MoveGroupCommander.set_goal_position_tolerance (   self,
  value 
)
Set the tolerance for a target end-effector position

Definition at line 450 of file move_group.py.

◆ set_goal_tolerance()

def moveit_commander.move_group.MoveGroupCommander.set_goal_tolerance (   self,
  value 
)
Set the joint, position and orientation goal tolerances simultaneously

Definition at line 442 of file move_group.py.

◆ set_joint_value_target()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 199 of file move_group.py.

◆ set_max_acceleration_scaling_factor()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 575 of file move_group.py.

◆ set_max_velocity_scaling_factor()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 565 of file move_group.py.

◆ set_named_target()

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 397 of file move_group.py.

◆ set_num_planning_attempts()

def moveit_commander.move_group.MoveGroupCommander.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.

Definition at line 546 of file move_group.py.

◆ set_orientation_target()

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 301 of file move_group.py.

◆ set_path_constraints()

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 477 of file move_group.py.

◆ set_planner_id()

def moveit_commander.move_group.MoveGroupCommander.set_planner_id (   self,
  planner_id 
)
Specify which planner of the currently selected pipeline to use when motion planning (e.g. RRTConnect, LIN)

Definition at line 538 of file move_group.py.

◆ set_planning_pipeline_id()

def moveit_commander.move_group.MoveGroupCommander.set_planning_pipeline_id (   self,
  planning_pipeline 
)
Specify which planning pipeline to use when motion planning (e.g. ompl, pilz_industrial_motion_planner)

Definition at line 530 of file move_group.py.

◆ set_planning_time()

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 522 of file move_group.py.

◆ set_pose_reference_frame()

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 113 of file move_group.py.

◆ set_pose_target()

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 328 of file move_group.py.

◆ set_pose_targets()

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 353 of file move_group.py.

◆ set_position_target()

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 316 of file move_group.py.

◆ set_random_target()

def moveit_commander.move_group.MoveGroupCommander.set_random_target (   self)
Set a random joint configuration target

Definition at line 389 of file move_group.py.

◆ set_rpy_target()

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 286 of file move_group.py.

◆ set_start_state()

def moveit_commander.move_group.MoveGroupCommander.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)

Definition at line 159 of file move_group.py.

◆ set_start_state_to_current_state()

def moveit_commander.move_group.MoveGroupCommander.set_start_state_to_current_state (   self)

Definition at line 156 of file move_group.py.

◆ set_support_surface_name()

def moveit_commander.move_group.MoveGroupCommander.set_support_surface_name (   self,
  value 
)
Set the support surface name for a place operation

Definition at line 762 of file move_group.py.

◆ set_trajectory_constraints()

def moveit_commander.move_group.MoveGroupCommander.set_trajectory_constraints (   self,
  value 
)
Specify the trajectory constraints to be used (setting from database is not implemented yet)

Definition at line 500 of file move_group.py.

◆ set_workspace()

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 550 of file move_group.py.

◆ shift_pose_target()

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 364 of file move_group.py.

◆ stop()

def moveit_commander.move_group.MoveGroupCommander.stop (   self)
Stop the current execution, if any

Definition at line 74 of file move_group.py.

Member Data Documentation

◆ _g

moveit_commander.move_group.MoveGroupCommander._g
private

Definition at line 64 of file move_group.py.


The documentation for this class was generated from the following file:


moveit_commander
Author(s): Ioan Sucan
autogenerated on Sun Mar 3 2024 03:25:22