SITL: added SIM_FLOW_DELAY parameter
This commit is contained in:
parent
0076413c0a
commit
228b04e21e
@ -64,6 +64,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
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_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -83,6 +83,7 @@ public:
|
||||
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 flow_delay; // optflow data delay
|
||||
AP_Int8 terrain_enable; // enable using terrain for height
|
||||
|
||||
// wind control
|
||||
|
Loading…
Reference in New Issue
Block a user