mirror of https://github.com/ArduPilot/ardupilot
Rover: Baro does its own dataflash logging now
This commit is contained in:
parent
a5dc87e2af
commit
63e8fffbe4
|
@ -51,7 +51,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
SCHED_TASK(set_servos, 50, 200),
|
||||
SCHED_TASK(update_GPS_50Hz, 50, 300),
|
||||
SCHED_TASK(update_GPS_10Hz, 10, 300),
|
||||
SCHED_TASK(update_alt, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200),
|
||||
SCHED_TASK(update_visual_odom, 50, 200),
|
||||
|
@ -178,14 +178,6 @@ void Rover::ahrs_update()
|
|||
}
|
||||
}
|
||||
|
||||
void Rover::update_alt()
|
||||
{
|
||||
barometer.update();
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_Baro();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
check for GCS failsafe - 10Hz
|
||||
*/
|
||||
|
|
|
@ -204,11 +204,6 @@ void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
|
|||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void Rover::Log_Write_Baro(void)
|
||||
{
|
||||
DataFlash.Log_Write_Baro();
|
||||
}
|
||||
|
||||
// log ahrs home and EKF origin to dataflash
|
||||
void Rover::Log_Write_Home_And_Origin()
|
||||
{
|
||||
|
@ -345,7 +340,6 @@ void Rover::Log_Write_Attitude() {}
|
|||
void Rover::Log_Write_RC(void) {}
|
||||
void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
|
||||
void Rover::Log_Write_Home_And_Origin() {}
|
||||
void Rover::Log_Write_Baro(void) {}
|
||||
void Rover::Log_Arm_Disarm() {}
|
||||
void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
||||
void Rover::Log_Write_Steering() {}
|
||||
|
|
|
@ -384,7 +384,6 @@ private:
|
|||
// APMrover2.cpp
|
||||
void stats_update();
|
||||
void ahrs_update();
|
||||
void update_alt();
|
||||
void gcs_failsafe_check(void);
|
||||
void update_compass(void);
|
||||
void update_logging1(void);
|
||||
|
@ -491,7 +490,6 @@ private:
|
|||
void Log_Arm_Disarm();
|
||||
void Log_Write_RC(void);
|
||||
void Log_Write_Error(uint8_t sub_system, uint8_t error_code);
|
||||
void Log_Write_Baro(void);
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
|
||||
void Log_Write_WheelEncoder();
|
||||
|
|
|
@ -103,6 +103,7 @@ void Rover::init_ardupilot()
|
|||
init_visual_odom();
|
||||
|
||||
// and baro for EKF
|
||||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||
barometer.calibrate();
|
||||
|
||||
// Do GPS init
|
||||
|
|
Loading…
Reference in New Issue