Browse Source

Sub: move automatic declination setting into AP_Compass itself

mission-4.1.18
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
03e6065380
  1. 3
      ArduSub/ArduSub.cpp
  2. 1
      ArduSub/Sub.h
  3. 15
      ArduSub/sensors.cpp

3
ArduSub/ArduSub.cpp

@ -284,9 +284,6 @@ void Sub::one_hz_loop()
// log terrain data // log terrain data
terrain_logging(); terrain_logging();
// init compass location for declination
init_compass_location();
// need to set "likely flying" when armed to allow for compass // need to set "likely flying" when armed to allow for compass
// learning to run // learning to run
ahrs.set_likely_flying(hal.util->get_soft_armed()); ahrs.set_likely_flying(hal.util->get_soft_armed());

1
ArduSub/Sub.h

@ -454,7 +454,6 @@ private:
static const AP_Param::Info var_info[]; static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[]; static const struct LogStructure log_structure[];
void init_compass_location();
void fast_loop(); void fast_loop();
void fifty_hz_loop(); void fifty_hz_loop();
void update_batt_compass(void); void update_batt_compass(void);

15
ArduSub/sensors.cpp

@ -80,21 +80,6 @@ void Sub::rpm_update(void)
} }
#endif #endif
/*
initialise compass's location used for declination
*/
void Sub::init_compass_location()
{
// update initial location used for declination
if (!ap.compass_init_location) {
Location loc;
if (ahrs.get_position(loc)) {
compass.set_initial_location(loc.lat, loc.lng);
ap.compass_init_location = true;
}
}
}
// initialise optical flow sensor // initialise optical flow sensor
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
void Sub::init_optflow() void Sub::init_optflow()

Loading…
Cancel
Save