spotmicro package

Submodules

spotmicro.env_randomizer_base module

Abstract base class for environment randomizer. Source: https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizer_base.py

class spotmicro.env_randomizer_base.EnvRandomizerBase[source]

Bases: object

Abstract base class for environment randomizer.

An EnvRandomizer is called in environment.reset(). It will randomize physical parameters of the objects in the simulation. The physical parameters will be fixed for that episode and be randomized again in the next environment.reset().

randomize_env(env)[source]

Randomize the simulated_objects in the environment.

Args:
env: The environment to be randomized.

spotmicro.heightfield module

CODE BASED ON EXAMPLE FROM: @misc{coumans2017pybullet,

title={Pybullet, a python module for physics simulation in robotics, games and machine learning}, author={Coumans, Erwin and Bai, Yunfei}, url={www.pybullet.org}, year={2017},

}

Example: heightfield.py https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/examples/heightfield.py

class spotmicro.heightfield.HeightField[source]

Bases: object

UpdateHeightField(heightPerturbationRange=0.08)[source]

spotmicro.motor module

This file implements an accurate motor model. Source: https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py

class spotmicro.motor.MotorModel(torque_control_enabled=False, kp=1.2, kd=0)[source]

Bases: object

The accurate motor model, which is based on the physics of DC motors.

The motor model support two types of control: position control and torque control. In position control mode, a desired motor angle is specified, and a torque is computed based on the internal motor model. When the torque control is specified, a pwm signal in the range of [-1.0, 1.0] is converted to the torque.

The internal motor model takes the following factors into consideration: pd gains, viscous friction, back-EMF voltage and current-torque profile.

convert_to_torque(motor_commands, current_motor_angle, current_motor_velocity)[source]

Convert the commands (position control or torque control) to torque.

Args:
motor_commands: The desired motor angle if the motor is in position
control mode. The pwm signal if the motor is in torque control mode.

current_motor_angle: The motor angle at the current time step. current_motor_velocity: The motor velocity at the current time step.

Returns:
actual_torque: The torque that needs to be applied to the motor. observed_torque: The torque observed by the sensor.
get_viscous_dampling()[source]
get_voltage()[source]
set_viscous_damping(viscous_damping)[source]
set_voltage(voltage)[source]

spotmicro.spot module

CODE BASED ON EXAMPLE FROM: @misc{coumans2017pybullet,

title={Pybullet, a python module for physics simulation in robotics, games and machine learning}, author={Coumans, Erwin and Bai, Yunfei}, url={www.pybullet.org}, year={2017},

}

Example: minitaur.py https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_envs/bullet/minitaur.py

spotmicro.spot.MapToMinusPiToPi(angles)[source]

Maps a list of angles to [-pi, pi].

Args:
angles: A list of angles in rad.
Returns:
A list of angle mapped to [-pi, pi].
class spotmicro.spot.Spot(pybullet_client, urdf_root='/home/docs/checkouts/readthedocs.org/user_builds/spot-mini-mini/checkouts/latest/spotmicro/util/pybullet_data', time_step=0.01, action_repeat=1, self_collision_enabled=False, motor_velocity_limit=9.7, pd_control_enabled=False, accurate_motor_model_enabled=False, remove_default_joint_damping=False, max_force=100.0, motor_kp=1.0, motor_kd=0.02, pd_latency=0.0, control_latency=0.0, observation_noise_stdev=(0.0, 0.0, 0.0, 0.0, 0.0), torque_control_enabled=False, motor_overheat_protection=False, on_rack=False, kd_for_pd_controllers=0.3, pose_id='stand', np_random=<module 'numpy.random' from '/home/docs/checkouts/readthedocs.org/user_builds/spot-mini-mini/envs/latest/lib/python3.7/site-packages/numpy/random/__init__.py'>, contacts=True)[source]

Bases: object

The spot class that simulates a quadruped robot.

ApplyAction(motor_commands)[source]

Set the desired motor angles to the motors of the minitaur. 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.
ApplyMotorLimits(joint_angles)[source]
ConvertFromLegModel(action)[source]
GetActionDimension()[source]

Get the length of the action list.

Returns:
The length of the action list.
GetBaseInertiasFromURDF()[source]

Get the inertia of the base from the URDF file.

GetBaseMassFromURDF()[source]

Get the mass of the base from the URDF file.

GetBaseMassesFromURDF()[source]

Get the mass of the base from the URDF file.

GetBaseOrientation()[source]

Get the orientation of spot’s base, represented as quaternion.

Returns:
The orientation of spot’s base.
GetBasePosition()[source]

Get the position of spot’s base.

Returns:
The position of spot’s base.
GetBaseRollPitchYaw()[source]

Get the rate of orientation change of the spot’s base in euler angle.

Returns:
rate of (roll, pitch, yaw) change of the spot’s base.
GetBaseRollPitchYawRate()[source]

Get the rate of orientation change of the spot’s base in euler angle.

This function mimicks the noisy sensor reading and adds latency. Returns:

rate of (roll, pitch, yaw) change of the spot’s base polluted by noise and latency.
GetBaseTwist()[source]

Get the Twist of minitaur’s base. Returns:

The Twist of the minitaur’s base.
GetControlInput(controller)[source]

Store Control Input as Observation

GetControlLatency()[source]

Get the control latency.

Returns:
The latency (in seconds) between when the motor command is sent and when
the sensor measurements are reported back to the controller.
GetExternalObservations(TrajectoryGenerator, controller)[source]

Augment State Space

GetLegInertiasFromURDF()[source]

Get the inertia of the legs from the URDF file.

GetLegMassesFromURDF()[source]

Get the mass of the legs from the URDF file.

GetLegPhases(TrajectoryGenerator)[source]

Leg phases according to TG from 0->2 0->1: Stance 1->2 Swing

GetMotorAngles()[source]

Gets the eight motor angles at the current moment, mapped to [-pi, pi].

Returns:
Motor angles, mapped to [-pi, pi].
GetMotorGains()[source]

Get the gains of the motor.

Returns:
The proportional gain. The derivative gain.
GetMotorTorques()[source]

Get the amount of torque the motors are exerting.

Returns:
Motor torques of all eight motors.
GetMotorVelocities()[source]

Get the velocity of all eight motors.

Returns:
Velocities of all eight motors.
GetNumKneeJoints()[source]
GetObservation()[source]

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. NOTE: DIVERGES FROM STOCK MINITAUR ENV. WILL LEAVE ORIGINAL COMMENTED For my purpose, the observation space includes Roll and Pitch, as well as acceleration and gyroscopic rate along the x,y,z axes. All of this information can be collected from an onboard IMU. The reward function will contain a hidden velocity reward (fwd, bwd) which cannot be measured and so is not included. For spinning, the gyroscopic z rate will be used as the (explicit) velocity reward. This version operates without motor torques, angles and velocities. Erwin Coumans’ paper suggests a sparse observation space leads to higher reward

# NOTE: use True version for perfect data, or other for realistic data

GetObservationDimension()[source]

Get the length of the observation list. Returns:

The length of the observation list.
GetObservationLowerBound()[source]

Get the lower bound of the observation.

GetObservationUpperBound()[source]

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.

NOTE: Changed just like GetObservation()

GetTimeSinceReset()[source]
INIT_POSES = {'liedown': array([-0.4, -1.5, 6. , 0.4, -1.5, 6. , -0.4, -1.5, 6. , 0.4, -1.5, 6. ]), 'stand': array([ 0.15192765, 0.7552236 , -1.5104472 , -0.15192765, 0.7552236 , -1.5104472 , 0.15192765, 0.7552236 , -1.5104472 , -0.15192765, 0.7552236 , -1.5104472 ]), 'zero': array([0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.])}
RealisticObservation()[source]

Receive the observation from sensors.

This function is called once per step. The observations are only updated when this function is called.

Reset(reload_urdf=True, default_motor_angles=None, reset_time=3.0)[source]

Reset the spot to its initial states.

Args:
reload_urdf: Whether to reload the urdf file. If not, Reset() just place
the spot back to its starting position.
default_motor_angles: The default motor angles. If it is None, spot
will hold a default pose for 100 steps. In torque control mode, the phase of holding the default pose is skipped.
reset_time: The duration (in seconds) to hold the default motor angles. If
reset_time <= 0 or in torque control mode, the phase of holding the default pose is skipped.
ResetPose(add_constraint)[source]

Reset the pose of the spot.

Args:
add_constraint: Whether to add a constraint at the joints of two feet.
SetBaseInertias(base_inertias)[source]

Set the inertias of spot’s base. Args:

base_inertias: A list of inertias of each body link in CHASIS_LINK_IDS.
The length of this list should be the same as the length of CHASIS_LINK_IDS.
Raises:
ValueError: It is raised when the length of base_inertias is not the same
as the length of self._chassis_link_ids and base_inertias contains negative values.
SetBaseMass(base_mass)[source]
SetBaseMasses(base_mass)[source]

Set the mass of spot’s base.

Args:
base_mass: A list of masses of each body link in CHASIS_LINK_IDS. The
length of this list should be the same as the length of CHASIS_LINK_IDS.
Raises:
ValueError: It is raised when the length of base_mass is not the same as
the length of self._chassis_link_ids.
SetBatteryVoltage(voltage)[source]
SetControlLatency(latency)[source]

Set the latency of the control loop.

It measures the duration between sending an action from Nvidia TX2 and receiving the observation from microcontroller.

Args:
latency: The latency (in seconds) of the control loop.
SetFootFriction(foot_friction=100.0)[source]

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.
SetFootRestitution(link_id, foot_restitution=1.0)[source]

Set the coefficient of restitution at the feet.

Args:
foot_restitution: The coefficient of restitution (bounciness) of the feet.
This value is shared by all four feet.
SetJointFriction(joint_frictions)[source]
SetLegInertias(leg_inertias)[source]

Set the inertias of the legs.

Args:
leg_inertias: The leg and motor inertias for all the leg links and motors.
Raises:
ValueError: It is raised when the length of inertias is not equal to the number of links + motors or leg_inertias contains negative values.
SetLegMasses(leg_masses)[source]

Set the mass of the legs. Args:

leg_masses: The leg and motor masses for all the leg links and motors.
Raises:
ValueError: It is raised when the length of masses is not equal to number
of links + motors.
SetMotorGains(kp, kd)[source]

Set the gains of all motors.

These gains are PD gains for motor positional control. kp is the proportional gain and kd is the derivative gain.

Args:
kp: proportional gain of the motors. kd: derivative gain of the motors.
SetMotorStrengthRatio(ratio)[source]

Set the strength of all motors relative to the default value.

Args:
ratio: The relative strength. A scalar range from 0.0 to 1.0.
SetMotorStrengthRatios(ratios)[source]

Set the strength of each motor relative to the default value.

Args:
ratios: The relative strength. A numpy array ranging from 0.0 to 1.0.
SetMotorViscousDamping(viscous_damping)[source]
SetTimeSteps(action_repeat, simulation_step)[source]

Set the time steps of the control and simulation.

Args:
action_repeat: The number of simulation steps that the same action is
repeated.

simulation_step: The simulation time step.

Step(action)[source]

spotmicro.spot_env_randomizer module

CODE BASED ON EXAMPLE FROM: @misc{coumans2017pybullet,

title={Pybullet, a python module for physics simulation in robotics, games and machine learning}, author={Coumans, Erwin and Bai, Yunfei}, url={www.pybullet.org}, year={2017},

}

Example: minitaur_env_randomizer.py https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py

class spotmicro.spot_env_randomizer.SpotEnvRandomizer(spot_base_mass_err_range=(-0.2, 0.2), spot_leg_mass_err_range=(-0.2, 0.2), battery_voltage_range=(7.0, 8.4), motor_viscous_damping_range=(0, 0.01))[source]

Bases: spotmicro.env_randomizer_base.EnvRandomizerBase

A randomizer that change the spot_gym_env during every reset.

randomize_env(env)[source]

Randomize the simulated_objects in the environment.

Args:
env: The environment to be randomized.

spotmicro.spot_gym_env module

CODE BASED ON EXAMPLE FROM: @misc{coumans2017pybullet,

title={Pybullet, a python module for physics simulation in robotics, games and machine learning}, author={Coumans, Erwin and Bai, Yunfei}, url={www.pybullet.org}, year={2017},

}

Example: minitaur_gym_env.py https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py

spotmicro.spot_gym_env.convert_to_list(obj)[source]
class spotmicro.spot_gym_env.spotGymEnv(distance_weight=1.0, rotation_weight=1.0, energy_weight=0.0005, shake_weight=0.005, drift_weight=2.0, rp_weight=0.1, rate_weight=0.1, urdf_root='/home/docs/checkouts/readthedocs.org/user_builds/spot-mini-mini/envs/latest/lib/python3.7/site-packages/pybullet_data', urdf_version=None, distance_limit=inf, observation_noise_stdev=(0.0, 0.0, 0.0, 0.0, 0.0), self_collision_enabled=True, motor_velocity_limit=inf, pd_control_enabled=False, leg_model_enabled=False, accurate_motor_model_enabled=False, remove_default_joint_damping=False, motor_kp=2.0, motor_kd=0.03, control_latency=0.0, pd_latency=0.0, torque_control_enabled=False, motor_overheat_protection=False, hard_reset=False, on_rack=False, render=True, num_steps_to_log=1000, action_repeat=1, control_time_step=None, env_randomizer=<spotmicro.spot_env_randomizer.SpotEnvRandomizer object>, forward_reward_cap=inf, reflection=True, log_path=None, desired_velocity=0.5, desired_rate=0.0, lateral=False, draw_foot_path=False, height_field=False, height_field_iters=2, AutoStepper=False, contacts=True)[source]

Bases: gym.core.Env

The gym environment for spot.

It simulates the locomotion of spot, a quadruped robot. The state space include the angles, velocities and torques for all the motors and the action space is the desired motor angle for each motor. The reward function is based on how far spot walks in 1000 steps and penalizes the energy expenditure.

DrawFootPath()[source]
configure(args)[source]
env_step_counter
get_objectives()[source]
get_spot_base_orientation()[source]

Get the spot’s base orientation, represented by a quaternion.

Returns:
A numpy array of spot’s orientation.
get_spot_motor_angles()[source]

Get the spot’s motor angles.

Returns:
A numpy array of motor angles.
get_spot_motor_torques()[source]

Get the spot’s motor torques.

Returns:
A numpy array of motor torques.
get_spot_motor_velocities()[source]

Get the spot’s motor velocities.

Returns:
A numpy array of motor velocities.
ground_id
is_fallen()[source]

Decide whether spot has fallen.

If the up directions between the base and the world is larger (the dot product is smaller than 0.85) or the base is very low on the ground (the height is smaller than 0.13 meter), spot is considered fallen.

Returns:
Boolean value that indicates whether spot has fallen.
metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
objective_weights

Accessor for the weights for all the objectives.

Returns:
List of floating points that corresponds to weights for the objectives in the order that objectives are stored.
pybullet_client
render(mode='rgb_array', close=False)[source]

Renders the environment.

The set of supported modes varies per environment. (And some environments do not support rendering at all.) By convention, if mode is:

  • human: render to the current display or terminal and return nothing. Usually for human consumption.
  • rgb_array: Return an numpy.ndarray with shape (x, y, 3), representing RGB values for an x-by-y pixel image, suitable for turning into a video.
  • ansi: Return a string (str) or StringIO.StringIO containing a terminal-style text representation. The text can include newlines and ANSI escape sequences (e.g. for colors).
Note:
Make sure that your class’s metadata ‘render.modes’ key includes
the list of supported modes. It’s recommended to call super() in implementations to use the functionality of this method.
Args:
mode (str): the mode to render with

Example:

class MyEnv(Env):

metadata = {‘render.modes’: [‘human’, ‘rgb_array’]}

def render(self, mode=’human’):
if mode == ‘rgb_array’:
return np.array(…) # return RGB frame suitable for video
elif mode == ‘human’:
… # pop up a window and render
else:
super(MyEnv, self).render(mode=mode) # just raise an exception
reset(initial_motor_angles=None, reset_duration=1.0, desired_velocity=None, desired_rate=None)[source]

Resets the state of the environment and returns an initial observation.

Returns:
observation (object): the initial observation.
seed(seed=None)[source]

Sets the seed for this env’s random number generator(s).

Note:
Some environments use multiple pseudorandom number generators. We want to capture all such seeds used in order to ensure that there aren’t accidental correlations between multiple generators.
Returns:
list<bigint>: Returns the list of seeds used in this env’s random
number generators. The first value in the list should be the “main” seed, or the value which a reproducer should pass to ‘seed’. Often, the main seed equals the provided ‘seed’, but this won’t be true if seed=None, for example.
set_env_randomizer(env_randomizer)[source]
set_time_step(control_step, simulation_step=0.001)[source]

Sets the time step of the environment.

Args:
control_step: The time period (in seconds) between two adjacent control
actions are applied.
simulation_step: The simulation time step in PyBullet. By default, the
simulation step is 0.001s, which is a good trade-off between simulation speed and accuracy.
Raises:
ValueError: If the control step is smaller than the simulation step.
step(action)[source]

Step forward the simulation, given the action.

Args:
action: A list of desired motor angles for eight motors.
Returns:
observations: The angles, velocities and torques of all motors. reward: The reward for the current state-action pair. done: Whether the episode has ended. info: A dictionary that stores diagnostic information.
Raises:
ValueError: The action dimension is not the same as the number of motors. ValueError: The magnitude of actions is out of bounds.

Module contents