Quadrupeds

Unitree A1

https://github.com/robfiras/loco-mujoco/assets/69359729/2fa1841e-f7fc-4758-8c8e-2b7057db0365 https://github.com/robfiras/loco-mujoco/assets/69359729/4a15dea9-afd1-4142-8503-cb7bc9ee09c4
class UnitreeA1(action_mode='torque', setup_random_rot=False, default_target_velocity=0.5, camera_params=None, **kwargs)[source]

Bases: LocoEnv

Description

Mujoco simulation of Unitree A1 model.

Tasks

  • Simple: The robot has to walk forward with a fixed speed of 0.5 m/s.

  • Hard: The robot has to walk in 8 different directions with a fixed speed of 0.5 m/s.

Dataset Types

The available dataset types for this environment can be found at: Overview of Environments, Tasks and Datasets.

Observation Space

The observation space has the following properties by default (i.e., only obs with Disabled == False):

For simple task: (min=-inf, max=inf, dim=37, dtype=float32)
For hard task: (min=-inf, max=inf, dim=37, dtype=float32)

Some observations are disabled by default, but can be turned on. The detailed observation space is:

0

Position of Joint trunk_tz

-inf

inf

False

1

Angle [rad]

1

Position of Joint trunk_list

-inf

inf

False

1

Angle [rad]

2

Position of Joint trunk_tilt

-inf

inf

False

1

Angle [rad]

3

Position of Joint trunk_rotation

-inf

inf

False

1

Angle [rad]

4

Position of Joint FR_hip_joint

-0.802851

0.802851

False

1

Angle [rad]

5

Position of Joint FR_thigh_joint

-1.0472

4.18879

False

1

Angle [rad]

6

Position of Joint FR_calf_joint

-2.69653

-0.916298

False

1

Angle [rad]

7

Position of Joint FL_hip_joint

-0.802851

0.802851

False

1

Angle [rad]

8

Position of Joint FL_thigh_joint

-1.0472

4.18879

False

1

Angle [rad]

9

Position of Joint FL_calf_joint

-2.69653

-0.916298

False

1

Angle [rad]

10

Position of Joint RR_hip_joint

-0.802851

0.802851

False

1

Angle [rad]

11

Position of Joint RR_thigh_joint

-1.0472

4.18879

False

1

Angle [rad]

12

Position of Joint RR_calf_joint

-2.69653

-0.916298

False

1

Angle [rad]

13

Position of Joint RL_hip_joint

-0.802851

0.802851

False

1

Angle [rad]

14

Position of Joint RL_thigh_joint

-1.0472

4.18879

False

1

Angle [rad]

15

Position of Joint RL_calf_joint

-2.69653

-0.916298

False

1

Angle [rad]

16

Velocity of Joint trunk_tx

-inf

inf

False

1

Angular Velocity [rad/s]

17

Velocity of Joint trunk_ty

-inf

inf

False

1

Angular Velocity [rad/s]

18

Velocity of Joint trunk_tz

-inf

inf

False

1

Angular Velocity [rad/s]

19

Velocity of Joint trunk_list

-inf

inf

False

1

Angular Velocity [rad/s]

20

Velocity of Joint trunk_tilt

-inf

inf

False

1

Angular Velocity [rad/s]

21

Velocity of Joint trunk_rotation

-inf

inf

False

1

Angular Velocity [rad/s]

22

Velocity of Joint FR_hip_joint

-inf

inf

False

1

Angular Velocity [rad/s]

23

Velocity of Joint FR_thigh_joint

-inf

inf

False

1

Angular Velocity [rad/s]

24

Velocity of Joint FR_calf_joint

-inf

inf

False

1

Angular Velocity [rad/s]

25

Velocity of Joint FL_hip_joint

-inf

inf

False

1

Angular Velocity [rad/s]

26

Velocity of Joint FL_thigh_joint

-inf

inf

False

1

Angular Velocity [rad/s]

27

Velocity of Joint FL_calf_joint

-inf

inf

False

1

Angular Velocity [rad/s]

28

Velocity of Joint RR_hip_joint

-inf

inf

False

1

Angular Velocity [rad/s]

29

Velocity of Joint RR_thigh_joint

-inf

inf

False

1

Angular Velocity [rad/s]

30

Velocity of Joint RR_calf_joint

-inf

inf

False

1

Angular Velocity [rad/s]

31

Velocity of Joint RL_hip_joint

-inf

inf

False

1

Angular Velocity [rad/s]

32

Velocity of Joint RL_thigh_joint

-inf

inf

False

1

Angular Velocity [rad/s]

33

Velocity of Joint RL_calf_joint

-inf

inf

False

1

Angular Velocity [rad/s]

34

Desired Velocity Angle represented as Sine-Cosine Feature

0.0

1

False

2

None

36

Desired Velocity

0.0

inf

False

1

Velocity [m/s]

37

3D linear Forces between Front Left Foot and Floor

0.0

inf

True

3

Force [N]

40

3D linear Forces between Front Right Foot and Floor

0.0

inf

True

3

Force [N]

43

3D linear Forces between Back Left Foot and Floor

0.0

inf

True

3

Force [N]

46

3D linear Forces between Back Right Foot and Floor

0.0

inf

True

3

Force [N]

Action Space

The action space has the following properties by default (i.e., only actions with Disabled == False):
(min=-1, max=1, dim=12, dtype=float32)

Index

Name in XML

Control Min

Control Max

Disabled

0

FR_hip

-1.0

1.0

False

1

FR_thigh

-1.0

1.0

False

2

FR_calf

-1.0

1.0

False

3

FL_hip

-1.0

1.0

False

4

FL_thigh

-1.0

1.0

False

5

FL_calf

-1.0

1.0

False

6

RR_hip

-1.0

1.0

False

7

RR_thigh

-1.0

1.0

False

8

RR_calf

-1.0

1.0

False

9

RL_hip

-1.0

1.0

False

10

RL_thigh

-1.0

1.0

False

11

RL_calf

-1.0

1.0

False

Rewards

Reward function based on the difference between the desired velocity vector and the actual center of mass velocity vector in horizontal plane. The desired velocity vector is given by the dataset to imitate.

Class: loco_mujoco.utils.reward.VelocityVectorReward

Initial States

The initial state is sampled by default from the dataset to imitate.

Terminal States

The terminal state is reached when the robot falls, or rather starts falling. The condition to check if the robot is falling is based on the orientation of the robot and the height of the center of mass. More details can be found in the _has_fallen method of the environment.

Methods

create_dataset(ignore_keys=None)[source]

Creates a dataset from the specified trajectories.

Args:

ignore_keys (list): List of keys to ignore in the dataset.

Returns:

Dictionary containing states, next_states and absorbing flags. For the states the shape is (N_traj x N_samples_per_traj, dim_state), while the absorbing flag has the shape is (N_traj x N_samples_per_traj).

static generate(task='simple', dataset_type='real', debug=False, **kwargs)[source]

Returns a Unitree environment corresponding to the specified task.

Args:
task (str): Main task to solve. Either “simple” or “hard”. “simple” is a straight walking

task. “hard” is a walking task in 8 direction. This makes this environment goal conditioned.

dataset_type (str): “real” or “perfect”. “real” uses real motion capture data as the

reference trajectory. This data does not perfectly match the kinematics and dynamics of this environment, hence it is more challenging. “perfect” uses a perfect dataset.

debug (bool): If True, the smaller test datasets are used for debugging purposes.

Returns:

An MDP of the Unitree A1 Robot.

get_kinematic_obs_mask()[source]

Returns a mask (np.array) for the observation specified in observation_spec (or part of it).

load_dataset_and_get_traj_files(dataset_path, freq=None)[source]

Calculates a dictionary containing the kinematics given a dataset. If freq is provided, the x and z positions are calculated based on the velocity.

Args:

dataset_path (str): Path to the dataset. freq (float): Frequency of the data in obs.

Returns:

Dictionary containing the keys specified in observation_spec with the corresponding values from the dataset.

set_sim_state(sample)[source]

Sets the state of the simulation according to an observation.

Args:

sample (list or np.array): Sample used to set the state of the simulation.

setup(obs)[source]

Function to setup the initial state of the simulation. Initialization can be done either randomly, from a certain initial, or from the default initial state of the model.

Args:

obs (np.array): Observation to initialize the environment from;

valid_task_confs = <loco_mujoco.environments.base.ValidTaskConf object>