mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
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:
parent
7b9f0f3fd7
commit
f5320e8816
@ -224,7 +224,9 @@ public:
|
|||||||
// set overall board orientation
|
// set overall board orientation
|
||||||
void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
|
void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
|
||||||
_board_orientation = orientation;
|
_board_orientation = orientation;
|
||||||
_custom_rotation = custom_rotation;
|
if (custom_rotation) {
|
||||||
|
_custom_rotation = custom_rotation;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Set the motor compensation type
|
/// Set the motor compensation type
|
||||||
|
@ -24,6 +24,7 @@ AP_Compass_SITL::AP_Compass_SITL()
|
|||||||
|
|
||||||
// save so the compass always comes up configured in SITL
|
// save so the compass always comes up configured in SITL
|
||||||
save_dev_id(_compass_instance[_num_compass]);
|
save_dev_id(_compass_instance[_num_compass]);
|
||||||
|
set_rotation(instance, ROTATION_NONE);
|
||||||
_num_compass++;
|
_num_compass++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user