Browse Source

SITL: added is_lock_step_scheduled() API

used to fix panic on bad timing
zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
bf1f27af32
  1. 1
      libraries/SITL/SIM_Aircraft.cpp
  2. 1
      libraries/SITL/SIM_Aircraft.h
  3. 1
      libraries/SITL/SIM_BalanceBot.cpp
  4. 1
      libraries/SITL/SIM_Blimp.cpp
  5. 1
      libraries/SITL/SIM_Helicopter.cpp
  6. 1
      libraries/SITL/SIM_Multicopter.cpp
  7. 3
      libraries/SITL/SIM_Plane.cpp
  8. 1
      libraries/SITL/SIM_QuadPlane.cpp
  9. 1
      libraries/SITL/SIM_Rover.cpp
  10. 1
      libraries/SITL/SIM_Sailboat.cpp
  11. 1
      libraries/SITL/SIM_SingleCopter.cpp
  12. 1
      libraries/SITL/SIM_Submarine.cpp
  13. 2
      libraries/SITL/SITL.h

1
libraries/SITL/SIM_Aircraft.cpp

@ -330,6 +330,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) @@ -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;

1
libraries/SITL/SIM_Aircraft.h

@ -173,6 +173,7 @@ protected: @@ -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;

1
libraries/SITL/SIM_BalanceBot.cpp

@ -28,6 +28,7 @@ BalanceBot::BalanceBot(const char *frame_str) : @@ -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");
}

1
libraries/SITL/SIM_Blimp.cpp

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

1
libraries/SITL/SIM_Helicopter.cpp

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

1
libraries/SITL/SIM_Multicopter.cpp

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

3
libraries/SITL/SIM_Plane.cpp

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

1
libraries/SITL/SIM_QuadPlane.cpp

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

1
libraries/SITL/SIM_Rover.cpp

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

1
libraries/SITL/SIM_Sailboat.cpp

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

1
libraries/SITL/SIM_SingleCopter.cpp

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

1
libraries/SITL/SIM_Submarine.cpp

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

2
libraries/SITL/SITL.h

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

Loading…
Cancel
Save