mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
SITL: added SIM_GPS_TYPE control
for choosing what sort of GPS to simulate
This commit is contained in:
parent
e8806b14ec
commit
2ec2c58f67
@ -26,6 +26,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 5),
|
||||
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
|
||||
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2),
|
||||
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -32,6 +32,13 @@ public:
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
enum GPSType {
|
||||
GPS_TYPE_UBLOX = 0,
|
||||
GPS_TYPE_MTK = 1,
|
||||
GPS_TYPE_MTK16 = 2,
|
||||
GPS_TYPE_MTK19 = 3
|
||||
};
|
||||
|
||||
struct sitl_fdm state;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
@ -48,6 +55,7 @@ public:
|
||||
AP_Float engine_mul; // engine multiplier
|
||||
AP_Int8 gps_disable; // disable simulated GPS
|
||||
AP_Int8 gps_delay; // delay in samples
|
||||
AP_Int8 gps_type; // see enum GPSType
|
||||
|
||||
// wind control
|
||||
AP_Float wind_speed;
|
||||
|
Loading…
Reference in New Issue
Block a user