pyrep.robots.arms package

Submodules

pyrep.robots.arms.arm module

class pyrep.robots.arms.arm.Arm(count: int, name: str, num_joints: int, base_name: str = None, max_velocity=1.0, max_acceleration=4.0, max_jerk=1000)

Bases: pyrep.robots.robot_component.RobotComponent

Base class representing a robot arm with path planning support.

check_arm_collision(obj: Optional[pyrep.objects.object.Object] = None) → bool

Checks whether two entities are colliding.

Parameters:obj – The other collidable object to check collision against, or None to check against all collidable objects. Note that objects must be marked as collidable!
Returns:If the object is colliding.
get_configs_for_tip_pose(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, ignore_collisions=False, trials=300, max_configs=60, relative_to: pyrep.objects.object.Object = None) → List[List[float]]

Gets a valid joint configuration for a desired end effector pose. Must specify either rotation in euler or quaternions, but not both! :param position: The x, y, z position of the target. :param euler: The x, y, z orientation of the target (in radians). :param quaternion: A list containing the quaternion (x,y,z,w). :param ignore_collisions: If collision checking should be disabled. :param trials: The maximum number of attempts to reach max_configs :param max_configs: The maximum number of configurations we want to

generate before ranking them.
Parameters:relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose. :raises: ConfigurationError if no joint configuration could be found. :return: A list of valid joint configurations for the desired end effector pose.

get_jacobian()

Calculates the Jacobian.

Returns:the row-major Jacobian matix.
get_linear_path(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, steps=50, ignore_collisions=False, relative_to: pyrep.objects.object.Object = None) → pyrep.robots.configuration_paths.arm_configuration_path.ArmConfigurationPath

Gets a linear configuration path given a target pose.

Generates a path that drives a robot from its current configuration to its target dummy in a straight line (i.e. shortest path in Cartesian space).

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • steps – The desired number of path points. Each path point contains a robot configuration. A minimum of two path points is required. If the target pose distance is large, a larger number of steps leads to better results for this function.
  • ignore_collisions – If collision checking should be disabled.
  • relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose. :raises: ConfigurationPathError if no path could be created.

Returns:A linear path in the arm configuration space.
get_nonlinear_path(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, ignore_collisions=False, trials=300, max_configs=1, distance_threshold: float = 0.65, max_time_ms: int = 10, trials_per_goal=1, algorithm=<ConfigurationPathAlgorithms.SBL: 'SBL'>, relative_to: pyrep.objects.object.Object = None) → pyrep.robots.configuration_paths.arm_configuration_path.ArmConfigurationPath

Gets a non-linear (planned) configuration path given a target pose.

A path is generated by finding several configs for a pose, and ranking them according to the distance in configuration space (smaller is better).

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • ignore_collisions – If collision checking should be disabled.
  • trials – The maximum number of attempts to reach max_configs. See ‘solve_ik_via_sampling’.
  • max_configs – The maximum number of configurations we want to generate before sorting them. See ‘solve_ik_via_sampling’.
  • distance_threshold – Distance indicating when IK should be computed in order to try to bring the tip onto the target. See ‘solve_ik_via_sampling’.
  • max_time_ms – Maximum time in ms spend searching for each configuation. See ‘solve_ik_via_sampling’.
  • trials_per_goal – The number of paths per config we want to trial.
  • algorithm – The algorithm for path planning to use.
  • relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose. :raises: ConfigurationPathError if no path could be created.

Returns:A non-linear path in the arm configuration space.
get_path(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, ignore_collisions=False, trials=300, max_configs=1, distance_threshold: float = 0.65, max_time_ms: int = 10, trials_per_goal=1, algorithm=<ConfigurationPathAlgorithms.SBL: 'SBL'>, relative_to: pyrep.objects.object.Object = None) → pyrep.robots.configuration_paths.arm_configuration_path.ArmConfigurationPath

Tries to get a linear path, failing that tries a non-linear path.

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • ignore_collisions – If collision checking should be disabled.
  • trials – The maximum number of attempts to reach max_configs. See ‘solve_ik_via_sampling’.
  • max_configs – The maximum number of configurations we want to generate before sorting them. See ‘solve_ik_via_sampling’.
  • distance_threshold – Distance indicating when IK should be computed in order to try to bring the tip onto the target. See ‘solve_ik_via_sampling’.
  • max_time_ms – Maximum time in ms spend searching for each configuation. See ‘solve_ik_via_sampling’.
  • trials_per_goal – The number of paths per config we want to trial.
  • algorithm – The algorithm for path planning to use.
  • relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose.

Raises:ConfigurationPathError if neither a linear or non-linear path can be created.
Returns:A linear or non-linear path in the arm configuration space.
get_path_from_cartesian_path(path: pyrep.objects.cartesian_path.CartesianPath) → pyrep.robots.configuration_paths.arm_configuration_path.ArmConfigurationPath

Translate a path from cartesian space, to arm configuration space.

Note: It must be possible to reach the start of the path via a linear path, otherwise an error will be raised.

Parameters:path – A CartesianPath instance to be translated to a configuration-space path.
Raises:ConfigurationPathError if no path could be created.
Returns:A path in the arm configuration space.
get_tip() → pyrep.objects.dummy.Dummy

Gets the tip of the arm.

Each arm is required to have a tip for path planning.

Returns:The tip of the arm.
set_ik_element_properties(constraint_x=True, constraint_y=True, constraint_z=True, constraint_alpha_beta=True, constraint_gamma=True) → None
set_ik_group_properties(resolution_method='pseudo_inverse', max_iterations=6, dls_damping=0.1) → None
solve_ik(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, relative_to: pyrep.objects.object.Object = None) → List[float]

Solves an IK group and returns the calculated joint values.

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose. :return: A list containing the calculated joint values.

solve_ik_via_jacobian(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, relative_to: pyrep.objects.object.Object = None) → List[float]

Solves an IK group and returns the calculated joint values.

This IK method performs a linearisation around the current robot configuration via the Jacobian. The linearisation is valid when the start and goal pose are not too far away, but after a certain point, linearisation will no longer be valid. In that case, the user is better off using ‘solve_ik_via_sampling’.

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • relative_to – Indicates relative to which reference frame we want

the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose. :return: A list containing the calculated joint values.

solve_ik_via_sampling(position: Union[List[float], numpy.ndarray], euler: Union[List[float], numpy.ndarray] = None, quaternion: Union[List[float], numpy.ndarray] = None, ignore_collisions: bool = False, trials: int = 300, max_configs: int = 1, distance_threshold: float = 0.65, max_time_ms: int = 10, relative_to: pyrep.objects.object.Object = None) → numpy.ndarray

Solves an IK group and returns the calculated joint values.

This IK method performs a random searches for manipulator configurations that matches the given end-effector pose in space. When the tip pose is close enough then IK is computed in order to try to bring the tip onto the target. This is the method that should be used when the start pose is far from the end pose.

We generate ‘max_configs’ number of samples within X number of ‘trials’, before ranking them according to angular distance.

Must specify either rotation in euler or quaternions, but not both!

Parameters:
  • position – The x, y, z position of the target.
  • euler – The x, y, z orientation of the target (in radians).
  • quaternion – A list containing the quaternion (x,y,z,w).
  • ignore_collisions – If collision checking should be disabled.
  • trials – The maximum number of attempts to reach max_configs.
  • max_configs – The maximum number of configurations we want to generate before sorting them.
  • distance_threshold – Distance indicating when IK should be computed in order to try to bring the tip onto the target.
  • max_time_ms – Maximum time in ms spend searching for each configuation.
  • relative_to – Indicates relative to which reference frame we want the target pose. Specify None to retrieve the absolute pose, or an Object relative to whose reference frame we want the pose.
Raises:

ConfigurationError if no joint configuration could be found.

Returns:

‘max_configs’ number of joint configurations, ranked according to angular distance.

pyrep.robots.arms.configuration_path module

pyrep.robots.arms.mico module

class pyrep.robots.arms.mico.Mico(count: int = 0)

Bases: pyrep.robots.arms.arm.Arm

pyrep.robots.arms.panda module

class pyrep.robots.arms.panda.Panda(count: int = 0)

Bases: pyrep.robots.arms.arm.Arm

Module contents