Camera: fix compile warnings re float constants

This commit is contained in:
Tom Pittenger 2015-04-24 12:27:55 +09:00 committed by Randy Mackay
parent 0926cf17dd
commit c1d4992dac
2 changed files with 3 additions and 3 deletions

View File

@ -224,7 +224,7 @@ void AP_Camera::send_feedback(mavlink_channel_t chan, AP_GPS &gps, const AP_AHRS
current_loc.lat, current_loc.lng, current_loc.lat, current_loc.lng,
altitude/100.0f, altitude_rel/100.0f, altitude/100.0f, altitude_rel/100.0f,
ahrs.roll_sensor/100.0f, ahrs.pitch_sensor/100.0f, ahrs.yaw_sensor/100.0f, ahrs.roll_sensor/100.0f, ahrs.pitch_sensor/100.0f, ahrs.yaw_sensor/100.0f,
0.0,CAMERA_FEEDBACK_PHOTO); 0.0f,CAMERA_FEEDBACK_PHOTO);
} }
@ -252,4 +252,4 @@ bool AP_Camera::update_location(const struct Location &loc)
} }
_last_location = loc; _last_location = loc;
return true; return true;
} }

View File

@ -81,4 +81,4 @@ private:
}; };
#endif /* AP_CAMERA_H */ #endif /* AP_CAMERA_H */