mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_Compass: remove vestiges of LearnType::LEARN_INTERNAL
57a3bc1397
changed the code from "internal" to "in-flight
It seems the old value of "1" was no longer valid
It also changed things to that the learning system saved the offsets.
This commit is contained in:
parent
e294cc03f9
commit
9e4a180878
@ -117,7 +117,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
||||
// @Param: LEARN
|
||||
// @DisplayName: Learn compass offsets automatically
|
||||
// @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
|
||||
// @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning
|
||||
// @Values: 0:Disabled,2:EKF-Learning,3:InFlight-Learning
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
|
||||
#endif
|
||||
|
@ -320,7 +320,7 @@ public:
|
||||
|
||||
enum LearnType {
|
||||
LEARN_NONE=0,
|
||||
LEARN_INTERNAL=1,
|
||||
// LEARN_INTERNAL=1,
|
||||
LEARN_EKF=2,
|
||||
LEARN_INFLIGHT=3
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user