Browse Source

SITL: added SIM_FLOW_DELAY parameter

master
Andrew Tridgell 10 years ago
parent
commit
228b04e21e
  1. 1
      libraries/SITL/SITL.cpp
  2. 1
      libraries/SITL/SITL.h

1
libraries/SITL/SITL.cpp

@ -64,6 +64,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { @@ -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
};

1
libraries/SITL/SITL.h

@ -83,6 +83,7 @@ public: @@ -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…
Cancel
Save