mirror of https://github.com/ArduPilot/ardupilot
DataFlash: use baro singleton
This commit is contained in:
parent
5da78ff17d
commit
735f671726
|
@ -121,7 +121,7 @@ public:
|
||||||
void Log_Write_RCIN(void);
|
void Log_Write_RCIN(void);
|
||||||
void Log_Write_RCOUT(void);
|
void Log_Write_RCOUT(void);
|
||||||
void Log_Write_RSSI(AP_RSSI &rssi);
|
void Log_Write_RSSI(AP_RSSI &rssi);
|
||||||
void Log_Write_Baro(AP_Baro &baro, uint64_t time_us=0);
|
void Log_Write_Baro(uint64_t time_us=0);
|
||||||
void Log_Write_Power(void);
|
void Log_Write_Power(void);
|
||||||
void Log_Write_AHRS2(AP_AHRS &ahrs);
|
void Log_Write_AHRS2(AP_AHRS &ahrs);
|
||||||
void Log_Write_POS(AP_AHRS &ahrs);
|
void Log_Write_POS(AP_AHRS &ahrs);
|
||||||
|
@ -295,7 +295,7 @@ private:
|
||||||
void Log_Write_EKF3(AP_AHRS_NavEKF &ahrs);
|
void Log_Write_EKF3(AP_AHRS_NavEKF &ahrs);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void Log_Write_Baro_instance(AP_Baro &baro, uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
|
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
|
||||||
void Log_Write_IMU_instance(const AP_InertialSensor &ins,
|
void Log_Write_IMU_instance(const AP_InertialSensor &ins,
|
||||||
uint64_t time_us,
|
uint64_t time_us,
|
||||||
uint8_t imu_instance,
|
uint8_t imu_instance,
|
||||||
|
|
|
@ -425,8 +425,9 @@ void DataFlash_Class::Log_Write_RSSI(AP_RSSI &rssi)
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Class::Log_Write_Baro_instance(AP_Baro &baro, uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
|
void DataFlash_Class::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
|
||||||
{
|
{
|
||||||
|
AP_Baro &baro = AP::baro();
|
||||||
float climbrate = baro.get_climb_rate();
|
float climbrate = baro.get_climb_rate();
|
||||||
float drift_offset = baro.get_baro_drift_offset();
|
float drift_offset = baro.get_baro_drift_offset();
|
||||||
float ground_temp = baro.get_ground_temperature();
|
float ground_temp = baro.get_ground_temperature();
|
||||||
|
@ -445,17 +446,18 @@ void DataFlash_Class::Log_Write_Baro_instance(AP_Baro &baro, uint64_t time_us, u
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a BARO packet
|
// Write a BARO packet
|
||||||
void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us)
|
void DataFlash_Class::Log_Write_Baro(uint64_t time_us)
|
||||||
{
|
{
|
||||||
if (time_us == 0) {
|
if (time_us == 0) {
|
||||||
time_us = AP_HAL::micros64();
|
time_us = AP_HAL::micros64();
|
||||||
}
|
}
|
||||||
Log_Write_Baro_instance(baro, time_us, 0, LOG_BARO_MSG);
|
const AP_Baro &baro = AP::baro();
|
||||||
|
Log_Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
|
||||||
if (baro.num_instances() > 1 && baro.healthy(1)) {
|
if (baro.num_instances() > 1 && baro.healthy(1)) {
|
||||||
Log_Write_Baro_instance(baro, time_us, 1, LOG_BAR2_MSG);
|
Log_Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
|
||||||
}
|
}
|
||||||
if (baro.num_instances() > 2 && baro.healthy(2)) {
|
if (baro.num_instances() > 2 && baro.healthy(2)) {
|
||||||
Log_Write_Baro_instance(baro, time_us, 2, LOG_BAR3_MSG);
|
Log_Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue