mirror of https://github.com/ArduPilot/ardupilot
ArduSub: make AHRS attitude member variables private
This commit is contained in:
parent
b3897c020e
commit
0275494042
|
@ -8,11 +8,11 @@ void Sub::update_turn_counter()
|
||||||
// Determine state
|
// Determine state
|
||||||
// 0: 0-90 deg, 1: 90-180 deg, 2: -180--90 deg, 3: -90--0 deg
|
// 0: 0-90 deg, 1: 90-180 deg, 2: -180--90 deg, 3: -90--0 deg
|
||||||
uint8_t turn_state;
|
uint8_t turn_state;
|
||||||
if (ahrs.yaw >= 0.0f && ahrs.yaw < radians(90)) {
|
if (ahrs.get_yaw() >= 0.0f && ahrs.get_yaw() < radians(90)) {
|
||||||
turn_state = 0;
|
turn_state = 0;
|
||||||
} else if (ahrs.yaw > radians(90)) {
|
} else if (ahrs.get_yaw() > radians(90)) {
|
||||||
turn_state = 1;
|
turn_state = 1;
|
||||||
} else if (ahrs.yaw < -radians(90)) {
|
} else if (ahrs.get_yaw() < -radians(90)) {
|
||||||
turn_state = 2;
|
turn_state = 2;
|
||||||
} else {
|
} else {
|
||||||
turn_state = 3;
|
turn_state = 3;
|
||||||
|
|
Loading…
Reference in New Issue