AP_HAL_SITL: remove unused/unimplemented methods/vars, tidy namespacing
This commit is contained in:
parent
7f0bf89003
commit
02dc42275c
@ -72,9 +72,6 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||
|
||||
// find the barometer object if it exists
|
||||
_sitl = AP::sitl();
|
||||
_barometer = AP_Baro::get_singleton();
|
||||
_ins = AP_InertialSensor::get_singleton();
|
||||
_compass = Compass::get_singleton();
|
||||
|
||||
if (_sitl != nullptr) {
|
||||
// setup some initial values
|
||||
@ -828,7 +825,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
|
||||
uint32_t now = AP_HAL::micros();
|
||||
last_update_usec = now;
|
||||
|
||||
float altitude = _barometer?_barometer->get_altitude():0;
|
||||
float altitude = AP::baro().get_altitude();
|
||||
float wind_speed = 0;
|
||||
float wind_direction = 0;
|
||||
float wind_dir_z = 0;
|
||||
|
@ -77,7 +77,6 @@ public:
|
||||
Blimp
|
||||
};
|
||||
|
||||
ssize_t gps_read(int fd, void *buf, size_t count);
|
||||
uint16_t pwm_output[SITL_NUM_CHANNELS];
|
||||
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS];
|
||||
bool output_ready = false;
|
||||
@ -162,10 +161,7 @@ private:
|
||||
pid_t _parent_pid;
|
||||
uint32_t _update_count;
|
||||
|
||||
AP_Baro *_barometer;
|
||||
AP_InertialSensor *_ins;
|
||||
Scheduler *_scheduler;
|
||||
Compass *_compass;
|
||||
|
||||
SocketAPM _sitl_rc_in{true};
|
||||
SITL::SIM *_sitl;
|
||||
|
@ -56,12 +56,6 @@ public:
|
||||
size_t write(uint8_t c) override;
|
||||
size_t write(const uint8_t *buffer, size_t size) override;
|
||||
|
||||
// file descriptor, exposed so SITL_State::loop_hook() can use it
|
||||
int _fd;
|
||||
|
||||
// file descriptor for reading multicast packets
|
||||
int _mc_fd;
|
||||
|
||||
bool _unbuffered_writes;
|
||||
|
||||
enum flow_control get_flow_control(void) override { return FLOW_CONTROL_ENABLE; }
|
||||
@ -88,6 +82,12 @@ public:
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
||||
|
||||
private:
|
||||
|
||||
int _fd;
|
||||
|
||||
// file descriptor for reading multicast packets
|
||||
int _mc_fd;
|
||||
|
||||
uint8_t _portNumber;
|
||||
bool _connected = false; // true if a client has connected
|
||||
bool _use_send_recv = false;
|
||||
|
@ -45,13 +45,13 @@ void SITL_State::_update_airspeed(float airspeed)
|
||||
if (!is_zero(_sitl->arspd_fail_pressure[0])) {
|
||||
// compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude
|
||||
// algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure
|
||||
float tube_pressure = fabsf(_sitl->arspd_fail_pressure[0] - _barometer->get_pressure() + _sitl->arspd_fail_pitot_pressure[0]);
|
||||
float tube_pressure = fabsf(_sitl->arspd_fail_pressure[0] - AP::baro().get_pressure() + _sitl->arspd_fail_pitot_pressure[0]);
|
||||
airspeed = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0));
|
||||
}
|
||||
if (!is_zero(_sitl->arspd_fail_pressure[1])) {
|
||||
// compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude
|
||||
// algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure
|
||||
float tube_pressure = fabsf(_sitl->arspd_fail_pressure[1] - _barometer->get_pressure() + _sitl->arspd_fail_pitot_pressure[1]);
|
||||
float tube_pressure = fabsf(_sitl->arspd_fail_pressure[1] - AP::baro().get_pressure() + _sitl->arspd_fail_pitot_pressure[1]);
|
||||
airspeed2 = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0));
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user