mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_AHRS: make it possible to setup board orientation at runtime
This commit is contained in:
parent
4c9bc30f58
commit
aaaa5247e3
@ -46,7 +46,7 @@ public:
|
||||
|
||||
// init sets up INS board orientation
|
||||
virtual void init() {
|
||||
_ins->set_board_orientation((enum Rotation)_board_orientation.get());
|
||||
set_orientation();
|
||||
};
|
||||
|
||||
// Accessors
|
||||
@ -60,10 +60,19 @@ public:
|
||||
|
||||
void set_compass(Compass *compass) {
|
||||
_compass = compass;
|
||||
set_orientation();
|
||||
}
|
||||
|
||||
|
||||
// allow for runtime change of orientation
|
||||
// this makes initial config easier
|
||||
void set_orientation() {
|
||||
_ins->set_board_orientation((enum Rotation)_board_orientation.get());
|
||||
if (_compass != NULL) {
|
||||
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
|
||||
}
|
||||
}
|
||||
|
||||
void set_airspeed(AP_Airspeed *airspeed) {
|
||||
_airspeed = airspeed;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user