SITL: added is_lock_step_scheduled() API

used to fix panic on bad timing
This commit is contained in:
Andrew Tridgell 2021-05-18 10:25:12 +10:00
parent d1f6d913d5
commit bf1f27af32
13 changed files with 15 additions and 1 deletions

View File

@ -330,6 +330,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
// initialise home // initialise home
fdm.home = home; fdm.home = home;
} }
fdm.is_lock_step_scheduled = lock_step_scheduled;
fdm.latitude = location.lat * 1.0e-7; fdm.latitude = location.lat * 1.0e-7;
fdm.longitude = location.lng * 1.0e-7; fdm.longitude = location.lng * 1.0e-7;
fdm.altitude = location.alt * 1.0e-2; fdm.altitude = location.alt * 1.0e-2;

View File

@ -173,6 +173,7 @@ protected:
float battery_voltage = -1.0f; float battery_voltage = -1.0f;
float battery_current; float battery_current;
float local_ground_level; // ground level at local position float local_ground_level; // ground level at local position
bool lock_step_scheduled;
// battery model // battery model
Battery battery; Battery battery;

View File

@ -28,6 +28,7 @@ BalanceBot::BalanceBot(const char *frame_str) :
skid_turn_rate(0.15708) // meters/sec skid_turn_rate(0.15708) // meters/sec
{ {
dcm.from_euler(0,0,0); // initial yaw, pitch and roll in radians dcm.from_euler(0,0,0); // initial yaw, pitch and roll in radians
lock_step_scheduled = true;
printf("Balance Bot Simulation Started\n"); printf("Balance Bot Simulation Started\n");
} }

View File

@ -28,6 +28,7 @@ Blimp::Blimp(const char *frame_str) :
{ {
frame_height = 0.0; frame_height = 0.0;
ground_behavior = GROUND_BEHAVIOR_NONE; ground_behavior = GROUND_BEHAVIOR_NONE;
lock_step_scheduled = true;
} }
// calculate rotational and linear accelerations // calculate rotational and linear accelerations

View File

@ -52,6 +52,7 @@ Helicopter::Helicopter(const char *frame_str) :
gas_heli = (strstr(frame_str, "-gas") != nullptr); gas_heli = (strstr(frame_str, "-gas") != nullptr);
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
lock_step_scheduled = true;
} }
/* /*

View File

@ -38,6 +38,7 @@ MultiCopter::MultiCopter(const char *frame_str) :
frame_height = 0.1; frame_height = 0.1;
num_motors = frame->num_motors; num_motors = frame->num_motors;
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
lock_step_scheduled = true;
} }
// calculate rotational and linear accelerations // calculate rotational and linear accelerations

View File

@ -37,7 +37,8 @@ Plane::Plane(const char *frame_str) :
num_motors = 1; num_motors = 1;
ground_behavior = GROUND_BEHAVIOR_FWD_ONLY; ground_behavior = GROUND_BEHAVIOR_FWD_ONLY;
lock_step_scheduled = true;
if (strstr(frame_str, "-heavy")) { if (strstr(frame_str, "-heavy")) {
mass = 8; mass = 8;
} }

View File

@ -95,6 +95,7 @@ QuadPlane::QuadPlane(const char *frame_str) :
frame->set_mass(mass); frame->set_mass(mass);
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
lock_step_scheduled = true;
} }
/* /*

View File

@ -41,6 +41,7 @@ SimRover::SimRover(const char *frame_str) :
if (vectored_thrust) { if (vectored_thrust) {
printf("Vectored Thrust Rover Simulation Started\n"); printf("Vectored Thrust Rover Simulation Started\n");
} }
lock_step_scheduled = true;
} }

View File

@ -46,6 +46,7 @@ Sailboat::Sailboat(const char *frame_str) :
sail_area(1.0) sail_area(1.0)
{ {
motor_connected = (strcmp(frame_str, "sailboat-motor") == 0); motor_connected = (strcmp(frame_str, "sailboat-motor") == 0);
lock_step_scheduled = true;
} }
// calculate the lift and drag as values from 0 to 1 // calculate the lift and drag as values from 0 to 1

View File

@ -39,6 +39,7 @@ SingleCopter::SingleCopter(const char *frame_str) :
*/ */
thrust_scale = (mass * GRAVITY_MSS) / hover_throttle; thrust_scale = (mass * GRAVITY_MSS) / hover_throttle;
frame_height = 0.1; frame_height = 0.1;
lock_step_scheduled = true;
} }
/* /*

View File

@ -62,6 +62,7 @@ Submarine::Submarine(const char *frame_str) :
thrusters = vectored_6dof_thrusters; thrusters = vectored_6dof_thrusters;
n_thrusters = 8; n_thrusters = 8;
} }
lock_step_scheduled = true;
} }
// calculate rotational and linear accelerations // calculate rotational and linear accelerations

View File

@ -81,6 +81,8 @@ struct sitl_fdm {
float speed; float speed;
float direction; float direction;
} wind_vane_apparent; } wind_vane_apparent;
bool is_lock_step_scheduled;
}; };
// number of rc output channels // number of rc output channels