Plane: avoid some float conversion warnings
This commit is contained in:
parent
baa0217bec
commit
3390224491
@ -126,8 +126,8 @@ static void stick_mix_channel(RC_Channel *channel, int16_t &servo_out)
|
||||
|
||||
ch_inf = (float)channel->radio_in - (float)channel->radio_trim;
|
||||
ch_inf = fabsf(ch_inf);
|
||||
ch_inf = min(ch_inf, 400.0);
|
||||
ch_inf = ((400.0 - ch_inf) / 400.0);
|
||||
ch_inf = min(ch_inf, 400.0f);
|
||||
ch_inf = ((400.0f - ch_inf) / 400.0f);
|
||||
servo_out *= ch_inf;
|
||||
servo_out += channel->pwm_to_angle();
|
||||
}
|
||||
@ -356,7 +356,7 @@ static void stabilize()
|
||||
*/
|
||||
if (channel_throttle->control_in == 0 &&
|
||||
relative_altitude_abs_cm() < 500 &&
|
||||
fabs(barometer.get_climb_rate()) < 0.5f &&
|
||||
fabsf(barometer.get_climb_rate()) < 0.5f &&
|
||||
gps.ground_speed() < 3) {
|
||||
// we are low, with no climb rate, and zero throttle, and very
|
||||
// low ground speed. Zero the attitude controller
|
||||
@ -747,8 +747,8 @@ static void set_servos(void)
|
||||
}
|
||||
|
||||
// directly set the radio_out values for elevon mode
|
||||
channel_roll->radio_out = elevon.trim1 + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0/ SERVO_MAX));
|
||||
channel_pitch->radio_out = elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0/ SERVO_MAX));
|
||||
channel_roll->radio_out = elevon.trim1 + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0f/ SERVO_MAX));
|
||||
channel_pitch->radio_out = elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0f/ SERVO_MAX));
|
||||
}
|
||||
|
||||
// push out the PWM values
|
||||
|
@ -277,7 +277,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
||||
current_loc.lat, // in 1E7 degrees
|
||||
current_loc.lng, // in 1E7 degrees
|
||||
gps.location().alt * 10UL, // millimeters above sea level
|
||||
relative_altitude() * 1.0e3, // millimeters above ground
|
||||
relative_altitude() * 1.0e3f, // millimeters above ground
|
||||
vel.x * 100, // X speed cm/s (+ve North)
|
||||
vel.y * 100, // Y speed cm/s (+ve East)
|
||||
vel.z * -100, // Z speed cm/s (+ve up)
|
||||
@ -384,12 +384,12 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
|
||||
mavlink_msg_raw_imu_send(
|
||||
chan,
|
||||
micros(),
|
||||
accel.x * 1000.0 / GRAVITY_MSS,
|
||||
accel.y * 1000.0 / GRAVITY_MSS,
|
||||
accel.z * 1000.0 / GRAVITY_MSS,
|
||||
gyro.x * 1000.0,
|
||||
gyro.y * 1000.0,
|
||||
gyro.z * 1000.0,
|
||||
accel.x * 1000.0f / GRAVITY_MSS,
|
||||
accel.y * 1000.0f / GRAVITY_MSS,
|
||||
accel.z * 1000.0f / GRAVITY_MSS,
|
||||
gyro.x * 1000.0f,
|
||||
gyro.y * 1000.0f,
|
||||
gyro.z * 1000.0f,
|
||||
mag.x,
|
||||
mag.y,
|
||||
mag.z);
|
||||
@ -826,7 +826,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
|
||||
// parameter sends
|
||||
if ((stream_num != STREAM_PARAMS) &&
|
||||
(waypoint_receiving || _queued_parameter != NULL)) {
|
||||
rate *= 0.25;
|
||||
rate *= 0.25f;
|
||||
}
|
||||
|
||||
if (rate <= 0) {
|
||||
@ -1299,8 +1299,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
|
||||
} else {
|
||||
Vector2l point;
|
||||
point.x = packet.lat*1.0e7;
|
||||
point.y = packet.lng*1.0e7;
|
||||
point.x = packet.lat*1.0e7f;
|
||||
point.y = packet.lng*1.0e7f;
|
||||
set_fence_point_with_index(point, packet.idx);
|
||||
}
|
||||
break;
|
||||
|
@ -393,8 +393,8 @@ static void Log_Write_Current()
|
||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
throttle_in : channel_throttle->control_in,
|
||||
battery_voltage : (int16_t)(battery.voltage() * 100.0),
|
||||
current_amps : (int16_t)(battery.current_amps() * 100.0),
|
||||
battery_voltage : (int16_t)(battery.voltage() * 100.0f),
|
||||
current_amps : (int16_t)(battery.current_amps() * 100.0f),
|
||||
board_voltage : (uint16_t)(hal.analogin->board_voltage()*1000),
|
||||
current_total : battery.current_total_mah()
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user