igibson.robots package¶
Submodules¶
igibson.robots.ant_robot module¶
-
class
igibson.robots.ant_robot.
Ant
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
OpenAI Ant Robot Uses joint torque control
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
igibson.robots.fetch_robot module¶
-
class
igibson.robots.fetch_robot.
Fetch
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Fetch Robot Reference: https://fetchrobotics.com/robotics-platforms/fetch-mobile-manipulator/ Uses joint velocity control
-
end_effector_part_index
()¶ Get end-effector link id
-
get_end_effector_position
()¶ Get end-effector position
-
load
()¶ Load the robot into pybullet. Filter out unnecessary self collision due to modeling imperfection in the URDF
-
robot_specific_reset
()¶ Fetch robot specific reset. Reset the torso lift joint and tuck the arm towards the body
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
igibson.robots.freight_robot module¶
-
class
igibson.robots.freight_robot.
Freight
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Freight Robot Reference: https://fetchrobotics.com/robotics-platforms/freight-base/ Uses joint velocity control
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-
igibson.robots.humanoid_robot module¶
-
class
igibson.robots.humanoid_robot.
Humanoid
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
OpenAI Humanoid robot Uses joint torque control
-
apply_action
(action)¶ Apply policy action
-
robot_specific_reset
()¶ Humanoid robot specific reset Add spherical radiance/glass shield to protect the robot’s camera
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-
igibson.robots.husky_robot module¶
-
class
igibson.robots.husky_robot.
Husky
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Husky robot Reference: https://clearpathrobotics.com/, http://wiki.ros.org/Robots/Husky Uses joint torque control
-
alive_bonus
(z, pitch)¶ Deprecated code for reward computation
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-
steering_cost
(action)¶ Deprecated code for reward computation
-
igibson.robots.jr2_kinova_robot module¶
-
class
igibson.robots.jr2_kinova_robot.
JR2_Kinova
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
JR2 Kinova robot Reference: https://cvgl.stanford.edu/projects/jackrabbot/ Uses joint velocity control
-
get_end_effector_position
()¶ Get end-effector position
-
load
()¶ Load the robot into pybullet. Filter out unnecessary self collision due to modeling imperfection in the URDF
-
robot_specific_reset
()¶ JR2 Kinova robot specific reset. Initialize JR’s arm to about the same height at its neck, facing forward
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
igibson.robots.jr2_robot module¶
-
class
igibson.robots.jr2_robot.
JR2
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
JR2 robot (no arm) Reference: https://cvgl.stanford.edu/projects/jackrabbot/ Uses joint velocity control
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-
igibson.robots.locobot_robot module¶
-
class
igibson.robots.locobot_robot.
Locobot
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Locobot robot Reference: https://www.trossenrobotics.com/locobot-pyrobot-ros-rover.aspx Uses differentiable_drive / twist command control
-
get_end_effector_position
()¶ Get end-effector position
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
igibson.robots.minitaur_robot module¶
This file implements the functionalities of a minitaur using pybullet.
-
class
igibson.robots.minitaur_robot.
Minitaur
(config, env, pd_control_enabled=True, accurate_motor_model_enabled=True)¶ Bases:
igibson.robots.minitaur_robot.MinitaurBase
Wrapper class for gibson interface
- Attribtues:
self.eyes self.resolution self.walk_target_x, self.walk_target_y self.mjcf_scaling self.observation_space self.action_space self.sensor_space
- Interface:
self.apply_action() self.calc_state() self.addToScene()
-
calc_state
()¶ Calculate commonly used proprioceptive states for the robot
- Returns
proprioceptive states
-
class
igibson.robots.minitaur_robot.
MinitaurBase
(config, env=None, pd_control_enabled=True, accurate_motor_model_enabled=True)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Minitaur robot Reference: https://www.ghostrobotics.io/ Uses joint position control
-
BASE_LINK_ID
= -1¶
-
ConvertFromLegModel
(actions)¶ Convert the actions that use leg model to the real motor actions.
- Args:
actions: The theta, phi of the leg model.
- Returns:
The eight desired motor angles that can be used in ApplyAction().
-
FOOT_LINK_ID
= [3, 6, 9, 12, 16, 19, 22, 25]¶
-
GetActionDimension
()¶ Get the length of the action list.
- Returns:
The length of the action list.
-
GetBaseMassFromURDF
()¶ Get the mass of the base from the URDF file.
-
GetBaseOrientation
()¶ Get the orientation of minitaur’s base, represented as quaternion.
- Returns:
The orientation of minitaur’s base.
-
GetBasePosition
()¶ Get the position of minitaur’s base.
- Returns:
The position of minitaur’s base.
-
GetLegMassesFromURDF
()¶ Get the mass of the legs from the URDF file.
-
GetMotorAngles
()¶ Get the eight motor angles at the current moment.
- Returns:
Motor angles.
-
GetMotorTorques
()¶ Get the amount of torques the motors are exerting.
- Returns:
Motor torques of all eight motors.
-
GetMotorVelocities
()¶ Get the velocity of all eight motors.
- Returns:
Velocities of all eight motors.
-
GetObservation
()¶ Get the observations of minitaur.
It includes the angles, velocities, torques and the orientation of the base.
- Returns:
The observation list. observation[0:8] are motor angles. observation[8:16] are motor velocities, observation[16:24] are motor torques. observation[24:28] is the orientation of the base, in quaternion form.
-
GetObservationDimension
()¶ Get the length of the observation list.
- Returns:
The length of the observation list.
-
GetObservationLowerBound
()¶ Get the lower bound of the observation.
-
GetObservationUpperBound
()¶ Get the upper bound of the observation.
- Returns:
- The upper bound of an observation. See GetObservation() for the details
of each element of an observation.
-
KNEE_CONSTRAINT_POINT_LEFT
= [0, 0.01, 0.2]¶
-
KNEE_CONSTRAINT_POINT_RIGHT
= [0, 0.005, 0.2]¶
-
LEG_LINK_ID
= [2, 3, 5, 6, 8, 9, 11, 12, 15, 16, 18, 19, 21, 22, 24, 25]¶
-
LEG_POSITION
= ['front_left', 'back_left', 'front_right', 'back_right']¶
-
MOTOR_LINK_ID
= [1, 4, 7, 10, 14, 17, 20, 23]¶
-
MOTOR_NAMES
= ['motor_front_leftL_joint', 'motor_front_leftR_joint', 'motor_back_leftL_joint', 'motor_back_leftR_joint', 'motor_front_rightL_joint', 'motor_front_rightR_joint', 'motor_back_rightL_joint', 'motor_back_rightR_joint']¶
-
OBSERVATION_DIM
= 28¶
-
OVERHEAT_SHUTDOWN_TIME
= 1.0¶
-
OVERHEAT_SHUTDOWN_TORQUE
= 2.45¶
-
ResetPose
(add_constraint)¶ Reset the pose of the minitaur.
- Args:
add_constraint: Whether to add a constraint at the joints of two feet.
-
SetBaseMass
(base_mass)¶
-
SetBatteryVoltage
(voltage)¶
-
SetFootFriction
(foot_friction)¶ Set the lateral friction of the feet.
- Args:
- foot_friction: The lateral friction coefficient of the foot. This value is
shared by all four feet.
-
SetLegMasses
(leg_masses)¶ Set the mass of the legs.
A leg includes leg_link and motor. All four leg_links have the same mass, which is leg_masses[0]. All four motors have the same mass, which is leg_mass[1].
- Args:
- leg_masses: The leg masses. leg_masses[0] is the mass of the leg link.
leg_masses[1] is the mass of the motor.
-
SetMotorViscousDamping
(viscous_damping)¶
-
applied_motor_torques
= array([0., 0., 0., 0., 0., 0., 0., 0.])¶
-
apply_action
(motor_commands)¶ Set the desired motor angles to the motors of the minitaur.
Note (hzyjerry): motor commands are set based on desired angles, not torques
The desired motor angles are clipped based on the maximum allowed velocity. If the pd_control_enabled is True, a torque is calculated according to the difference between current and desired joint angle, as well as the joint velocity. This torque is exerted to the motor. For more information about PD control, please refer to: https://en.wikipedia.org/wiki/PID_controller.
- Args:
motor_commands: The eight desired motor angles.
-
calc_potential
()¶
-
calc_state
()¶ Calculate commonly used proprioceptive states for the robot
- Returns
proprioceptive states
-
default_scale
= 1¶
-
joint_name_to_id
= None¶ The minitaur class that simulates a quadruped robot from Ghost Robotics.
-
kd_for_pd_controllers
= 0.3¶
-
max_force
= 5.5¶
-
mjcf_scaling
= 1¶
-
model_type
= 'URDF'¶
-
motor_direction
= [-1, -1, -1, -1, 1, 1, 1, 1]¶
-
motor_kd
= 0.2¶
-
motor_kp
= 1.0¶
-
motor_overheat_protection
= True¶
-
motor_velocity_limit
= inf¶
-
num_legs
= 4¶
-
num_motors
= 8¶
-
observed_motor_torques
= array([0., 0., 0., 0., 0., 0., 0., 0.])¶
-
on_rack
= False¶
-
robot_specific_reset
(reload_urdf=True)¶ Reset the minitaur to its initial states.
- Parameters
reload_urdf – whether to reload the urdf file. If not, reset() just place the minitaur back to its starting position.
-
self_collision_enabled
= True¶
-
setup_keys_to_action
()¶
-
torque_control_enabled
= False¶
-
igibson.robots.quadrotor_robot module¶
-
class
igibson.robots.quadrotor_robot.
Quadrotor
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Quadrotor robot Reference: https://repository.upenn.edu/cgi/viewcontent.cgi?referer=https://www.google.com/&httpsredir=1&article=1705&context=edissertations Uses joint torque control
-
apply_action
(action)¶ Apply policy action. Zero gravity.
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-
igibson.robots.robot_base module¶
-
class
igibson.robots.robot_base.
BaseRobot
(model_file, base_name=None, scale=1, self_collision=False)¶ Bases:
object
Base class for mujoco xml/ROS urdf based agents. Handles object loading
-
calc_state
()¶ Calculate proprioceptive states for each specific robot. Overwritten by subclasses
-
load
()¶ Load the robot model into pybullet
- Returns
body id in pybullet
-
parse_robot
(bodies)¶ Parse the robot to get properties including joint information and mass
- Parameters
bodies – body ids in pybullet
- Returns
parts, joints, ordered_joints, robot_body, robot_mass
-
robot_specific_reset
()¶ Reset function for each specific robot. Overwritten by subclasses
-
-
class
igibson.robots.robot_base.
BodyPart
(body_name, bodies, body_index, body_part_index)¶ Bases:
object
Body part (link) of Robots
-
contact_list
()¶ Get contact points of the body part
-
current_orientation
()¶ Synonym method for get_orientation
-
current_position
()¶ Synonym method for get_position
-
get_angular_velocity
()¶ Get angular velocity of the body part
-
get_linear_velocity
()¶ Get linear velocity of the body part
-
get_name
()¶ Get name of body part
-
get_orientation
()¶ Get orientation of body part Orientation is by default defined in [x,y,z,w]
-
get_pose
()¶ Get pose of body part
-
get_position
()¶ Get position of body part
-
get_rpy
()¶ Get roll, pitch and yaw of body part [roll, pitch, yaw]
-
reset_orientation
(orientation)¶ Synonym method for set_orientation
-
reset_pose
(position, orientation)¶ Synonym method for set_pose
-
reset_position
(position)¶ Synonym method for set_position
-
set_orientation
(orientation)¶ Get position of body part Orientation is defined in [x,y,z,w]
-
set_pose
(position, orientation)¶ Set pose of body part
-
set_position
(position)¶ Get position of body part
-
-
class
igibson.robots.robot_base.
Joint
(joint_name, bodies, body_index, joint_index)¶ Bases:
object
Joint of Robots
-
current_position
()¶ Synonym method for get_state
-
current_relative_position
()¶ Synonym method for get_relative_state
-
disable_motor
()¶ disable the motor of joint
-
get_joint_relative_state
()¶ Synonym method for get_relative_state
-
get_relative_state
()¶ Get normalized state of joint
-
get_state
()¶ Get state of joint
-
reset_current_position
(position, velocity)¶ Synonym method for reset_state
-
reset_joint_state
(position, velocity)¶ Synonym method for reset_state
-
reset_position
(position, velocity)¶ Synonym method for reset_state
-
reset_state
(pos, vel)¶ Reset pos and vel of joint
-
set_motor_position
(pos)¶ Synonym method for set_position
-
set_motor_torque
(torque)¶ Synonym method for set_torque
-
set_motor_velocity
(vel)¶ Synonym method for set_velocity
-
set_position
(position)¶ Set position of joint
-
set_torque
(torque)¶ Set torque of joint
-
set_velocity
(velocity)¶ Set velocity of joint
-
igibson.robots.robot_locomotor module¶
-
class
igibson.robots.robot_locomotor.
LocomotorRobot
(filename, action_dim, base_name=None, scale=1.0, control='torque', is_discrete=True, torque_coef=1.0, velocity_coef=1.0, self_collision=False)¶ Bases:
igibson.robots.robot_base.BaseRobot
Built on top of BaseRobot. Provides common interface for a wide variety of robots.
-
apply_action
(action)¶ Apply policy action
-
apply_robot_action
(action)¶ Apply robot action. Support joint torque, velocity, position control and differentiable drive / twist command control
- Parameters
action – robot action
-
calc_state
()¶ Calculate commonly used proprioceptive states for the robot
- Returns
proprioceptive states
-
get_angular_velocity
()¶ Set robot base angular velocity
- Returns
base angular velocity
-
get_linear_velocity
()¶ Set robot base linear velocity
- Returns
base linear velocity
-
get_orientation
()¶ Return robot orientation
- Returns
quaternion in xyzw
-
get_position
()¶ Get current robot position
-
get_rpy
()¶ Return robot orientation in roll, pitch, yaw
- Returns
roll, pitch, yaw
-
keep_still
()¶ Keep the robot still. Apply zero velocity to all joints.
-
move_backward
(backward=0.05)¶ Move robot base backward without physics simulation
- Parameters
backward – delta base position backward
-
move_by
(delta)¶ Move robot base without physics simulation
- Parameters
delta – delta base position
-
move_forward
(forward=0.05)¶ Move robot base forward without physics simulation
- Parameters
forward – delta base position forward
-
policy_action_to_robot_action
(action)¶ Scale the policy action (always in [-1, 1]) to robot action based on action range
- Parameters
action – policy action
- Returns
robot action
-
robot_specific_reset
()¶ Robot specific reset. Apply zero velocity for all joints.
-
set_orientation
(orn)¶ Set robot orientation
- Parameters
orn – robot orientation
-
set_position
(pos)¶ Set robot position
- Parameters
pos – robot position
-
set_position_orientation
(pos, orn)¶ Set robot position and orientation
- Parameters
pos – robot position
orn – robot orientation
-
set_up_continuous_action_space
()¶ Each subclass implements their own continuous action spaces
-
set_up_discrete_action_space
()¶ Each subclass implements their own discrete action spaces
-
turn_left
(delta=0.03)¶ Rotate robot base left without physics simulation
- Parameters
delta – delta angle to rotate the base left
-
turn_right
(delta=0.03)¶ Rotate robot base right without physics simulation
- Parameters
delta – delta angle to rotate the base right
-
igibson.robots.turtlebot_robot module¶
-
class
igibson.robots.turtlebot_robot.
Turtlebot
(config)¶ Bases:
igibson.robots.robot_locomotor.LocomotorRobot
Turtlebot robot Reference: http://wiki.ros.org/Robots/TurtleBot Uses joint velocity control
-
set_up_continuous_action_space
()¶ Set up continuous action space
-
set_up_discrete_action_space
()¶ Set up discrete action space
-
setup_keys_to_action
()¶
-