Browse Source

SITL: record throttle value instead of motors on/off

c415-sdk
Andy Piper 5 years ago committed by Andrew Tridgell
parent
commit
a6a020b3c7
  1. 2
      libraries/SITL/SITL.cpp
  2. 8
      libraries/SITL/SITL.h

2
libraries/SITL/SITL.cpp

@ -206,6 +206,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = { @@ -206,6 +206,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
// max motor vibration frequency
AP_GROUPINFO("VIB_MOT_MAX", 61, SITL, vibe_motor, 0.0f),
// minimum throttle for simulated ins noise
AP_GROUPINFO("INS_THR_MIN", 62, SITL, ins_noise_throttle_min, 0.1f),
AP_GROUPEND

8
libraries/SITL/SITL.h

@ -108,8 +108,8 @@ public: @@ -108,8 +108,8 @@ public:
// loop update rate in Hz
uint16_t update_rate_hz;
// true when motors are active
bool motors_on;
// throttle when motors are active
float throttle;
// height above ground
float height_agl;
@ -248,8 +248,10 @@ public: @@ -248,8 +248,10 @@ public:
// vibration frequencies in Hz on each axis
AP_Vector3f vibe_freq;
// hover frequency to use as baseline for adding motor noise for the gyros and accels
// max frequency to use as baseline for adding motor noise for the gyros and accels
AP_Float vibe_motor;
// minimum throttle for addition of ins noise
AP_Float ins_noise_throttle_min;
// gyro and accel fail masks
AP_Int8 gyro_fail_mask;

Loading…
Cancel
Save