used to fix panic on bad timing
@ -330,6 +330,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
// initialise home
fdm.home = home;
}
fdm.is_lock_step_scheduled = lock_step_scheduled;
fdm.latitude = location.lat * 1.0e-7;
fdm.longitude = location.lng * 1.0e-7;
fdm.altitude = location.alt * 1.0e-2;
@ -173,6 +173,7 @@ protected:
float battery_voltage = -1.0f;
float battery_current;
float local_ground_level; // ground level at local position
bool lock_step_scheduled;
// battery model
Battery battery;
@ -28,6 +28,7 @@ BalanceBot::BalanceBot(const char *frame_str) :
skid_turn_rate(0.15708) // meters/sec
{
dcm.from_euler(0,0,0); // initial yaw, pitch and roll in radians
lock_step_scheduled = true;
printf("Balance Bot Simulation Started\n");
@ -28,6 +28,7 @@ Blimp::Blimp(const char *frame_str) :
frame_height = 0.0;
ground_behavior = GROUND_BEHAVIOR_NONE;
// calculate rotational and linear accelerations
@ -52,6 +52,7 @@ Helicopter::Helicopter(const char *frame_str) :
gas_heli = (strstr(frame_str, "-gas") != nullptr);
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
/*
@ -38,6 +38,7 @@ MultiCopter::MultiCopter(const char *frame_str) :
frame_height = 0.1;
num_motors = frame->num_motors;
@ -37,7 +37,8 @@ Plane::Plane(const char *frame_str) :
num_motors = 1;
ground_behavior = GROUND_BEHAVIOR_FWD_ONLY;
if (strstr(frame_str, "-heavy")) {
mass = 8;
@ -95,6 +95,7 @@ QuadPlane::QuadPlane(const char *frame_str) :
frame->set_mass(mass);
@ -41,6 +41,7 @@ SimRover::SimRover(const char *frame_str) :
if (vectored_thrust) {
printf("Vectored Thrust Rover Simulation Started\n");
@ -46,6 +46,7 @@ Sailboat::Sailboat(const char *frame_str) :
sail_area(1.0)
motor_connected = (strcmp(frame_str, "sailboat-motor") == 0);
// calculate the lift and drag as values from 0 to 1
@ -39,6 +39,7 @@ SingleCopter::SingleCopter(const char *frame_str) :
*/
thrust_scale = (mass * GRAVITY_MSS) / hover_throttle;
@ -62,6 +62,7 @@ Submarine::Submarine(const char *frame_str) :
thrusters = vectored_6dof_thrusters;
n_thrusters = 8;
@ -81,6 +81,8 @@ struct sitl_fdm {
float speed;
float direction;
} wind_vane_apparent;
bool is_lock_step_scheduled;
};
// number of rc output channels