mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: Baro does its own dataflash logging
This commit is contained in:
parent
fdd410f105
commit
753b710477
@ -38,7 +38,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(update_GPS, 10, 4000),
|
SCHED_TASK(update_GPS, 10, 4000),
|
||||||
SCHED_TASK(update_compass, 10, 1500),
|
SCHED_TASK(update_compass, 10, 1500),
|
||||||
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500),
|
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500),
|
||||||
SCHED_TASK(update_barometer, 10, 1500),
|
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500),
|
||||||
SCHED_TASK(gcs_update, 50, 1700),
|
SCHED_TASK(gcs_update, 50, 1700),
|
||||||
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
||||||
SCHED_TASK(compass_accumulate, 50, 1500),
|
SCHED_TASK(compass_accumulate, 50, 1500),
|
||||||
|
@ -19,11 +19,6 @@ void Tracker::Log_Write_Attitude()
|
|||||||
DataFlash.Log_Write_POS(ahrs);
|
DataFlash.Log_Write_POS(ahrs);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tracker::Log_Write_Baro(void)
|
|
||||||
{
|
|
||||||
DataFlash.Log_Write_Baro();
|
|
||||||
}
|
|
||||||
|
|
||||||
struct PACKED log_Vehicle_Baro {
|
struct PACKED log_Vehicle_Baro {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
@ -95,7 +90,6 @@ void Tracker::log_init(void)
|
|||||||
#else // LOGGING_ENABLED
|
#else // LOGGING_ENABLED
|
||||||
|
|
||||||
void Tracker::Log_Write_Attitude(void) {}
|
void Tracker::Log_Write_Attitude(void) {}
|
||||||
void Tracker::Log_Write_Baro(void) {}
|
|
||||||
|
|
||||||
void Tracker::log_init(void) {}
|
void Tracker::log_init(void) {}
|
||||||
void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const Vector3f& vel) {}
|
void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const Vector3f& vel) {}
|
||||||
|
@ -220,7 +220,6 @@ private:
|
|||||||
void update_scan(void);
|
void update_scan(void);
|
||||||
bool servo_test_set_servo(uint8_t servo_num, uint16_t pwm);
|
bool servo_test_set_servo(uint8_t servo_num, uint16_t pwm);
|
||||||
void read_radio();
|
void read_radio();
|
||||||
void update_barometer(void);
|
|
||||||
void update_ahrs();
|
void update_ahrs();
|
||||||
void update_compass(void);
|
void update_compass(void);
|
||||||
void compass_accumulate(void);
|
void compass_accumulate(void);
|
||||||
@ -256,7 +255,6 @@ private:
|
|||||||
void init_capabilities(void);
|
void init_capabilities(void);
|
||||||
void compass_cal_update();
|
void compass_cal_update();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
void Log_Write_Baro(void);
|
|
||||||
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
|
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
|
||||||
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
||||||
void Log_Write_Vehicle_Startup_Messages();
|
void Log_Write_Vehicle_Startup_Messages();
|
||||||
|
@ -1,15 +1,5 @@
|
|||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
// read the barometer and return the updated altitude in meters
|
|
||||||
void Tracker::update_barometer(void)
|
|
||||||
{
|
|
||||||
barometer.update();
|
|
||||||
if (should_log(MASK_LOG_IMU)) {
|
|
||||||
Log_Write_Baro();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
update INS and attitude
|
update INS and attitude
|
||||||
*/
|
*/
|
||||||
|
@ -46,6 +46,7 @@ void Tracker::init_tracker()
|
|||||||
AP_Notify::flags.failsafe_battery = false;
|
AP_Notify::flags.failsafe_battery = false;
|
||||||
|
|
||||||
// init baro before we start the GCS, so that the CLI baro test works
|
// init baro before we start the GCS, so that the CLI baro test works
|
||||||
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||||
barometer.init();
|
barometer.init();
|
||||||
|
|
||||||
// we start by assuming USB connected, as we initialed the serial
|
// we start by assuming USB connected, as we initialed the serial
|
||||||
|
Loading…
Reference in New Issue
Block a user