Robot

class panda_gym.envs.core.PyBulletRobot(sim: PyBullet, body_name: str, file_name: str, base_position: ndarray, action_space: Space, joint_indices: ndarray, joint_forces: ndarray)

Base class for robot env.

Parameters:
  • sim (PyBullet) – Simulation instance.

  • body_name (str) – The name of the robot within the simulation.

  • file_name (str) – Path of the urdf file.

  • base_position (np.ndarray) – Position of the base of the robot as (x, y, z).

control_joints(target_angles: ndarray) None

Control the joints of the robot.

Parameters:

target_angles (np.ndarray) – The target angles. The length of the array must equal to the number of joints.

get_joint_angle(joint: int) float

Returns the angle of a joint

Parameters:

joint (int) – The joint index.

Returns:

float – Joint angle

get_joint_velocity(joint: int) float

Returns the velocity of a joint as (wx, wy, wz)

Parameters:

joint (int) – The joint index.

Returns:

np.ndarray – Joint velocity as (wx, wy, wz)

Returns the position of a link as (x, y, z)

Parameters:

link (int) – The link index.

Returns:

np.ndarray – Position as (x, y, z)

Returns the velocity of a link as (vx, vy, vz)

Parameters:

link (int) – The link index.

Returns:

np.ndarray – Velocity as (vx, vy, vz)

abstract get_obs() ndarray

Return the observation associated to the robot.

Returns:

np.ndarray – The observation.

inverse_kinematics(link: int, position: ndarray, orientation: ndarray) ndarray

Compute the inverse kinematics and return the new joint values.

Parameters:
  • link (int) – The link.

  • position (x, y, z) – Desired position of the link.

  • orientation (x, y, z, w) – Desired orientation of the link.

Returns:

List of joint values.

abstract reset() None

Reset the robot and return the observation.

abstract set_action(action: ndarray) None

Set the action. Must be called just before sim.step().

Parameters:

action (np.ndarray) – The action.

set_joint_angles(angles: ndarray) None

Set the joint position of a body. Can induce collisions.

Parameters:

angles (list) – Joint angles.

setup() None

Called after robot loading.