mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
SITL: added SIM_GPSDRIFTALT simulation control
This commit is contained in:
parent
3535574b9d
commit
63c792bc1c
@ -65,6 +65,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
|
||||
AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
|
||||
AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
|
||||
AP_GROUPINFO("GPS_DRIFTALT", 37, SITL, gps_drift_alt, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -90,6 +90,7 @@ public:
|
||||
AP_Float wind_speed;
|
||||
AP_Float wind_direction;
|
||||
AP_Float wind_turbulance;
|
||||
AP_Float gps_drift_alt;
|
||||
|
||||
void simstate_send(mavlink_channel_t chan);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user