mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: compile warnings: float to double. print statements require doubles
This commit is contained in:
parent
928a5e0766
commit
1020be9d9f
@ -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) {
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user