forked from Archive/PX4-Autopilot
Prevent some warnings for lat/lon double conversions
This commit is contained in:
parent
32c7aea2a6
commit
effa62937f
|
@ -513,8 +513,8 @@ __EXPORT bool inside_geofence(const struct vehicle_global_position_s *vehicle, c
|
|||
|
||||
unsigned int i, j, vertices = fence->count;
|
||||
bool c = false;
|
||||
double lat = vehicle->lat / 1e7;
|
||||
double lon = vehicle->lon / 1e7;
|
||||
double lat = vehicle->lat / 1e7d;
|
||||
double lon = vehicle->lon / 1e7d;
|
||||
|
||||
// skip vertex 0 (return point)
|
||||
for (i = 0, j = vertices - 1; i < vertices; j = i++)
|
||||
|
|
|
@ -416,8 +416,8 @@ l_global_position_setpoint(const struct listener *l)
|
|||
if (gcs_link)
|
||||
mavlink_msg_global_position_setpoint_int_send(MAVLINK_COMM_0,
|
||||
coordinate_frame,
|
||||
(int32_t)(triplet.current.lat * 1e7f),
|
||||
(int32_t)(triplet.current.lon * 1e7f),
|
||||
(int32_t)(triplet.current.lat * 1e7d),
|
||||
(int32_t)(triplet.current.lon * 1e7d),
|
||||
(int32_t)(triplet.current.altitude * 1e3f),
|
||||
(int16_t)(triplet.current.yaw * M_RAD_TO_DEG_F * 1e2f));
|
||||
}
|
||||
|
|
|
@ -723,7 +723,7 @@ Navigator::status()
|
|||
{
|
||||
warnx("Global position is %svalid", _global_pos.valid ? "" : "in");
|
||||
if (_global_pos.valid) {
|
||||
warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7, _global_pos.lat / 1e7);
|
||||
warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7d, _global_pos.lat / 1e7d);
|
||||
warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
|
||||
(double)_global_pos.alt, (double)_global_pos.relative_alt);
|
||||
warnx("Ground velocity in m/s, x %5.5f, y %5.5f, z %5.5f",
|
||||
|
@ -947,8 +947,8 @@ Navigator::start_loiter()
|
|||
_mission_item_triplet.current_valid = true;
|
||||
_mission_item_triplet.next_valid = false;
|
||||
|
||||
_mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7;
|
||||
_mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7;
|
||||
_mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d;
|
||||
_mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d;
|
||||
_mission_item_triplet.current.yaw = 0.0f;
|
||||
|
||||
get_loiter_item(&_mission_item_triplet.current);
|
||||
|
@ -1162,11 +1162,11 @@ Navigator::mission_item_reached()
|
|||
|
||||
// if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
|
||||
dist = get_distance_to_point_global_wgs84(_mission_item_triplet.current.lat, _mission_item_triplet.current.lon, _mission_item_triplet.current.altitude,
|
||||
(double)_global_pos.lat / 1e7, (double)_global_pos.lon / 1e7, _global_pos.alt,
|
||||
(double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt,
|
||||
&dist_xy, &dist_z);
|
||||
|
||||
// warnx("1 lat: %2.2f, lon: %2.2f, alt: %2.2f", _mission_item_triplet.current.lat, _mission_item_triplet.current.lon, _mission_item_triplet.current.altitude);
|
||||
// warnx("2 lat: %2.2f, lon: %2.2f, alt: %2.2f", (double)_global_pos.lat / 1e7, (double)_global_pos.lon / 1e7, _global_pos.alt);
|
||||
// warnx("2 lat: %2.2f, lon: %2.2f, alt: %2.2f", (double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt);
|
||||
|
||||
// warnx("Dist: %4.4f", dist);
|
||||
|
||||
|
|
|
@ -614,8 +614,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
if (local_pos.xy_global) {
|
||||
double est_lat, est_lon;
|
||||
map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
|
||||
global_pos.lat = (int32_t)(est_lat * 1e7);
|
||||
global_pos.lon = (int32_t)(est_lon * 1e7);
|
||||
global_pos.lat = (int32_t)(est_lat * 1e7d);
|
||||
global_pos.lon = (int32_t)(est_lon * 1e7d);
|
||||
global_pos.time_gps_usec = gps.time_gps_usec;
|
||||
}
|
||||
|
||||
|
|
|
@ -1153,8 +1153,8 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
orb_copy(ORB_ID(mission_item_triplet), subs.triplet_sub, &buf.triplet);
|
||||
log_msg.msg_type = LOG_GPSP_MSG;
|
||||
log_msg.body.log_GPSP.altitude_is_relative = buf.triplet.current.altitude_is_relative;
|
||||
log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7);
|
||||
log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7);
|
||||
log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
|
||||
log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
|
||||
log_msg.body.log_GPSP.altitude = buf.triplet.current.altitude;
|
||||
log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw;
|
||||
log_msg.body.log_GPSP.nav_cmd = buf.triplet.current.nav_cmd;
|
||||
|
|
Loading…
Reference in New Issue