Browse Source

SITL: added SIM_LOOP_DELAY parameter

this allows us to test high CPU load conditions by adding a delay to
each loop
master
Andrew Tridgell 5 years ago
parent
commit
3d9f393f4b
  1. 3
      libraries/SITL/SITL.cpp
  2. 1
      libraries/SITL/SITL.h

3
libraries/SITL/SITL.cpp

@ -186,6 +186,9 @@ const AP_Param::GroupInfo SITL::var_info2[] = { @@ -186,6 +186,9 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
AP_GROUPINFO("OPOS_ALT", 53, SITL, opos.alt, 584.0f),
AP_GROUPINFO("OPOS_HDG", 54, SITL, opos.hdg, 353.0f),
// extra delay per main loop
AP_GROUPINFO("LOOP_DELAY", 55, SITL, loop_delay, 0),
AP_GROUPEND
};

1
libraries/SITL/SITL.h

@ -176,6 +176,7 @@ public: @@ -176,6 +176,7 @@ public:
AP_Float flow_noise; // optical flow measurement noise (rad/sec)
AP_Int8 baro_count; // number of simulated baros to create
AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
AP_Int32 loop_delay; // extra delay to add to every loop
// wind control
enum WindType {

Loading…
Cancel
Save