pyCub

class pycub.EndEffector(name, client)[source]

Bases: object

Help function for end-effector encapsulaation

Parameters:
  • name (str) – name of the end-effector

  • client (pointer to pyCub instance) – parent client

get_position()[source]

Function to get current position of the end-effector

class pycub.Joint(name, robot_joint_id, joints_id, lower_limit, upper_limit, max_force, max_velocity)[source]

Bases: object

Help class to encapsulate joint information

Parameters:
  • name (str) – name of the joint

  • robot_joint_id (int) – id of the joint in pybullet

  • joints_id (int) – id of the joint in pycub.joints

  • lower_limit (float) – lower limit of the joint

  • upper_limit (float) – upper limit of the joint

  • max_force (float) – max force of the joint

  • max_velocity (float) – max velocity of the joint

Bases: object

Help function to encapsulate link information

Parameters:
  • name (str) – name of the link

  • robot_link_id (int) – id of the link in pybullet

  • urdf_link (int) – id of the link in pycub.urdfs[“robot”].links

class pycub.pyCub(config='default.yaml')[source]

Bases: BulletClient

Client class which inherits from BulletClient and contains the whole simulation functionality

Parameters:

config (str, optional, default="default.yaml") – path to the config file

static bbox_overlap(b1_min, b1_max, b2_min, b2_max)[source]
compute_skin()[source]

Function to emulate skin activations using ray casting.

contactPoints = {'DISTANCE': 8, 'FLAG': 0, 'FORCE': 9, 'FRICTION1': 10, 'FRICTION2': 12, 'FRICTIONDIR1': 11, 'FRICTIONDIR2': 13, 'IDA': 1, 'IDB': 2, 'INDEXA': 3, 'INDEXB': 4, 'NORMAL': 7, 'POSITIONA': 5, 'POSITIONB': 6}
create_urdf(object_path, fixed, color, suffix='')[source]

Creates a URDF for the given .obj file

Parameters:
  • object_path (str) – path to the .obj

  • fixed (bool) – whether the object is fixed in space

  • color (list of 3 floats) – color of the object

dynamicsInfo = {'BODYTYPE': 10, 'DAMPING': 8, 'FRICTION': 1, 'INERTIAOR': 4, 'INERTIAPOS': 3, 'INTERTIADIAGONAL': 2, 'MARGIN': 11, 'MASS': 0, 'RESTITUTION': 5, 'ROLLINGFRICTION': 6, 'SPINNINGFRICTION': 7, 'STIFFNESS': 9}
find_joint_id(joint_name)[source]

Help function to get indexes from joint name of joint index in self.joints list

Parameters:

joint_name (str or int) – name or index of the link

Returns:

joint id in pybullet and pycub space

Return type:

int, int

Help function to find link id from mesh name

Parameters:
  • mesh_name (str) – name of the mesh (only basename with extension)

  • robot (int, optional, default=None) – robot pybullet id

  • urdf_name (str, optional, default="robot") – name of the object in pycub.urdfs

Returns:

id of the link in pybullet space

Return type:

int

get_cameraimages()[source]

Gets the images from enabled eye cameras

Returns:

list of numpy arrays

Return type:

list

get_joint_state(joints=None)[source]

Get the state of the specified joints

Parameters:

joints (int or list, optional, default=None) – joint or list of joints to get the state of

Returns:

list of states of the joints

Return type:

list

init_robot()[source]

Load the robot URDF and get its joints’ information

Returns:

robot and its joints

Return type:

int or list

is_alive()[source]

Checks whether the engine is still running

Returns:

True when running

Return type:

bool

jointInfo = {'AXIS': 13, 'DAMPING': 6, 'FLAGS': 5, 'FRICTION': 7, 'INDEX': 0, 'LINKNAME': 12, 'LOWERLIMIT': 8, 'MAXFORCE': 10, 'MAXVELOCITY': 11, 'NAME': 1, 'PARENTINDEX': 16, 'PARENTORN': 15, 'PARENTPOS': 14, 'QINDEX': 3, 'TYPE': 2, 'UINDEX': 4, 'UPPERLIMIT': 9}
jointStates = {'FORCES': 2, 'POSITION': 0, 'TORQUE': 3, 'VELOCITY': 1}
kill_open3d()[source]
linkInfo = {'ANGVEL': 7, 'INERTIAORI': 3, 'INERTIAPOS': 2, 'LINVEL': 6, 'URDFORI': 5, 'URDFPOS': 4, 'WORLDORI': 1, 'WORLDPOS': 0}
motion_done(joints=None, check_collision=True)[source]

Checks whether the motion is done.

Parameters:
  • joints (int or list, optional, default=None) – joint or list of joints to get the state of

  • check_collision (bool, optional, default=True) – whether to check for collision during motion

Returns:

True when motion is done, false otherwise

Return type:

bool

move_cartesian(pose, wait=True, velocity=1, check_collision=True)[source]

Move the robot in cartesian space by computing inverse kinematics and running position control

Parameters:
  • pose (utils.Pose) – desired pose of the end effector

  • wait (bool, optional, default=True) – whether to wait for movement completion

  • velocity (float, optional, default=1) – joint velocity to move with

  • check_collision (bool, optional, default=True) – whether to check for collisions during motion

move_position(joints, positions, wait=True, velocity=1, set_col_state=True, check_collision=True)[source]

Move the specified joints to the given positions

Parameters:
  • joints (int, list, str) – joint or list of joints to move

  • positions (float or list) – position or list of positions to move the joints to

  • wait (bool, optional, default=True) – whether to wait until the motion is done

  • velocity (float, optional, default=1) – velocity to move the joints with

  • set_col_state (bool, optional, default=True) – whether to reset collision state

  • check_collision (bool, optional, default=True) – whether to check for collision during motion

move_velocity(joints, velocities)[source]

Move the specified joints with the specified velocity IT IS HERE, BUT NOT IN WORKING STATE

Parameters:
  • joints (int or list) – joint or list of joints to move

  • velocities (float or list) – velocity or list of velocities to move the joints to

prepare_log()[source]

Prepares the log string

Returns:

log string

Return type:

str

print_collision_info(c=None)[source]

Help function to print collision info

Parameters:

c (list, optional, default=None) – one collision

run_vhacd()[source]

Function to run VHACD on all objects in loaded URDFs, and to create new URDFs with changed collision meshes

static scale_bbox(bbox, scale)[source]
stop_robot()[source]

Stops the robot

toggle_gravity()[source]

Toggles the gravity

update_simulation(sleep_duration=0.01)[source]

Updates the simulation

Parameters:

sleep_duration (float, optional, default=0.01) – duration to sleep before the next simulation step

visualShapeData = {'COLOR': 7, 'DIMS': 3, 'FILE': 4, 'GEOMTYPE': 2, 'ID': 0, 'LINK': 1, 'ORI': 6, 'POS': 5, 'TEXTURE': 8}
wait_motion_done(sleep_duration=0.01, check_collision=True)[source]

Help function to wait for motion to be done. Can sleep for a specific duration

Parameters:
  • sleep_duration (float, optional, default=0.01) – how long to sleep before running simulation step

  • check_collision (bool, optional, default=True) – whether to check for collisions during motion