aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-04-25 14:47:37 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-04-25 14:47:37 +0200
commitaab64af8844e03b04f5616c1beecf18c9f6a7d81 (patch)
tree3604273182a15e20183b41705f23fe02e2b8a1bd
parent241a99fc28992694f807595ce6bb48f460c9a28a (diff)
downloadpx4-firmware-aab64af8844e03b04f5616c1beecf18c9f6a7d81.tar.gz
px4-firmware-aab64af8844e03b04f5616c1beecf18c9f6a7d81.tar.bz2
px4-firmware-aab64af8844e03b04f5616c1beecf18c9f6a7d81.zip
geo: map projection: safer initialization, only accept init from navigator, return int instead of bool
-rw-r--r--src/lib/geo/geo.c41
-rw-r--r--src/lib/geo/geo.h16
2 files changed, 32 insertions, 25 deletions
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index a2117ecd0..6cbf74e46 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -55,7 +55,7 @@
* formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html
*/
-static struct map_projection_reference_s mp_ref;
+static struct map_projection_reference_s mp_ref = {0};
__EXPORT bool map_projection_initialized()
{
@@ -67,34 +67,41 @@ __EXPORT uint64_t map_projection_timestamp()
return mp_ref.timestamp;
}
-__EXPORT void map_projection_init(double lat_0, double lon_0, uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+__EXPORT int map_projection_init(double lat_0, double lon_0, uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
{
- mp_ref.lat = lat_0 / 180.0 * M_PI;
- mp_ref.lon = lon_0 / 180.0 * M_PI;
+ if (strcmp("navigator", getprogname() == 0)) {
- mp_ref.sin_lat = sin(mp_ref.lat);
- mp_ref.cos_lat = cos(mp_ref.lat);
+ mp_ref.lat = lat_0 / 180.0 * M_PI;
+ mp_ref.lon = lon_0 / 180.0 * M_PI;
- mp_ref.timestamp = timestamp;
- mp_ref.init_done = true;
+ mp_ref.sin_lat = sin(mp_ref.lat);
+ mp_ref.cos_lat = cos(mp_ref.lat);
+
+ mp_ref.timestamp = timestamp;
+ mp_ref.init_done = true;
+
+ return 0;
+ } else {
+ return -1;
+ }
}
-__EXPORT bool map_projection_reference(double *ref_lat, double *ref_lon)
+__EXPORT int map_projection_reference(double *ref_lat, double *ref_lon)
{
if (!map_projection_initialized()) {
- return false;
+ return -1;
}
*ref_lat = mp_ref.lat;
*ref_lon = mp_ref.lon;
- return true;
+ return 0;
}
-__EXPORT bool map_projection_project(double lat, double lon, float *x, float *y)
+__EXPORT int map_projection_project(double lat, double lon, float *x, float *y)
{
if (!map_projection_initialized()) {
- return false;
+ return -1;
}
double lat_rad = lat / 180.0 * M_PI;
@@ -110,13 +117,13 @@ __EXPORT bool map_projection_project(double lat, double lon, float *x, float *y)
*x = k * (mp_ref.cos_lat * sin_lat - mp_ref.sin_lat * cos_lat * cos_d_lon) * CONSTANTS_RADIUS_OF_EARTH;
*y = k * cos_lat * sin(lon_rad - mp_ref.lon) * CONSTANTS_RADIUS_OF_EARTH;
- return true;
+ return 0;
}
-__EXPORT bool map_projection_reproject(float x, float y, double *lat, double *lon)
+__EXPORT int map_projection_reproject(float x, float y, double *lat, double *lon)
{
if (!map_projection_initialized()) {
- return false;
+ return -1;
}
float x_rad = x / CONSTANTS_RADIUS_OF_EARTH;
@@ -140,7 +147,7 @@ __EXPORT bool map_projection_reproject(float x, float y, double *lat, double *lo
*lat = lat_rad * 180.0 / M_PI;
*lon = lon_rad * 180.0 / M_PI;
- return true;
+ return 0;
}
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index b5e659685..b0f8d6bc4 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -77,7 +77,7 @@ struct map_projection_reference_s {
/**
* Initializes the map transformation.
- * @return true if map_projection_init was called before, false else
+ * @return true if map was initialized before, false else
*/
__EXPORT bool map_projection_initialized();
@@ -90,9 +90,9 @@ __EXPORT uint64_t map_projection_timestamp();
/**
* Writes the reference values to ref_lat and ref_lon
- * @return true if map_projection_init was called before, false else
+ * @return 0 if map_projection_init was called before, -1 else
*/
-__EXPORT bool map_projection_reference(double *ref_lat, double *ref_lon);
+__EXPORT int map_projection_reference(double *ref_lat, double *ref_lon);
/**
* Initializes the map transformation.
@@ -101,7 +101,7 @@ __EXPORT bool map_projection_reference(double *ref_lat, double *ref_lon);
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
-__EXPORT void map_projection_init(double lat_0, double lon_0, uint64_t timestamp);
+__EXPORT int map_projection_init(double lat_0, double lon_0, uint64_t timestamp);
/**
* Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
@@ -109,9 +109,9 @@ __EXPORT void map_projection_init(double lat_0, double lon_0, uint64_t timestamp
* @param y east
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
- * @return true if map_projection_init was called before, false else
+ * @return 0 if map_projection_init was called before, -1 else
*/
-__EXPORT bool map_projection_project(double lat, double lon, float *x, float *y);
+__EXPORT int map_projection_project(double lat, double lon, float *x, float *y);
/**
* Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
@@ -120,9 +120,9 @@ __EXPORT bool map_projection_project(double lat, double lon, float *x, float *y)
* @param y east
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
- * @return true if map_projection_init was called before, false else
+ * @return 0 if map_projection_init was called before, -1 else
*/
-__EXPORT bool map_projection_reproject(float x, float y, double *lat, double *lon);
+__EXPORT int map_projection_reproject(float x, float y, double *lat, double *lon);
/**
* Returns the distance to the next waypoint in meters.