mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: move automatic declination setting into AP_Compass itself
This commit is contained in:
parent
1adda1ccf0
commit
9d54b4820f
@ -283,9 +283,6 @@ 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
|
||||
|
@ -423,7 +423,6 @@ private:
|
||||
bool trim_radio();
|
||||
|
||||
// sensors.cpp
|
||||
void init_compass_location(void);
|
||||
void update_compass(void);
|
||||
void compass_save(void);
|
||||
void init_beacon();
|
||||
|
@ -3,21 +3,6 @@
|
||||
#include <AP_RangeFinder/RangeFinder_Backend.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
|
||||
/*
|
||||
initialise compass's location used for declination
|
||||
*/
|
||||
void Rover::init_compass_location(void)
|
||||
{
|
||||
// update initial location used for declination
|
||||
if (!compass_init_location) {
|
||||
Location loc;
|
||||
if (ahrs.get_position(loc)) {
|
||||
compass.set_initial_location(loc.lat, loc.lng);
|
||||
compass_init_location = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// check for new compass data - 10Hz
|
||||
void Rover::update_compass(void)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user