mirror of https://github.com/ArduPilot/ardupilot
Rover: remove compass accumulate
This commit is contained in:
parent
b323a5bffe
commit
936dca7531
|
@ -74,7 +74,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
#endif
|
||||
SCHED_TASK(gcs_failsafe_check, 10, 200),
|
||||
SCHED_TASK(fence_check, 10, 200),
|
||||
SCHED_TASK(compass_accumulate, 50, 200),
|
||||
SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200),
|
||||
SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300),
|
||||
SCHED_TASK(one_second_loop, 1, 1500),
|
||||
|
@ -291,6 +290,9 @@ void Rover::one_second_loop(void)
|
|||
update_home();
|
||||
}
|
||||
|
||||
// init compass location for declination
|
||||
init_compass_location();
|
||||
|
||||
// update error mask of sensors and subsystems. The mask uses the
|
||||
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
|
||||
// indicates that the sensor or subsystem is present but not
|
||||
|
|
|
@ -492,7 +492,7 @@ private:
|
|||
|
||||
// sensors.cpp
|
||||
void init_compass(void);
|
||||
void compass_accumulate(void);
|
||||
void init_compass_location(void);
|
||||
void init_beacon();
|
||||
void init_visual_odom();
|
||||
void update_visual_odom();
|
||||
|
|
|
@ -18,17 +18,10 @@ void Rover::init_compass()
|
|||
}
|
||||
|
||||
/*
|
||||
if the compass is enabled then try to accumulate a reading
|
||||
also update initial location used for declination
|
||||
initialise compass's location used for declination
|
||||
*/
|
||||
void Rover::compass_accumulate(void)
|
||||
void Rover::init_compass_location(void)
|
||||
{
|
||||
if (!g.compass_enabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
compass.accumulate();
|
||||
|
||||
// update initial location used for declination
|
||||
if (!compass_init_location) {
|
||||
Location loc;
|
||||
|
|
Loading…
Reference in New Issue