APMrover2: compiler warnings: apply is_zero(float) or is_equal(float)

This commit is contained in:
Tom Pittenger 2015-05-02 02:14:03 -07:00 committed by Andrew Tridgell
parent 9b53961a7d
commit 8ddd97c06f
1 changed files with 9 additions and 9 deletions

View File

@ -869,7 +869,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1) {
if (AP_Math::is_equal(packet.param1,1.0f)) {
ins.init_gyro();
if (ins.gyro_calibrated_ok_all()) {
ahrs.reset_gyro_drift();
@ -877,13 +877,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else {
result = MAV_RESULT_FAILED;
}
} else if (packet.param3 == 1) {
} else if (AP_Math::is_equal(packet.param3,1.0f)) {
init_barometer();
result = MAV_RESULT_ACCEPTED;
} else if (packet.param4 == 1) {
} else if (AP_Math::is_equal(packet.param4,1.0f)) {
trim_radio();
result = MAV_RESULT_ACCEPTED;
} else if (packet.param5 == 1) {
} else if (AP_Math::is_equal(packet.param5,1.0f)) {
float trim_roll, trim_pitch;
AP_InertialSensor_UserInteract_MAVLink interact(this);
if (g.skip_gyro_cal) {
@ -905,12 +905,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
if (packet.param1 == 2) {
if (AP_Math::is_equal(packet.param1,2.0f)) {
// save first compass's offsets
compass.set_and_save_offsets(0, packet.param2, packet.param3, packet.param4);
result = MAV_RESULT_ACCEPTED;
}
if (packet.param1 == 5) {
if (AP_Math::is_equal(packet.param1,5.0f)) {
// save secondary compass's offsets
compass.set_and_save_offsets(1, packet.param2, packet.param3, packet.param4);
result = MAV_RESULT_ACCEPTED;
@ -967,15 +967,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (packet.param1 == 1 || packet.param1 == 3) {
if (AP_Math::is_equal(packet.param1,1.0f) || AP_Math::is_equal(packet.param1,3.0f)) {
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(packet.param1 == 3);
hal.scheduler->reboot(AP_Math::is_equal(packet.param1,3.0f));
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
if (packet.param1 == 1) {
if (AP_Math::is_equal(packet.param1,1.0f)) {
gcs[chan-MAVLINK_COMM_0].send_autopilot_version();
result = MAV_RESULT_ACCEPTED;
}