Skip to content

mdp

Modules:

Name Description
actions
commands
rewards

Classes:

Name Description
FlightActionMapper

Map batched normalized actions into controller targets, wrench, or RPM.

Mixer

Map thrust and moment demands to rotor commands.

VehicleParams

LAV2 vehicle parameters.

RotorDynamics

Batched rotor dynamics model.

ControlActionManager

Base class for action managers that control actuators.

HeadingVelocityCommandRange

4-D velocity command range: vx, vy, vz, wz.

HeadingVelocityCommandManager

Velocity command manager with heading-based yaw rate control and z velocity.

Functions:

Name Description
wrap_to_pi

Wraps input angles (in radians) to the range :math:[-\pi, \pi].

lin_vel_l2

Penalize base linear velocity using L2 squared kernel.

ang_vel_l2

Penalize base angular velocity using L2 squared kernel.

pos_error_l2

Penalize asset pos from its target pos using L2 squared kernel.

pos_error_tanh

Penalize asset pos from its target pos using tanh kernel.

yaw_error_l2

Penalize heading error from target heading using L2 squared kernel.

yaw_error_tanh

Penalize heading error from target heading.

command_tracking_lin_vel

Reward for tracking commanded linear velocity (xyz axes).

command_tracking_ang_vel

Reward for tracking commanded angular velocity (yaw).

FlightActionMapper

FlightActionMapper(control_mode: str, params: VehicleParams = VehicleParams(), mapping: FlightMappingConfig | None = None, *, num_envs: int = 1, device: str | device = 'cpu')

Map batched normalized actions into controller targets, wrench, or RPM.

Initialize a batched Torch flight action mapper for the selected mode.

Methods:

Name Description
randomize

Randomize mapper runtime parameters used by action scaling.

action_to_collective_acc

Map a normalized policy collective action to total collective acceleration.

collective_acc_to_thrust

Convert total collective acceleration into total thrust in Newtons.

action_to_collective_thrust

Convert a normalized policy collective action into total thrust.

map_action

Map a normalized batched action into RPM commands and intermediates.

Attributes:

Name Type Description
requires_controller bool

Whether this mode needs a controller target expansion step.

requires_controller property

requires_controller: bool

Whether this mode needs a controller target expansion step.

randomize

randomize(env_ids=None, randomization: dict[str, tuple[float, float]] | None = None) -> None

Randomize mapper runtime parameters used by action scaling.

action_to_collective_acc

action_to_collective_acc(action: Tensor, mixer: Mixer) -> torch.Tensor

Map a normalized policy collective action to total collective acceleration.

collective_acc_to_thrust

collective_acc_to_thrust(collective_acc: Tensor) -> torch.Tensor

Convert total collective acceleration into total thrust in Newtons.

action_to_collective_thrust

action_to_collective_thrust(action: Tensor, mixer: Mixer) -> torch.Tensor

Convert a normalized policy collective action into total thrust.

map_action

map_action(action: Tensor, mixer: Mixer, *, state: Tensor | None = None, flight_controller: ControllerBase | None = None) -> FlightMappingResult

Map a normalized batched action into RPM commands and intermediates.

Mixer

Mixer(params: VehicleParams = VehicleParams(), num_envs: int = 1, device: str | device = 'cpu')

Map thrust and moment demands to rotor commands.

Note

电机推力分配: 电机1 = 推力 - 横滚(roll) + 俯仰(pitch) + 偏航(yaw) 电机2 = 推力 + 横滚(roll) - 俯仰(pitch) + 偏航(yaw) 电机3 = 推力 + 横滚(roll) + 俯仰(pitch) - 偏航(yaw) 电机4 = 推力 - 横滚(roll) - 俯仰(pitch) - 偏航(yaw)

Initialize the torch mixer with vehicle parameters and device.

Methods:

Name Description
randomize

Randomize mixer runtime parameters from nominal values.

calculate_rotor_commands

Allocate thrust and moments into rotor speeds.

randomize

randomize(env_ids=None, randomization=None)

Randomize mixer runtime parameters from nominal values.

calculate_rotor_commands

calculate_rotor_commands(control: Tensor) -> torch.Tensor

Allocate thrust and moments into rotor speeds.

Parameters:

Name Type Description Default

control

Tensor

Desired total thrust and roll/pitch/yaw moments. Shape: (num_envs, 4)

required

Returns:

Type Description
Tensor

torch.Tensor: The amplitude of each motor's rotational speed (calculated using sqrt(clip(rpm_sq))). Shape: (num_envs, 4)

VehicleParams dataclass

VehicleParams(rho: float = 1.184, g: float = 9.81, sim_dt: float = 0.01, step_dt: float = 0.01, randomization: dict[str, dict[str, tuple[float, float]]] = dict(), mass: float = 2.1, inertia: list = (lambda: np.diag([0.015, 0.0348, 0.042503]).tolist())(), diameter: float = 0.476, Cdx: float = 0.5, x: float = 0.0952, y: float = 0.114423, h: float = -0.0125, alpha: float = math.radians(8.0), r_p: float = 0.0775, Ct: float = 0.666, Cq: float = 0.0716, theta0: float = math.radians(14.6), thetaTip: float = math.radians(6.8), lock: float = 0.6051, max_rpm: float = 10000.0, init_rpm: float = math.nan, rotor_rpm_rate_limit: float = 50000.0, tau_f: float = 0.01, tau_m: float = 0.05, tau_up: float = math.nan, tau_down: float = math.nan, r_w: float = 0.0285, n_w: int = 4, B: float = 0.136, L: float = 0.23, h_cg: float = 0.078, f: float = 0.01, mu0: float = 0.8, K: float = 20, track_cmd_rate_limit: float = 100, mpc_xy_vel_max: float = 12.0, mpc_z_vel_max_up: float = 3.0, mpc_z_vel_max_dn: float = 1.5, mpc_man_tilt_max: float = math.radians(35.0), mc_rollrate_max: float = math.radians(220.0), mc_pitchrate_max: float = math.radians(220.0), mc_yawrate_max: float = math.radians(200.0))

LAV2 vehicle parameters.

Methods:

Name Description
__post_init__

Calculate derived parameters.

Attributes:

Name Type Description
rho float

空气密度 (kg/m^3)

g float

重力加速度 (m/s^2)

sim_dt float

仿真步长 (s)

step_dt float

控制步长 (s)

randomization dict[str, dict[str, tuple[float, float]]]

运行时参数随机化配置,按组件 (e.g. rotor/mixer) 划分为多个 scale 相对范围子表

mass float

质量 (kg)

inertia list

惯性矩阵 (kg*m^2)

diameter float

直径 (m)

Cdx float

空气阻力系数

x float

x方向臂长 (m)

y float

y方向臂长 (m)

h float

重心高度 (m)

alpha float

y方向涵道外倾角度 (rad)

r_p float

螺旋桨半径 (m)

Ct float

推力系数

Cq float

扭矩系数

theta0 float

桨根角 (rad)

thetaTip float

桨尖角 (rad)

theta1 float

桨叶扭转角 (rad)

lock float

Lock number

max_rpm float

最大转速

init_rpm float

初始转速

rotor_rpm_rate_limit float

旋翼转速变化率限制 (rpm/s)

cT float

转速平方到推力增益 (N/(rpm^2))

cM float

转速平方到扭矩增益 (N*m/(rpm^2))

tau_f float

电机滤波时间常数 (s)

tau_m float

兼容保留的电机时间常数 (s)

tau_up float

电机升速时间常数 (s)

tau_down float

电机降速时间常数 (s)

r_w float

主动轮半径 (m)

n_w int

负重轮个数

B float

两侧履带中心距 (m)

L float

履带节点接地部分长度 (m)

h_cg float

车体质心高度 (m)

f float

滚动阻力系数(以干燥混凝土路面或沥青路面为例)

mu0 float

滑转率为1时的摩擦系数

K float

依赖于土壤黏聚系数和摩擦特性的常数

track_cmd_rate_limit float

履带主动轮指令变化率限制 (rad/s^2)

mpc_xy_vel_max float

Maximum horizontal velocity setpoint magnitude in m/s (0 - 20).

mpc_z_vel_max_up float

Maximum upward velocity setpoint in m/s (0.5 - 8).

mpc_z_vel_max_dn float

Maximum downward velocity setpoint magnitude in m/s (0.5 - 4).

mpc_man_tilt_max float

Maximum manual tilt angle in radians (deg: 0 - 90).

mc_rollrate_max float

Maximum roll-rate setpoint in rad/s (deg/s: 0 - 1800).

mc_pitchrate_max float

Maximum pitch-rate setpoint in rad/s (deg/s: 0 - 1800).

mc_yawrate_max float

Maximum yaw-rate setpoint in rad/s (deg/s: 0 - 1800).

rho class-attribute instance-attribute

rho: float = 1.184

空气密度 (kg/m^3)

g class-attribute instance-attribute

g: float = 9.81

重力加速度 (m/s^2)

sim_dt class-attribute instance-attribute

sim_dt: float = 0.01

仿真步长 (s)

step_dt class-attribute instance-attribute

step_dt: float = 0.01

控制步长 (s)

randomization class-attribute instance-attribute

randomization: dict[str, dict[str, tuple[float, float]]] = field(default_factory=dict)

运行时参数随机化配置,按组件 (e.g. rotor/mixer) 划分为多个 scale 相对范围子表

mass class-attribute instance-attribute

mass: float = 2.1

质量 (kg)

inertia class-attribute instance-attribute

inertia: list = field(default_factory=lambda: tolist())

惯性矩阵 (kg*m^2)

diameter class-attribute instance-attribute

diameter: float = 0.476

直径 (m)

Cdx class-attribute instance-attribute

Cdx: float = 0.5

空气阻力系数

x class-attribute instance-attribute

x: float = 0.0952

x方向臂长 (m)

y class-attribute instance-attribute

y: float = 0.114423

y方向臂长 (m)

h class-attribute instance-attribute

h: float = -0.0125

重心高度 (m)

alpha class-attribute instance-attribute

alpha: float = radians(8.0)

y方向涵道外倾角度 (rad)

r_p class-attribute instance-attribute

r_p: float = 0.0775

螺旋桨半径 (m)

Ct class-attribute instance-attribute

Ct: float = 0.666

推力系数

Cq class-attribute instance-attribute

Cq: float = 0.0716

扭矩系数

theta0 class-attribute instance-attribute

theta0: float = radians(14.6)

桨根角 (rad)

thetaTip class-attribute instance-attribute

thetaTip: float = radians(6.8)

桨尖角 (rad)

theta1 class-attribute instance-attribute

theta1: float = field(init=False)

桨叶扭转角 (rad)

lock class-attribute instance-attribute

lock: float = 0.6051

Lock number

max_rpm class-attribute instance-attribute

max_rpm: float = 10000.0

最大转速

init_rpm class-attribute instance-attribute

init_rpm: float = nan

初始转速

rotor_rpm_rate_limit class-attribute instance-attribute

rotor_rpm_rate_limit: float = 50000.0

旋翼转速变化率限制 (rpm/s)

cT class-attribute instance-attribute

cT: float = field(init=False)

转速平方到推力增益 (N/(rpm^2))

cM class-attribute instance-attribute

cM: float = field(init=False)

转速平方到扭矩增益 (N*m/(rpm^2))

tau_f class-attribute instance-attribute

tau_f: float = 0.01

电机滤波时间常数 (s)

tau_m class-attribute instance-attribute

tau_m: float = 0.05

兼容保留的电机时间常数 (s)

tau_up class-attribute instance-attribute

tau_up: float = nan

电机升速时间常数 (s)

tau_down class-attribute instance-attribute

tau_down: float = nan

电机降速时间常数 (s)

r_w class-attribute instance-attribute

r_w: float = 0.0285

主动轮半径 (m)

n_w class-attribute instance-attribute

n_w: int = 4

负重轮个数

B class-attribute instance-attribute

B: float = 0.136

两侧履带中心距 (m)

L class-attribute instance-attribute

L: float = 0.23

履带节点接地部分长度 (m)

h_cg class-attribute instance-attribute

h_cg: float = 0.078

车体质心高度 (m)

f class-attribute instance-attribute

f: float = 0.01

滚动阻力系数(以干燥混凝土路面或沥青路面为例)

mu0 class-attribute instance-attribute

mu0: float = 0.8

滑转率为1时的摩擦系数

K class-attribute instance-attribute

K: float = 20

依赖于土壤黏聚系数和摩擦特性的常数

track_cmd_rate_limit class-attribute instance-attribute

track_cmd_rate_limit: float = 100

履带主动轮指令变化率限制 (rad/s^2)

mpc_xy_vel_max class-attribute instance-attribute

mpc_xy_vel_max: float = 12.0

Maximum horizontal velocity setpoint magnitude in m/s (0 - 20).

mpc_z_vel_max_up class-attribute instance-attribute

mpc_z_vel_max_up: float = 3.0

Maximum upward velocity setpoint in m/s (0.5 - 8).

mpc_z_vel_max_dn class-attribute instance-attribute

mpc_z_vel_max_dn: float = 1.5

Maximum downward velocity setpoint magnitude in m/s (0.5 - 4).

mpc_man_tilt_max class-attribute instance-attribute

mpc_man_tilt_max: float = radians(35.0)

Maximum manual tilt angle in radians (deg: 0 - 90).

mc_rollrate_max class-attribute instance-attribute

mc_rollrate_max: float = radians(220.0)

Maximum roll-rate setpoint in rad/s (deg/s: 0 - 1800).

mc_pitchrate_max class-attribute instance-attribute

mc_pitchrate_max: float = radians(220.0)

Maximum pitch-rate setpoint in rad/s (deg/s: 0 - 1800).

mc_yawrate_max class-attribute instance-attribute

mc_yawrate_max: float = radians(200.0)

Maximum yaw-rate setpoint in rad/s (deg/s: 0 - 1800).

__post_init__

__post_init__()

Calculate derived parameters.

RotorDynamics

RotorDynamics(params: VehicleParams = VehicleParams(), num_envs: int = 1, device: str | device = 'cpu')

Bases: DynamicsBase

Batched rotor dynamics model.

Initialize batched rotor dynamics on the specified device.

Methods:

Name Description
randomize

Randomize rotor runtime parameters from nominal values.

update

Calculate the output thrust and torque for each motor based on the motor commands.

reset

Resets the rotor model to initial conditions.

Attributes:

Name Type Description
params VehicleParams

Vehicle parameters for the dynamics model.

params instance-attribute

params: VehicleParams = params

Vehicle parameters for the dynamics model.

randomize

randomize(env_ids: slice | Sequence[int] | Tensor | None = None, randomization: dict[str, tuple[float, float]] | None = None) -> None

Randomize rotor runtime parameters from nominal values.

update

update(commands: Tensor) -> torch.Tensor

Calculate the output thrust and torque for each motor based on the motor commands.

Parameters:

Name Type Description Default

commands

Tensor

Command tensor for each motor. Shape: (num_envs, 4)

required

Returns:

Type Description
Tensor

torch.Tensor: Thrust and torque tensor for each motor. Shape: (num_envs, 8)

reset

reset(env_ids: slice | Sequence[int] | Tensor) -> None

Resets the rotor model to initial conditions.

Parameters:

Name Type Description Default

env_ids

slice | Sequence[int] | Tensor

The environment ids to reset.

required

ControlActionManager

ControlActionManager(env: GenesisEnv, delay_step: int = 0, params: VehicleParams = VehicleParams(), entity_attr: str = 'robot')

Bases: BaseActionManager

Base class for action managers that control actuators.

Parameters:

Name Type Description Default

env

GenesisEnv

The environment to manage the DOF actuators for.

required

delay_step

int

The number of steps to delay the actions for. This is an easy way to emulate the latency in the system.

0

params

VehicleParams

Vehicle physical parameters.

VehicleParams()

entity_attr

str

Attribute name on the environment for the robot entity.

'robot'

Methods:

Name Description
step

Handle the received actions.

reset

Reset environments.

get_actions

Get the current actions for the environments.

Attributes:

Name Type Description
num_actions int

The total number of actions.

action_space tuple[float, float]

If using the default action handler, the action space is [-1, 1].

actions Tensor

The actions for for the current step.

raw_actions Tensor

The actions received from the policy, before being converted.

num_actions property

num_actions: int

The total number of actions.

action_space property

action_space: tuple[float, float]

If using the default action handler, the action space is [-1, 1].

actions property

actions: Tensor

The actions for for the current step.

raw_actions property

raw_actions: Tensor

The actions received from the policy, before being converted.

step

step(actions: Tensor) -> None

Handle the received actions.

reset

reset(envs_idx: list[int] | None)

Reset environments.

get_actions

get_actions() -> torch.Tensor

Get the current actions for the environments.

HeadingVelocityCommandRange

Bases: TypedDict

4-D velocity command range: vx, vy, vz, wz.

HeadingVelocityCommandManager

HeadingVelocityCommandManager(env: GenesisEnv, range: HeadingVelocityCommandRange, resample_time_sec: float = 5.0, standing_probability: float = 0.0, heading_command: bool = False, heading_control_stiffness: float = 1.0, rel_heading_envs: float = 1.0, heading_range: tuple[float, float] = (-math.pi, math.pi), debug_visualizer: bool = False, debug_visualizer_cfg: VelocityDebugVisualizerConfig = DEFAULT_VISUALIZER_CONFIG)

Bases: VelocityCommandManager

Velocity command manager with heading-based yaw rate control and z velocity.

Uses its own HeadingVelocityCommandRange config with 4 velocity dimensions. The parent's _command buffer stores 4-D [vx, vy, vz, wz]. The public command property returns the same 4-D tensor.

When heading_command=True, the angular velocity (wz) is overridden for heading-enabled environments by a proportional controller on the heading error::

wz = clip(stiffness * wrap_to_pi(heading_target - heading_w), ang_vel_z_range)

Parameters:

Name Type Description Default

env

GenesisEnv

The environment to control.

required

range

HeadingVelocityCommandRange

The ranges of linear & angular velocities (4-D: vx, vy, vz, wz).

required

resample_time_sec

float

The time interval between changing the command.

5.0

standing_probability

float

Probability of standing still.

0.0

heading_command

bool

Enable heading-based angular velocity control.

False

heading_control_stiffness

float

P-gain for heading error to yaw rate.

1.0

rel_heading_envs

float

Fraction of environments that use heading control.

1.0

heading_range

tuple[float, float]

Range for sampling heading targets (radians).

(-pi, pi)

debug_visualizer

bool

Enable debug arrow visualization.

False

debug_visualizer_cfg

VelocityDebugVisualizerConfig

Configuration for the debug visualizer.

DEFAULT_VISUALIZER_CONFIG

Attributes:

Name Type Description
command Tensor

The desired velocity command in base frame. Shape is (num_envs, 4).

command property

command: Tensor

The desired velocity command in base frame. Shape is (num_envs, 4).

Columns: [vx, vy, vz, wz].

wrap_to_pi

wrap_to_pi(angles: Tensor) -> torch.Tensor

Wraps input angles (in radians) to the range :math:[-\pi, \pi].

This function wraps angles in radians to the range :math:[-\pi, \pi], such that :math:\pi maps to :math:\pi, and :math:-\pi maps to :math:-\pi. In general, odd positive multiples of :math:\pi are mapped to :math:\pi, and odd negative multiples of :math:\pi are mapped to :math:-\pi.

The function behaves similar to MATLAB's wrapToPi <https://www.mathworks.com/help/map/ref/wraptopi.html>_ function.

Parameters:

Name Type Description Default

angles

Tensor

Input angles of any shape.

required

Returns:

Type Description
Tensor

torch.Tensor: Angles in the range :math:[-\pi, \pi].

lin_vel_l2

lin_vel_l2(env: GenesisEnv, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Penalize base linear velocity using L2 squared kernel.

ang_vel_l2

ang_vel_l2(env: GenesisEnv, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Penalize base angular velocity using L2 squared kernel.

pos_error_l2

pos_error_l2(env: GenesisEnv, target_pose: Tensor, pose_command: CommandManager = None, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Penalize asset pos from its target pos using L2 squared kernel.

pos_error_tanh

pos_error_tanh(env: GenesisEnv, target_pose: Tensor, pose_command: CommandManager = None, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Penalize asset pos from its target pos using tanh kernel.

yaw_error_l2

yaw_error_l2(env: GenesisEnv, target_pose: Tensor, pose_command: CommandManager = None, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Penalize heading error from target heading using L2 squared kernel.

yaw_error_tanh

yaw_error_tanh(env: GenesisEnv, target_pose: Tensor, pose_command: CommandManager = None, entity_attr: str = 'robot', entity_manager: EntityManager = None, std: float = 0.8) -> torch.Tensor

Penalize heading error from target heading.

command_tracking_lin_vel

command_tracking_lin_vel(env: GenesisEnv, vel_cmd_manager: VelocityCommandManager, sensitivity: float = 0.25, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Reward for tracking commanded linear velocity (xyz axes).

Uses 4-D command [vx, vy, vz, wz] and tracks all three linear axes.

command_tracking_ang_vel

command_tracking_ang_vel(env: GenesisEnv, vel_cmd_manager: VelocityCommandManager, sensitivity: float = 0.25, entity_attr: str = 'robot', entity_manager: EntityManager = None) -> torch.Tensor

Reward for tracking commanded angular velocity (yaw).

Uses 4-D command [vx, vy, vz, wz] where wz is at index 3.