mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Rover: call compass cal routine directly from sched table
This commit is contained in:
parent
0e8722181f
commit
47d9960eb9
@ -85,7 +85,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||||||
SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300),
|
SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300),
|
||||||
SCHED_TASK(one_second_loop, 1, 1500),
|
SCHED_TASK(one_second_loop, 1, 1500),
|
||||||
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90),
|
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90),
|
||||||
SCHED_TASK(compass_cal_update, 50, 200),
|
SCHED_TASK_CLASS(Compass, &rover.compass, cal_update, 50, 200),
|
||||||
SCHED_TASK(compass_save, 0.1, 200),
|
SCHED_TASK(compass_save, 0.1, 200),
|
||||||
SCHED_TASK(accel_cal_update, 10, 200),
|
SCHED_TASK(accel_cal_update, 10, 200),
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
@ -463,7 +463,6 @@ private:
|
|||||||
// sensors.cpp
|
// sensors.cpp
|
||||||
void init_compass_location(void);
|
void init_compass_location(void);
|
||||||
void update_compass(void);
|
void update_compass(void);
|
||||||
void compass_cal_update(void);
|
|
||||||
void compass_save(void);
|
void compass_save(void);
|
||||||
void init_beacon();
|
void init_beacon();
|
||||||
void init_visual_odom();
|
void init_visual_odom();
|
||||||
|
@ -30,13 +30,6 @@ void Rover::update_compass(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Calibrate compass
|
|
||||||
void Rover::compass_cal_update() {
|
|
||||||
if (!hal.util->get_soft_armed()) {
|
|
||||||
compass.compass_cal_update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Save compass offsets
|
// Save compass offsets
|
||||||
void Rover::compass_save() {
|
void Rover::compass_save() {
|
||||||
if (AP::compass().enabled() &&
|
if (AP::compass().enabled() &&
|
||||||
|
Loading…
Reference in New Issue
Block a user