mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
SITL: added SIM_GPS_LOG_NUM
for replaying GPS logs recorded with --enable-gps-logging
This commit is contained in:
parent
761e4a05e2
commit
01cad1c4aa
@ -1023,7 +1023,7 @@ void GPS::update_file()
|
||||
{
|
||||
static int fd[2] = {-1,-1};
|
||||
static uint32_t base_time[2];
|
||||
const uint16_t lognum = 9;
|
||||
const uint16_t lognum = uint16_t(_sitl->gps_log_num.get());
|
||||
if (instance > 1) {
|
||||
return;
|
||||
}
|
||||
|
@ -376,6 +376,8 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
|
||||
AP_GROUPINFO("INIT_LON_OFS", 46, SIM, gps_init_lon_ofs, 0),
|
||||
AP_GROUPINFO("INIT_ALT_OFS", 47, SIM, gps_init_alt_ofs, 0),
|
||||
|
||||
AP_GROUPINFO("GPS_LOG_NUM", 48, SIM, gps_log_num, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
#endif // HAL_SIM_GPS_ENABLED
|
||||
|
@ -209,6 +209,9 @@ public:
|
||||
AP_Float gps_init_lon_ofs;
|
||||
AP_Float gps_init_alt_ofs;
|
||||
|
||||
// log number for GPS::update_file()
|
||||
AP_Int16 gps_log_num;
|
||||
|
||||
AP_Float batt_voltage; // battery voltage base
|
||||
AP_Float batt_capacity_ah; // battery capacity in Ah
|
||||
AP_Int8 rc_fail; // fail RC input
|
||||
|
Loading…
Reference in New Issue
Block a user