AP_Compass: allow for COMPASS_EXTERNAL=2 for forced external

this allows users with unusual compass bus connections to force the
compass to external
This commit is contained in:
Andrew Tridgell 2016-04-29 09:16:14 +10:00
parent e7974702d4
commit 0e32c047c3
2 changed files with 9 additions and 7 deletions

View File

@ -113,8 +113,8 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Param: EXTERNAL
// @DisplayName: Compass is attached via an external cable
// @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk, but must be set correctly on an APM2. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option
// @Values: 0:Internal,1:External
// @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
// @Values: 0:Internal,1:External,2:ForcedExternal
// @User: Advanced
AP_GROUPINFO("EXTERNAL", 9, Compass, _state[0].external, 0),
@ -244,8 +244,8 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Param: EXTERN2
// @DisplayName: Compass2 is attached via an external cable
// @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
// @Values: 0:Internal,1:External,2:ForcedExternal
// @User: Advanced
AP_GROUPINFO("EXTERN2",20, Compass, _state[1].external, 0),
@ -265,8 +265,8 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Param: EXTERN3
// @DisplayName: Compass3 is attached via an external cable
// @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
// @Values: 0:Internal,1:External,2:ForcedExternal
// @User: Advanced
AP_GROUPINFO("EXTERN3",23, Compass, _state[2].external, 0),

View File

@ -107,5 +107,7 @@ void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
*/
void AP_Compass_Backend::set_external(uint8_t instance, bool external)
{
_compass._state[instance].external.set(external);
if (_compass._state[instance].external != 2) {
_compass._state[instance].external.set(external);
}
}