mirror of https://github.com/ArduPilot/ardupilot
Copter: Baro does its own dataflash logging
This commit is contained in:
parent
2b54113334
commit
c95ff96263
|
@ -828,7 +828,6 @@ private:
|
||||||
void Log_Write_Data(uint8_t id, uint16_t value);
|
void Log_Write_Data(uint8_t id, uint16_t value);
|
||||||
void Log_Write_Data(uint8_t id, float value);
|
void Log_Write_Data(uint8_t id, float value);
|
||||||
void Log_Write_Error(uint8_t sub_system, uint8_t error_code);
|
void Log_Write_Error(uint8_t sub_system, uint8_t error_code);
|
||||||
void Log_Write_Baro(void);
|
|
||||||
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high);
|
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high);
|
||||||
void Log_Write_Home_And_Origin();
|
void Log_Write_Home_And_Origin();
|
||||||
void Log_Sensor_Health();
|
void Log_Sensor_Health();
|
||||||
|
|
|
@ -336,13 +336,6 @@ void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
|
||||||
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
void Copter::Log_Write_Baro(void)
|
|
||||||
{
|
|
||||||
if (!ahrs.have_ekf_logging()) {
|
|
||||||
DataFlash.Log_Write_Baro();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
struct PACKED log_ParameterTuning {
|
struct PACKED log_ParameterTuning {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
|
@ -616,7 +609,6 @@ void Copter::Log_Write_Data(uint8_t id, int16_t value) {}
|
||||||
void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
|
void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
|
||||||
void Copter::Log_Write_Data(uint8_t id, float value) {}
|
void Copter::Log_Write_Data(uint8_t id, float value) {}
|
||||||
void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
||||||
void Copter::Log_Write_Baro(void) {}
|
|
||||||
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {}
|
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {}
|
||||||
void Copter::Log_Write_Home_And_Origin() {}
|
void Copter::Log_Write_Home_And_Origin() {}
|
||||||
void Copter::Log_Sensor_Health() {}
|
void Copter::Log_Sensor_Health() {}
|
||||||
|
|
|
@ -4,9 +4,7 @@
|
||||||
void Copter::read_barometer(void)
|
void Copter::read_barometer(void)
|
||||||
{
|
{
|
||||||
barometer.update();
|
barometer.update();
|
||||||
if (should_log(MASK_LOG_IMU)) {
|
|
||||||
Log_Write_Baro();
|
|
||||||
}
|
|
||||||
baro_alt = barometer.get_altitude() * 100.0f;
|
baro_alt = barometer.get_altitude() * 100.0f;
|
||||||
baro_climbrate = barometer.get_climb_rate() * 100.0f;
|
baro_climbrate = barometer.get_climb_rate() * 100.0f;
|
||||||
|
|
||||||
|
|
|
@ -210,6 +210,7 @@ void Copter::init_ardupilot()
|
||||||
|
|
||||||
// read Baro pressure at ground
|
// read Baro pressure at ground
|
||||||
//-----------------------------
|
//-----------------------------
|
||||||
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||||
barometer.calibrate();
|
barometer.calibrate();
|
||||||
|
|
||||||
// initialise rangefinder
|
// initialise rangefinder
|
||||||
|
|
Loading…
Reference in New Issue