mdp
模块:
| 名称 | 描述 |
|---|---|
actions |
|
commands |
|
rewards |
|
类:
| 名称 | 描述 |
|---|---|
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. |
ControlAction |
Body torque control action term. |
ControlActionCfg |
See :class: |
UniformPoseCommandGlobal |
Command generator that generates pose commands containing a 3-D position and heading. |
UniformPoseCommandGlobalCfg |
Configuration for the uniform 3D-pose command generator. |
函数:
| 名称 | 描述 |
|---|---|
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 using tanh kernel. |
FlightActionMapper
FlightActionMapper(control_mode: str, params: VehicleParams = VehicleParams(), limits: FlightMappingLimits = FlightMappingLimits(), *, 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.
方法:
| 名称 | 描述 |
|---|---|
map_action |
Map a normalized batched action into RPM commands and intermediates. |
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
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.
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.
方法:
| 名称 | 描述 |
|---|---|
randomize |
Randomize mixer runtime parameters from nominal values. |
apply_thrust_curve |
Apply thrust curve to normalized thrust command. |
calculate_rotor_commands |
Allocate thrust and moments into rotor speeds. |
randomize
randomize(env_ids=None, randomization=None)
Randomize mixer runtime parameters from nominal values.
apply_thrust_curve
apply_thrust_curve(normalized_thrust: Tensor, mode: int = 1) -> torch.Tensor
Apply thrust curve to normalized thrust command.
References
cmd_ctatt: https://github.com/PX4/PX4-Autopilot/blob/e5a483e4b71ab4b994cb0121fe28992d8ce0c8cd/src/modules/mc_att_control/mc_att_control_main.cpp#L111-L137 cmd_ctbr: https://github.com/PX4/PX4-Autopilot/blob/e5a483e4b71ab4b994cb0121fe28992d8ce0c8cd/src/modules/mc_rate_control/MulticopterRateControl.cpp#L156-L179
参数:
| 名称 | 类型 | 描述 | 默认 |
|---|---|---|---|
|
Tensor
|
Normalized thrust command [-1, 1]. Shape: arbitrary, e.g. (num_envs, n_motors). Applied elementwise. |
必需 |
|
int
|
Thrust curve mode. |
1
|
返回:
| 类型 | 描述 |
|---|---|
Tensor
|
torch.Tensor: Thrust in Newtons with the same shape as |
引发:
| 类型 | 描述 |
|---|---|
NotImplementedError
|
If the specified mode is not implemented. |
calculate_rotor_commands
calculate_rotor_commands(control: Tensor) -> torch.Tensor
Allocate thrust and moments into rotor speeds.
参数:
| 名称 | 类型 | 描述 | 默认 |
|---|---|---|---|
|
Tensor
|
Desired total thrust and roll/pitch/yaw moments. Shape: (num_envs, 4) |
必需 |
返回:
| 类型 | 描述 |
|---|---|
Tensor
|
torch.Tensor: The amplitude of each motor's rotational speed (calculated using |
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.11, 0.108, 0.215]).tolist())(), diameter: float = 0.476, Cdx: float = 0.5, x: float = 0.0952, y: float = 0.114423, h: float = -0.0125, alpha: float = 8 * (np.pi / 180), r_p: float = 0.0775, J_m: float = 1e-05, Ct: float = 0.666, Cq: float = 0.0716, theta0: float = 14.6 * (np.pi / 180), thetaTip: float = 6.8 * (np.pi / 180), lock: float = 0.6051, max_rpm: float = 10000.0, init_rpm: float = -1.0, rotor_rpm_rate_limit: float = 50000.0, tau_f: float = 0.01, tau_m: float = 0.05, tau_up: float = -1.0, tau_down: float = -1.0, 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, min_throttle_manual: float = 0.08, min_throttle: float = 0.12, max_throttle: float = 1.0, hover_throttle: float = -1)
LAV2 vehicle parameters.
方法:
| 名称 | 描述 |
|---|---|
__post_init__ |
Calculate derived parameters. |
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
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) |
J_m |
float
|
电机转动惯量 (kg*m^2) |
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) |
min_throttle_manual |
float
|
MPC_MANTHR_MIN: Minimum manual thrust (0.0 - 1.0). Default: 0.08 |
min_throttle |
float
|
MPC_THR_MIN: Minimum thrust in auto thrust control (0.05 - 1.0). Default: 0.12 |
max_throttle |
float
|
MPC_THR_MAX: Maximum thrust in auto thrust control (0.0 - 1.0). Default: 1.0 |
hover_throttle |
float
|
MPC_THR_HOVER: Hover throttle manual (0.1 - 0.8). Default: 0.5 in PX4, calculated hover throttle in LAV2 |
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 = 8 * (pi / 180)
y方向涵道外倾角度 (rad)
r_p
class-attribute
instance-attribute
r_p: float = 0.0775
螺旋桨半径 (m)
J_m
class-attribute
instance-attribute
J_m: float = 1e-05
电机转动惯量 (kg*m^2)
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 = 14.6 * (pi / 180)
桨根角 (rad)
thetaTip
class-attribute
instance-attribute
thetaTip: float = 6.8 * (pi / 180)
桨尖角 (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 = -1.0
初始转速
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 = -1.0
电机升速时间常数 (s)
tau_down
class-attribute
instance-attribute
tau_down: float = -1.0
电机降速时间常数 (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)
min_throttle_manual
class-attribute
instance-attribute
min_throttle_manual: float = 0.08
MPC_MANTHR_MIN: Minimum manual thrust (0.0 - 1.0). Default: 0.08
min_throttle
class-attribute
instance-attribute
min_throttle: float = 0.12
MPC_THR_MIN: Minimum thrust in auto thrust control (0.05 - 1.0). Default: 0.12
max_throttle
class-attribute
instance-attribute
max_throttle: float = 1.0
MPC_THR_MAX: Maximum thrust in auto thrust control (0.0 - 1.0). Default: 1.0
hover_throttle
class-attribute
instance-attribute
hover_throttle: float = -1
MPC_THR_HOVER: Hover throttle manual (0.1 - 0.8). Default: 0.5 in PX4, calculated hover throttle in LAV2
__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.
方法:
| 名称 | 描述 |
|---|---|
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. |
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
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.
参数:
| 名称 | 类型 | 描述 | 默认 |
|---|---|---|---|
|
Tensor
|
Command tensor for each motor. Shape: (num_envs, 4) |
必需 |
返回:
| 类型 | 描述 |
|---|---|
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.
参数:
| 名称 | 类型 | 描述 | 默认 |
|---|---|---|---|
|
slice | Sequence[int] | Tensor
|
The environment ids to reset. |
必需 |
ControlAction
ControlAction(cfg: ControlActionCfg, env: ManagerBasedRlEnv)
Bases: ActionTerm
Body torque control action term.
This action term applies a wrench to the drone body frame based on action commands
ControlActionCfg
dataclass
ControlActionCfg(*, class_type: type[ActionTerm] = ControlAction, entity_name: str = 'robot', params: VehicleParams = VehicleParams())
Bases: ActionTermCfg
See :class:ControlAction for more details.
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
class_type |
type[ActionTerm]
|
Class of the action term. |
entity_name |
str
|
Name of the asset in the environment for which the commands are generated. |
params |
VehicleParams
|
Vehicle parameters. |
class_type
class-attribute
instance-attribute
class_type: type[ActionTerm] = ControlAction
Class of the action term.
entity_name
class-attribute
instance-attribute
entity_name: str = 'robot'
Name of the asset in the environment for which the commands are generated.
params
class-attribute
instance-attribute
params: VehicleParams = field(default_factory=VehicleParams)
Vehicle parameters.
UniformPoseCommandGlobal
UniformPoseCommandGlobal(cfg: UniformPoseCommandGlobalCfg, env: ManagerBasedRlEnv)
Bases: CommandTerm
Command generator that generates pose commands containing a 3-D position and heading.
The command generator samples uniform 3D positions around the environment origin. The
heading command is either set to point towards the target or is sampled uniformly.
This can be configured through the :attr:UniformPoseCommandGlobalCfg.simple_heading
parameter in the configuration.
Initialize the command generator class.
参数:
| 名称 | 类型 | 描述 | 默认 |
|---|---|---|---|
|
UniformPoseCommandGlobalCfg
|
The configuration parameters for the command generator. |
必需 |
|
ManagerBasedRlEnv
|
The environment object. |
必需 |
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
cfg |
UniformPoseCommandGlobalCfg
|
Configuration for the command generator. |
command |
Tensor
|
The desired 3D-pose in base frame. Shape is (num_envs, 4). |
cfg
instance-attribute
cfg: UniformPoseCommandGlobalCfg
Configuration for the command generator.
command
property
command: Tensor
The desired 3D-pose in base frame. Shape is (num_envs, 4).
UniformPoseCommandGlobalCfg
dataclass
UniformPoseCommandGlobalCfg(*, class_type: type = UniformPoseCommandGlobal, entity_name: str, simple_heading: bool, ranges: Ranges, viz: VizCfg = VizCfg())
Bases: CommandTermCfg
Configuration for the uniform 3D-pose command generator.
类:
| 名称 | 描述 |
|---|---|
Ranges |
Uniform distribution ranges for the position commands. |
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
entity_name |
str
|
Name of the asset in the environment for which the commands are generated. |
simple_heading |
bool
|
Whether to use simple heading or not. |
ranges |
Ranges
|
Distribution ranges for the position commands. |
entity_name
instance-attribute
entity_name: str
Name of the asset in the environment for which the commands are generated.
simple_heading
instance-attribute
simple_heading: bool
Whether to use simple heading or not.
If True, the heading is in the direction of the target position.
ranges
instance-attribute
ranges: Ranges
Distribution ranges for the position commands.
Ranges
dataclass
Ranges(pos_x: tuple[float, float], pos_y: tuple[float, float], pos_z: tuple[float, float], heading: tuple[float, float])
Uniform distribution ranges for the position commands.
属性:
| 名称 | 类型 | 描述 |
|---|---|---|
pos_x |
tuple[float, float]
|
Range for the x position (in m). |
pos_y |
tuple[float, float]
|
Range for the y position (in m). |
pos_z |
tuple[float, float]
|
Range for the z position (in m). |
heading |
tuple[float, float]
|
Heading range for the position commands (in rad). |
pos_x
instance-attribute
pos_x: tuple[float, float]
Range for the x position (in m).
pos_y
instance-attribute
pos_y: tuple[float, float]
Range for the y position (in m).
pos_z
instance-attribute
pos_z: tuple[float, float]
Range for the z position (in m).
heading
instance-attribute
heading: tuple[float, float]
Heading range for the position commands (in rad).
Used only if :attr:simple_heading is False.
lin_vel_l2
lin_vel_l2(env: ManagerBasedRlEnv, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize base linear velocity using L2 squared kernel.
ang_vel_l2
ang_vel_l2(env: ManagerBasedRlEnv, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize base angular velocity using L2 squared kernel.
pos_error_l2
pos_error_l2(env: ManagerBasedRlEnv, command_name: str, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize asset pos from its target pos using L2 squared kernel.
pos_error_tanh
pos_error_tanh(env: ManagerBasedRlEnv, command_name: str, std: float = 0.8, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize asset pos from its target pos using tanh kernel.
yaw_error_l2
yaw_error_l2(env: ManagerBasedRlEnv, command_name: str, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize heading error from target heading using L2 squared kernel.
yaw_error_tanh
yaw_error_tanh(env: ManagerBasedRlEnv, command_name: str, std: float = 0.8, asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG) -> torch.Tensor
Penalize heading error from target heading using tanh kernel.