Tracker: compile warnings: float to double. print statements require doubles

This commit is contained in:
Tom Pittenger 2015-05-02 23:01:37 -07:00 committed by Andrew Tridgell
parent 928a5e0766
commit 1020be9d9f
2 changed files with 2 additions and 2 deletions

View File

@ -375,7 +375,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
// send at a much lower rate during parameter sends
if (_queued_parameter != NULL) {
rate *= 0.25;
rate *= 0.25f;
}
if (rate <= 0) {

View File

@ -234,7 +234,7 @@ static void update_yaw_position_servo(float yaw)
(int)slew_dir, (int)new_slew_dir,
(long)angle_err,
(long)channel_yaw.servo_out,
degrees(ahrs.get_gyro().z));
(double)degrees(ahrs.get_gyro().z));
}
slew_dir = new_slew_dir;