mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: use singleton getter for Baro in SIMState
this instance variable was always nullptr due to constructor ordering
This commit is contained in:
parent
27c4293302
commit
1c9d01c8fd
|
@ -43,9 +43,6 @@ void SIMState::_sitl_setup(const char *home_str)
|
|||
_home_str = home_str;
|
||||
|
||||
printf("Starting SITL input\n");
|
||||
|
||||
// find the barometer object if it exists
|
||||
_barometer = AP_Baro::get_singleton();
|
||||
}
|
||||
|
||||
|
||||
|
@ -235,6 +232,9 @@ void SIMState::_simulator_servos(struct sitl_input &input)
|
|||
uint32_t now = AP_HAL::micros();
|
||||
// last_update_usec = now;
|
||||
|
||||
// find the barometer object if it exists
|
||||
const auto *_barometer = AP_Baro::get_singleton();
|
||||
|
||||
float altitude = _barometer?_barometer->get_altitude():0;
|
||||
float wind_speed = 0;
|
||||
float wind_direction = 0;
|
||||
|
|
|
@ -87,8 +87,6 @@ private:
|
|||
pid_t _parent_pid;
|
||||
uint32_t _update_count;
|
||||
|
||||
class AP_Baro *_barometer;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
SocketAPM _sitl_rc_in{true};
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue