Browse Source

SITL: added SIM_RATE_HZ

this allows the physics step size to be changed while flying the
internal models, which allows for lower CPU usage
zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
e4596efe9b
  1. 3
      libraries/SITL/SIM_Aircraft.cpp
  2. 2
      libraries/SITL/SITL.cpp
  3. 1
      libraries/SITL/SITL.h

3
libraries/SITL/SIM_Aircraft.cpp

@ -598,6 +598,9 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) @@ -598,6 +598,9 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
}
}
}
// allow for changes in physics step
adjust_frame_time(constrain_float(sitl->loop_rate_hz, rate_hz-1, rate_hz+1));
}
/*

2
libraries/SITL/SITL.cpp

@ -257,6 +257,8 @@ const AP_Param::GroupInfo SITL::var_info3[] = { @@ -257,6 +257,8 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
// vicon velocity glitch in NED frame
AP_GROUPINFO("VICON_VGLI", 21, SITL, vicon_vel_glitch, 0),
AP_GROUPINFO("RATE_HZ", 22, SITL, loop_rate_hz, 1200),
AP_GROUPEND
};

1
libraries/SITL/SITL.h

@ -194,6 +194,7 @@ public: @@ -194,6 +194,7 @@ public:
AP_Float mag_scaling; // scaling factor on first compasses
AP_Int32 mag_devid[MAX_CONNECTED_MAGS]; // Mag devid
AP_Float buoyancy; // submarine buoyancy in Newtons
AP_Int16 loop_rate_hz;
// EFI type
enum EFIType {

Loading…
Cancel
Save