mirror of https://github.com/ArduPilot/ardupilot
SITL: added SIM_FLOW_RATE parameter
This commit is contained in:
parent
205b312789
commit
5758f39127
|
@ -63,6 +63,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||
AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
|
||||
AP_GROUPINFO("FLOW_ENABLE", 33, SITL, flow_enable, 0),
|
||||
AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
|
||||
AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -82,6 +82,7 @@ public:
|
|||
AP_Int8 baro_disable; // disable simulated barometer
|
||||
AP_Int8 float_exception; // enable floating point exception checks
|
||||
AP_Int8 flow_enable; // enable simulated optflow
|
||||
AP_Int16 flow_rate; // optflow data rate (Hz)
|
||||
AP_Int8 terrain_enable; // enable using terrain for height
|
||||
|
||||
// wind control
|
||||
|
|
Loading…
Reference in New Issue