Skip to content

Commit 4450731

Browse files
committed
AP_Common: Location: allow retrieval of Vector3p from vector-from-origin
1 parent f0409f6 commit 4450731

File tree

2 files changed

+21
-4
lines changed

2 files changed

+21
-4
lines changed

libraries/AP_Common/Location.cpp

+17-2
Original file line numberDiff line numberDiff line change
@@ -224,7 +224,8 @@ bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const
224224
#if AP_AHRS_ENABLED
225225
// converts location to a vector from origin; if this method returns
226226
// false then vec_ne is unmodified
227-
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
227+
template<typename T>
228+
bool Location::get_vector_xy_from_origin_NE(T &vec_ne) const
228229
{
229230
Location ekf_origin;
230231
if (!AP::ahrs().get_origin(ekf_origin)) {
@@ -235,9 +236,16 @@ bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
235236
return true;
236237
}
237238

239+
// define for float and position vectors
240+
template bool Location::get_vector_xy_from_origin_NE<Vector2f>(Vector2f &vec_ne) const;
241+
#if HAL_WITH_POSTYPE_DOUBLE
242+
template bool Location::get_vector_xy_from_origin_NE<Vector2p>(Vector2p &vec_ne) const;
243+
#endif
244+
238245
// converts location to a vector from origin; if this method returns
239246
// false then vec_neu is unmodified
240-
bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
247+
template<typename T>
248+
bool Location::get_vector_from_origin_NEU(T &vec_neu) const
241249
{
242250
// convert altitude
243251
int32_t alt_above_origin_cm = 0;
@@ -254,6 +262,13 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
254262

255263
return true;
256264
}
265+
266+
// define for float and position vectors
267+
template bool Location::get_vector_from_origin_NEU<Vector3f>(Vector3f &vec_neu) const;
268+
#if HAL_WITH_POSTYPE_DOUBLE
269+
template bool Location::get_vector_from_origin_NEU<Vector3p>(Vector3p &vec_neu) const;
270+
#endif
271+
257272
#endif // AP_AHRS_ENABLED
258273

259274
// return horizontal distance in meters between two locations

libraries/AP_Common/Location.h

+4-2
Original file line numberDiff line numberDiff line change
@@ -60,10 +60,12 @@ class Location
6060
// happen if the EKF origin has not been set yet x, y and z are in
6161
// centimetres. If this method returns false then vec_ne is
6262
// unmodified.
63-
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const WARN_IF_UNUSED;
63+
template<typename T>
64+
bool get_vector_xy_from_origin_NE(T &vec_ne) const WARN_IF_UNUSED;
6465
// converts location to a vector from origin; if this method returns
6566
// false then vec_neu is unmodified
66-
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const WARN_IF_UNUSED;
67+
template<typename T>
68+
bool get_vector_from_origin_NEU(T &vec_neu) const WARN_IF_UNUSED;
6769

6870
// return horizontal distance in meters between two locations
6971
ftype get_distance(const Location &loc2) const;

0 commit comments

Comments
 (0)