mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: compiler warnings - float to float compare and bool cast
This commit is contained in:
parent
113961b66e
commit
0aa0380db8
|
@ -286,10 +286,10 @@ uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
|||
}
|
||||
|
||||
uint8_t mag_mask = packet.param1;
|
||||
bool retry = packet.param2;
|
||||
bool autosave = packet.param3;
|
||||
bool retry = !is_zero(packet.param2);
|
||||
bool autosave = !is_zero(packet.param3);
|
||||
float delay = packet.param4;
|
||||
bool autoreboot = packet.param5;
|
||||
bool autoreboot = !is_zero(packet.param5);
|
||||
|
||||
if (mag_mask == 0) { // 0 means all
|
||||
if (!start_calibration_all(retry, autosave, delay, autoreboot)) {
|
||||
|
|
|
@ -151,7 +151,7 @@ void CompassCalibrator::update(bool &failure) {
|
|||
|
||||
if(_status == COMPASS_CAL_RUNNING_STEP_ONE) {
|
||||
if (_fit_step >= 10) {
|
||||
if(_fitness == _initial_fitness || isnan(_fitness)) { //if true, means that fitness is diverging instead of converging
|
||||
if(is_equal(_fitness,_initial_fitness) || isnan(_fitness)) { //if true, means that fitness is diverging instead of converging
|
||||
set_status(COMPASS_CAL_FAILED);
|
||||
failure = true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue