polysim.envs package¶
Subpackages¶
Submodules¶
polysim.envs.abstract_env module¶
- class polysim.envs.abstract_env.AbstractControlledEnv¶
Bases:
ABC
Parent class for simulation environments.
- abstract apply_joint_torques(torques)¶
- input:
np.ndarray: Desired torques
- abstract get_current_joint_pos_vel()¶
- Returns:
Joint positions np.ndarray: Joint velocities
- Return type:
np.ndarray
- abstract get_current_joint_torques()¶
- Returns:
Torques received from apply_joint_torques np.ndarray: Torques sent to robot (e.g. after clipping) np.ndarray: Torques generated by the actuators (e.g. after grav comp) np.ndarray: Torques exerted onto the robot
- Return type:
np.ndarray
- abstract get_num_dofs()¶
Get the number of degrees of freedom for controlling the simulation.
- Returns:
Number of control input dimensions
- Return type:
int
- abstract reset()¶
Reset the environment.
- abstract set_robot_state(robot_state)¶
- input:
RobotState: Desired state of robot
polysim.envs.bullet_manipulator module¶
- class polysim.envs.bullet_manipulator.BulletManipulatorEnv(robot_model_cfg: DictConfig, gui: bool, use_grav_comp: bool = True, gravity: float = 9.81, extract_config_from_rdf=False)¶
Bases:
AbstractControlledEnv
A manipulator environment using PyBullet.
- Parameters:
robot_model_cfg – A Hydra configuration file containing information needed for the robot model, e.g. URDF. For an example, see polymetis/conf/robot_model/franka_panda.yaml
gui – Whether to initialize the PyBullet simulation in GUI mode.
use_grav_comp – If True, adds gravity compensation torques to the input torques.
- apply_joint_torques(torque: ndarray)¶
Applies a NumPy array of torques and returns the final applied torque (after gravity compensation, if used).
- compute_forward_kinematics(joint_pos: Optional[List[float]] = None)¶
Computes forward kinematics.
Warning
Uses PyBullet forward kinematics by resetting to the given joint position (or, if not given, the rest position). Therefore, drastically modifies simulation state!
- Parameters:
joint_pos – Joint positions for which to compute forward kinematics.
- Returns:
3-dimensional end-effector position
np.ndarray: 4-dimensional end-effector orientation as quaternion
- Return type:
np.ndarray
- compute_inverse_dynamics(joint_pos: ndarray, joint_vel: ndarray, joint_acc: ndarray)¶
Computes inverse dynamics by returning the torques necessary to get the desired accelerations at the given joint position and velocity.
- compute_inverse_kinematics(target_position: List[float], target_orientation: Optional[List[float]] = None)¶
Computes inverse kinematics.
Uses PyBullet to compute inverse kinematics.
- Parameters:
target_position – Desired end-effector position.
target_orientation – Desired end-effector orientation as quaternion.
- Returns:
Joint position satisfying the given target end-effector position/orientation.
- Return type:
np.ndarray
- get_current_joint_pos()¶
Returns current joint position as a NumPy array.
- get_current_joint_pos_vel()¶
Returns (current joint position, current joint velocity) as a tuple of NumPy arrays
- get_current_joint_torques()¶
Returns torques: [inputted, clipped, added with gravity compensation, and measured externally]
- get_current_joint_vel()¶
Returns current joint velocity as a NumPy array.
- get_num_dofs()¶
Return number of degrees of freedom for control
- static load_robot_description_from_sdf(abs_urdf_path: str, sim: BulletClient)¶
Loads a SDF file into the simulation.
- static load_robot_description_from_urdf(abs_urdf_path: str, sim: BulletClient)¶
Loads a URDF file into the simulation.
- reset(joint_pos: Optional[List[float]] = None, joint_vel: Optional[List[float]] = None)¶
Resets simulation to the given pose, or if not given, the default rest pose
- set_robot_state(robot_state)¶
- input:
RobotState: Desired state of robot