mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Compass: use_for_yaw for each compass
This commit is contained in:
parent
84d792216e
commit
798cc36e64
@ -45,7 +45,7 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
||||
// @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw, 1), // true if used for DCM yaw
|
||||
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw[0], 1), // true if used for DCM yaw
|
||||
|
||||
#if !defined( __AVR_ATmega1280__ )
|
||||
// @Param: AUTODEC
|
||||
@ -303,6 +303,21 @@ Compass::set_initial_location(int32_t latitude, int32_t longitude)
|
||||
#endif
|
||||
}
|
||||
|
||||
/// return true if the compass should be used for yaw calculations
|
||||
bool
|
||||
Compass::use_for_yaw(void) const
|
||||
{
|
||||
uint8_t prim = get_primary();
|
||||
return healthy(prim) && use_for_yaw(prim);
|
||||
}
|
||||
|
||||
/// return true if the specified compass can be used for yaw calculations
|
||||
bool
|
||||
Compass::use_for_yaw(uint8_t i) const
|
||||
{
|
||||
return _use_for_yaw[i];
|
||||
}
|
||||
|
||||
void
|
||||
Compass::set_declination(float radians, bool save_to_eeprom)
|
||||
{
|
||||
|
@ -151,9 +151,8 @@ public:
|
||||
void learn_offsets(void);
|
||||
|
||||
/// return true if the compass should be used for yaw calculations
|
||||
bool use_for_yaw(void) const {
|
||||
return healthy() && _use_for_yaw;
|
||||
}
|
||||
bool use_for_yaw(uint8_t i) const;
|
||||
bool use_for_yaw(void) const;
|
||||
|
||||
/// Sets the local magnetic field declination.
|
||||
///
|
||||
@ -253,7 +252,7 @@ protected:
|
||||
AP_Int8 _orientation;
|
||||
AP_Vector3f _offset[COMPASS_MAX_INSTANCES];
|
||||
AP_Float _declination;
|
||||
AP_Int8 _use_for_yaw; ///<enable use for yaw calculation
|
||||
AP_Int8 _use_for_yaw[COMPASS_MAX_INSTANCES];///<enable use for yaw calculation
|
||||
AP_Int8 _auto_declination; ///<enable automatic declination code
|
||||
AP_Int8 _external; ///<compass is external
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
|
Loading…
Reference in New Issue
Block a user