mirror of https://github.com/ArduPilot/ardupilot
SITL: allow for extra actuators to be marked as motors
This commit is contained in:
parent
dc3f6fe69d
commit
1138f9e624
|
@ -390,7 +390,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
|||
fdm.velocity_air_bf = velocity_air_bf;
|
||||
fdm.battery_voltage = battery_voltage;
|
||||
fdm.battery_current = battery_current;
|
||||
fdm.motor_mask = motor_mask;
|
||||
fdm.motor_mask = motor_mask | sitl->vibe_motor_mask;
|
||||
memcpy(fdm.rpm, rpm, sizeof(fdm.rpm));
|
||||
fdm.rcin_chan_count = rcin_chan_count;
|
||||
fdm.range = rangefinder_range();
|
||||
|
|
|
@ -174,6 +174,9 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
|
|||
// motor harmonics
|
||||
AP_GROUPINFO("VIB_MOT_HMNC", 60, SIM, vibe_motor_harmonics, 1),
|
||||
|
||||
// motor mask, allowing external simulators to mark motors
|
||||
AP_GROUPINFO("VIB_MOT_MASK", 5, SIM, vibe_motor_mask, 0),
|
||||
|
||||
// max motor vibration frequency
|
||||
AP_GROUPINFO("VIB_MOT_MAX", 61, SIM, vibe_motor, 0.0f),
|
||||
// minimum throttle for simulated ins noise
|
||||
|
|
|
@ -336,6 +336,9 @@ public:
|
|||
// what harmonics to generate
|
||||
AP_Int16 vibe_motor_harmonics;
|
||||
|
||||
// what servos are motors
|
||||
AP_Int32 vibe_motor_mask;
|
||||
|
||||
// minimum throttle for addition of ins noise
|
||||
AP_Float ins_noise_throttle_min;
|
||||
|
||||
|
|
Loading…
Reference in New Issue