AP_Compass: make sure SITL rotation gets initialized like all the others

don't remove a custom rotation that has already been set
This commit is contained in:
Andy Piper 2020-05-07 07:44:47 +01:00 committed by Andrew Tridgell
parent 7b9f0f3fd7
commit f5320e8816
2 changed files with 4 additions and 1 deletions

View File

@ -224,8 +224,10 @@ public:
// set overall board orientation
void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
_board_orientation = orientation;
if (custom_rotation) {
_custom_rotation = custom_rotation;
}
}
/// Set the motor compensation type
///

View File

@ -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++;
}
}