@@ -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
0 commit comments