aboutsummaryrefslogtreecommitdiff
path: root/src/modules/position_estimator_inav
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-03-17 22:20:41 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-03-17 22:20:41 +0400
commit3d5f52678fa093a248d824828fcafe12ac2f8f15 (patch)
treeb95401fd45205dac6c8311de68ad0cdb101364a2 /src/modules/position_estimator_inav
parent2284a7e985b174dab4b3c1666d9f019d9479a230 (diff)
downloadpx4-firmware-3d5f52678fa093a248d824828fcafe12ac2f8f15.tar.gz
px4-firmware-3d5f52678fa093a248d824828fcafe12ac2f8f15.tar.bz2
px4-firmware-3d5f52678fa093a248d824828fcafe12ac2f8f15.zip
Use updated map_projection_XXX functions in apps
Diffstat (limited to 'src/modules/position_estimator_inav')
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c8
1 files changed, 5 insertions, 3 deletions
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index a14354138..eddf6e94e 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -206,6 +206,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
bool ref_inited = false;
hrt_abstime ref_init_start = 0;
const hrt_abstime ref_init_delay = 1000000; // wait for 1s after 3D fix
+ struct map_projection_reference_s ref;
+ memset(&ref, 0, sizeof(ref));
uint16_t accel_updates = 0;
uint16_t baro_updates = 0;
@@ -560,7 +562,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.ref_timestamp = t;
/* initialize projection */
- map_projection_init(lat, lon);
+ map_projection_init(&ref, lat, lon);
warnx("init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
mavlink_log_info(mavlink_fd, "[inav] init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
}
@@ -569,7 +571,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (ref_inited) {
/* project GPS lat lon to plane */
float gps_proj[2];
- map_projection_project(gps.lat * 1e-7, gps.lon * 1e-7, &(gps_proj[0]), &(gps_proj[1]));
+ map_projection_project(&ref, gps.lat * 1e-7, gps.lon * 1e-7, &(gps_proj[0]), &(gps_proj[1]));
/* calculate correction for position */
corr_gps[0][0] = gps_proj[0] - x_est[0];
corr_gps[1][0] = gps_proj[1] - y_est[0];
@@ -836,7 +838,7 @@ 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);
+ map_projection_reproject(&ref, local_pos.x, local_pos.y, &est_lat, &est_lon);
global_pos.lat = est_lat;
global_pos.lon = est_lon;
global_pos.time_gps_usec = gps.time_gps_usec;