AP_GPS: add casts to consider literals as doubles

Since we pass -fsingle-precision-constant to the compiler, add casts to
make literals real doubles.
This commit is contained in:
Lucas De Marchi 2017-01-31 09:19:09 -08:00
parent a500aced3c
commit 747f15b514
5 changed files with 15 additions and 15 deletions

View File

@ -154,9 +154,9 @@ AP_GPS_ERB::_parse_gps(void)
case MSG_POS:
Debug("Message POS");
_last_pos_time = _buffer.pos.time;
state.location.lng = (int32_t)(_buffer.pos.longitude * 1e7);
state.location.lat = (int32_t)(_buffer.pos.latitude * 1e7);
state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 1e2);
state.location.lng = (int32_t)(_buffer.pos.longitude * (double)1e7);
state.location.lat = (int32_t)(_buffer.pos.latitude * (double)1e7);
state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100);
state.status = next_fix;
_new_position = true;
state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f;

View File

@ -294,9 +294,9 @@ AP_GPS_GSOF::process_message(void)
}
else if (output_type == 2) // position
{
state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a)) * 1e7);
state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a + 8)) * 1e7);
state.location.alt = (int32_t)(SwapDouble(gsof_msg.data, a + 16) * 1e2);
state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a)) * (double)1e7);
state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a + 8)) * (double)1e7);
state.location.alt = (int32_t)(SwapDouble(gsof_msg.data, a + 16) * 100);
state.last_gps_time_ms = state.time_week_ms;

View File

@ -196,9 +196,9 @@ AP_GPS_NOVA::process_message(void)
state.time_week_ms = (uint32_t) nova_msg.header.nova_headeru.tow;
state.last_gps_time_ms = state.time_week_ms;
state.location.lat = (int32_t) (bestposu.lat*1e7);
state.location.lng = (int32_t) (bestposu.lng*1e7);
state.location.alt = (int32_t) (bestposu.hgt*1e2);
state.location.lat = (int32_t) (bestposu.lat * (double)1e7);
state.location.lng = (int32_t) (bestposu.lng * (double)1e7);
state.location.alt = (int32_t) (bestposu.hgt * 100);
state.num_sats = bestposu.svsused;

View File

@ -236,9 +236,9 @@ AP_GPS_SBF::process_message(void)
// Update position state (don't use 2·10^10)
if (temp.Latitude > -200000) {
state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * 1e7);
state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * 1e7);
state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f );
state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7);
state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);
state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f);
}
if (temp.NrSV != 255) {

View File

@ -274,9 +274,9 @@ AP_GPS_SBP::_attempt_state_update()
// Update position state
state.location.lat = (int32_t) (pos_llh->lat*1e7);
state.location.lng = (int32_t) (pos_llh->lon*1e7);
state.location.alt = (int32_t) (pos_llh->height*1e2);
state.location.lat = (int32_t) (pos_llh->lat * (double)1e7);
state.location.lng = (int32_t) (pos_llh->lon * (double)1e7);
state.location.alt = (int32_t) (pos_llh->height * 100);
state.num_sats = pos_llh->n_sats;
if (pos_llh->flags == 0) {