Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Compass: correct edge case where checks pass when saved dev_id != detected dev_id #7970

Merged
merged 3 commits into from
Aug 7, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 35 additions & 7 deletions libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -453,6 +453,24 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Description: When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
// @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix
AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),

// @Param: EXP_DID
// @DisplayName: Compass device id expected
// @Description: The expected value of COMPASS_DEV_ID, used by arming checks. Setting this to -1 means "don't care."
// @User: Advanced
AP_GROUPINFO("EXP_DID", 36, Compass, _state[0].expected_dev_id, -1),

// @Param: EXP_DID2
// @DisplayName: Compass2 device id expected
// @Description: The expected value of COMPASS_DEV_ID2, used by arming checks. Setting this to -1 means "don't care."
// @User: Advanced
AP_GROUPINFO("EXP_DID2", 37, Compass, _state[1].expected_dev_id, -1),

// @Param: EXP_DID3
// @DisplayName: Compass3 device id expected
// @Description: The expected value of COMPASS_DEV_ID3, used by arming checks. Setting this to -1 means "don't care."
// @User: Advanced
AP_GROUPINFO("EXP_DID3", 38, Compass, _state[2].expected_dev_id, -1),

AP_GROUPEND
};
Expand Down Expand Up @@ -1092,7 +1110,7 @@ void
Compass::save_offsets(uint8_t i)
{
_state[i].offset.save(); // save offsets
_state[i].dev_id.save(); // save device id corresponding to these offsets
_state[i].dev_id.set_and_save(_state[i].detected_dev_id);
}

void
Expand Down Expand Up @@ -1215,20 +1233,30 @@ bool Compass::configured(uint8_t i)
return false;
}

// backup detected dev_id
int32_t dev_id_orig = _state[i].dev_id;
// exit immediately if dev_id hasn't been detected
if (_state[i].detected_dev_id == 0) {
return false;
}

// back up cached value of dev_id
int32_t dev_id_cache_value = _state[i].dev_id;

// load dev_id from eeprom
_state[i].dev_id.load();

// if different then the device has not been configured
if (_state[i].dev_id != dev_id_orig) {
// restore device id
_state[i].dev_id = dev_id_orig;
// if dev_id loaded from eeprom is different from detected dev id or dev_id loaded from eeprom is different from cached dev_id, compass is unconfigured
if (_state[i].dev_id != _state[i].detected_dev_id || _state[i].dev_id != dev_id_cache_value) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does the second condition really matter? The only way I'm seeing for the second condition to be true is if it was the detection code changing it, in which case, the first condition is also true. Am I missing something?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

or if a user changed the ID by mavlink. I think the check is at worst harmless

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

or if a user changed the ID by mavlink.

No, if a user changed it via MAVLink, then it's saved, so the cache will be equal to the loaded value. If we cached the value on initialization then it could do something.

I agree it's harmless, but, unless I missed something, it is also useless.

// restore cached value
_state[i].dev_id = dev_id_cache_value;
// return failure
return false;
}

// if expected_dev_id is configured and the detected dev_id is different, return false
if (_state[i].expected_dev_id != -1 && _state[i].expected_dev_id != _state[i].dev_id) {
return false;
}

// if we got here then it must be configured
return true;
}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -435,6 +435,8 @@ friend class AP_Compass_Backend;
// saved to eeprom when offsets are saved allowing ram &
// eeprom values to be compared as consistency check
AP_Int32 dev_id;
AP_Int32 expected_dev_id;
int32_t detected_dev_id;

AP_Int8 use_for_yaw;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Compass/AP_Compass_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ uint8_t AP_Compass_Backend::register_compass(void) const
void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
{
_compass._state[instance].dev_id.set_and_notify(dev_id);
_compass._state[instance].detected_dev_id = dev_id;
}

/*
Expand Down