GCS_MAVLink: correct output of AHRS2 mavlink message
The || here was causing short-circuiting
This commit is contained in:
parent
317181922c
commit
7480a2a00b
@ -437,7 +437,8 @@ void GCS_MAVLINK::send_ahrs2()
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
Vector3f euler;
|
||||
struct Location loc {};
|
||||
if (ahrs.get_secondary_attitude(euler) ||
|
||||
// we want one or both of these, use | to avoid short-circuiting:
|
||||
if (ahrs.get_secondary_attitude(euler) |
|
||||
ahrs.get_secondary_position(loc)) {
|
||||
mavlink_msg_ahrs2_send(chan,
|
||||
euler.x,
|
||||
|
Loading…
Reference in New Issue
Block a user