HAL_SITL: cope with no _sitl state
This commit is contained in:
parent
f5bc7f02a8
commit
c1016ae52e
@ -327,12 +327,13 @@ void SITL_State::_output_to_flightgear(void)
|
|||||||
*/
|
*/
|
||||||
void SITL_State::_fdm_input_local(void)
|
void SITL_State::_fdm_input_local(void)
|
||||||
{
|
{
|
||||||
|
if (_sitl == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
struct sitl_input input;
|
struct sitl_input input;
|
||||||
|
|
||||||
// check for direct RC input
|
// check for direct RC input
|
||||||
if (_sitl != nullptr) {
|
|
||||||
_check_rc_input();
|
_check_rc_input();
|
||||||
}
|
|
||||||
|
|
||||||
// construct servos structure for FDM
|
// construct servos structure for FDM
|
||||||
_simulator_servos(input);
|
_simulator_servos(input);
|
||||||
@ -350,7 +351,6 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
sitl_model->update_model(input);
|
sitl_model->update_model(input);
|
||||||
|
|
||||||
// get FDM output from the model
|
// get FDM output from the model
|
||||||
if (_sitl) {
|
|
||||||
sitl_model->fill_fdm(_sitl->state);
|
sitl_model->fill_fdm(_sitl->state);
|
||||||
|
|
||||||
#if HAL_NUM_CAN_IFACES
|
#if HAL_NUM_CAN_IFACES
|
||||||
@ -364,7 +364,6 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000;
|
pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
#if HAL_SIM_JSON_MASTER_ENABLED
|
#if HAL_SIM_JSON_MASTER_ENABLED
|
||||||
// output JSON state to ride along flight controllers
|
// output JSON state to ride along flight controllers
|
||||||
@ -373,16 +372,12 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
|
|
||||||
sim_update();
|
sim_update();
|
||||||
|
|
||||||
if (_sitl && _use_fg_view) {
|
if (_use_fg_view) {
|
||||||
_output_to_flightgear();
|
_output_to_flightgear();
|
||||||
}
|
}
|
||||||
|
|
||||||
// update simulation time
|
// update simulation time
|
||||||
if (_sitl) {
|
|
||||||
hal.scheduler->stop_clock(_sitl->state.timestamp_us);
|
hal.scheduler->stop_clock(_sitl->state.timestamp_us);
|
||||||
} else {
|
|
||||||
hal.scheduler->stop_clock(AP_HAL::micros64()+100);
|
|
||||||
}
|
|
||||||
|
|
||||||
set_height_agl();
|
set_height_agl();
|
||||||
|
|
||||||
@ -395,6 +390,9 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
*/
|
*/
|
||||||
void SITL_State::_simulator_servos(struct sitl_input &input)
|
void SITL_State::_simulator_servos(struct sitl_input &input)
|
||||||
{
|
{
|
||||||
|
if (_sitl == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
static uint32_t last_update_usec;
|
static uint32_t last_update_usec;
|
||||||
|
|
||||||
/* this maps the registers used for PWM outputs. The RC
|
/* this maps the registers used for PWM outputs. The RC
|
||||||
|
Loading…
Reference in New Issue
Block a user