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

Prevent internal error from compass custom rotation #14315

Merged
merged 1 commit into from
May 21, 2020
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
4 changes: 3 additions & 1 deletion libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,9 @@ friend class AP_Compass_Backend;
// set overall board orientation
void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
_board_orientation = orientation;
_custom_rotation = custom_rotation;
if (custom_rotation) {
Copy link
Contributor

Choose a reason for hiding this comment

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

why the check? if it's nullptr, then don't we want that set? eg. if it changes

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

_custom_rotation is either used for a board custom rotation (internal) or for a compass custom rotation (external). set_board_orientation() is called unilaterally after set_rotation(). So what happens is you select a custom rotation for the compass, it gets setup in set_rotation() and then it gets zeroed out in set_board_orientation(). The other way to do this would be simply to have two variables - one for the board and one for the compass - but they are never used together and it would mean changing all the sites where it is checked.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Urrg, re-reviewing this I think I am wrong - the compass rotation is stored in the front-end so it's perfectly possible for there to be a custom board orientation and and a custom external compass orientation at the same time. So we need two slots (which we effectively had before the change to save the 36 bytes of flash).

_custom_rotation = custom_rotation;
}
}

/// Set the motor compensation type
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Compass/AP_Compass_SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ AP_Compass_SITL::AP_Compass_SITL()

// save so the compass always comes up configured in SITL
save_dev_id(_compass_instance[_num_compass]);
set_rotation(instance, ROTATION_NONE);
_num_compass++;
}
}
Expand Down