mirror of https://github.com/ArduPilot/ardupilot
APMrover2: Fix use of logical op instead of bitwise op
../../ArduCopter/GCS_Mavlink.cpp: In member function 'void Copter::send_extended_status1(mavlink_channel_t)': ../../ArduCopter/GCS_Mavlink.cpp:281:37: error: suggest parentheses around operand of '!' or change '&' to '&&' or '!' to '~' [-Werror=parentheses] uint32_t sensors_error_flags = !control_sensors_health & control_sensors_enabled & control_sensors_present; ^ compilation terminated due to -Wfatal-errors. cc1plus: all warnings being treated as errors Thanks to Ralph Campbell <ralphcampbell1@gmail.com> for the bug report.
This commit is contained in:
parent
0ad3b0421f
commit
b4a3e8a9c9
|
@ -209,7 +209,7 @@ void Rover::send_extended_status1(mavlink_channel_t chan)
|
|||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// give mask of error flags to Frsky_Telemetry
|
||||
uint32_t sensors_error_flags = !control_sensors_health & control_sensors_enabled & control_sensors_present;
|
||||
uint32_t sensors_error_flags = (~control_sensors_health) & control_sensors_enabled & control_sensors_present;
|
||||
frsky_telemetry.update_sensor_status_flags(sensors_error_flags);
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue