mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
SITL: added SIM_GPS2_ENABLE option
This commit is contained in:
parent
8d99de5eb5
commit
7a52938f68
@ -54,6 +54,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
||||
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
||||
AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
|
||||
AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -63,6 +63,7 @@ public:
|
||||
AP_Float drift_time; // period in minutes
|
||||
AP_Float engine_mul; // engine multiplier
|
||||
AP_Int8 gps_disable; // disable simulated GPS
|
||||
AP_Int8 gps2_enable; // enable 2nd simulated GPS
|
||||
AP_Int8 gps_delay; // delay in samples
|
||||
AP_Int8 gps_type; // see enum GPSType
|
||||
AP_Float gps_byteloss;// byte loss as a percent
|
||||
|
Loading…
Reference in New Issue
Block a user