@@ -224,7 +224,8 @@ bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const
224
224
#if AP_AHRS_ENABLED
225
225
// converts location to a vector from origin; if this method returns
226
226
// 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
228
229
{
229
230
Location ekf_origin;
230
231
if (!AP::ahrs ().get_origin (ekf_origin)) {
@@ -235,9 +236,16 @@ bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
235
236
return true ;
236
237
}
237
238
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
+
238
245
// converts location to a vector from origin; if this method returns
239
246
// 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
241
249
{
242
250
// convert altitude
243
251
int32_t alt_above_origin_cm = 0 ;
@@ -254,6 +262,13 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
254
262
255
263
return true ;
256
264
}
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
+
257
272
#endif // AP_AHRS_ENABLED
258
273
259
274
// return horizontal distance in meters between two locations
0 commit comments