SITL: add SIM_BATT_VOLTAGE

This commit is contained in:
Randy Mackay 2013-10-02 17:44:20 +09:00
parent 21360aeebf
commit 8d1d8c78b5
2 changed files with 3 additions and 1 deletions

View File

@ -44,6 +44,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("SERVO_RATE", 16, SITL, servo_rate, 0),
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
AP_GROUPEND
};

View File

@ -62,8 +62,9 @@ public:
AP_Int8 gps_type; // see enum GPSType
AP_Float gps_byteloss;// byte loss as a percent
AP_Int8 gps_numsats; // number of visible satellites
AP_Int8 gps_hertz; // GPS update rate in Hz
AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
AP_Int8 gps_hertz; // GPS update rate in Hz
AP_Float batt_voltage; // battery voltage base
// wind control
AP_Float wind_speed;