Skip to content

AP_Common: Location: allow retrieval of Vector3p from vector-from-origin #27256

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 17 additions & 2 deletions libraries/AP_Common/Location.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,8 @@ bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const
#if AP_AHRS_ENABLED
// converts location to a vector from origin; if this method returns
// false then vec_ne is unmodified
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
template<typename T>
bool Location::get_vector_xy_from_origin_NE(T &vec_ne) const
{
Location ekf_origin;
if (!AP::ahrs().get_origin(ekf_origin)) {
Expand All @@ -235,9 +236,16 @@ bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
return true;
}

// define for float and position vectors
template bool Location::get_vector_xy_from_origin_NE<Vector2f>(Vector2f &vec_ne) const;
#if HAL_WITH_POSTYPE_DOUBLE
template bool Location::get_vector_xy_from_origin_NE<Vector2p>(Vector2p &vec_ne) const;
#endif

// converts location to a vector from origin; if this method returns
// false then vec_neu is unmodified
bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
template<typename T>
bool Location::get_vector_from_origin_NEU(T &vec_neu) const
{
// convert altitude
int32_t alt_above_origin_cm = 0;
Expand All @@ -254,6 +262,13 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const

return true;
}

// define for float and position vectors
template bool Location::get_vector_from_origin_NEU<Vector3f>(Vector3f &vec_neu) const;
#if HAL_WITH_POSTYPE_DOUBLE
template bool Location::get_vector_from_origin_NEU<Vector3p>(Vector3p &vec_neu) const;
#endif

#endif // AP_AHRS_ENABLED

// return horizontal distance in meters between two locations
Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_Common/Location.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,12 @@ class Location
// happen if the EKF origin has not been set yet x, y and z are in
// centimetres. If this method returns false then vec_ne is
// unmodified.
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const WARN_IF_UNUSED;
template<typename T>
bool get_vector_xy_from_origin_NE(T &vec_ne) const WARN_IF_UNUSED;
// converts location to a vector from origin; if this method returns
// false then vec_neu is unmodified
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const WARN_IF_UNUSED;
template<typename T>
bool get_vector_from_origin_NEU(T &vec_neu) const WARN_IF_UNUSED;

// return horizontal distance in meters between two locations
ftype get_distance(const Location &loc2) const;
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/AP_HAL_Boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -381,4 +381,8 @@
#error "HAL_GPIO_LED_OFF must not be defined, it is implicitly !HAL_GPIO_LED_ON"
#endif

#ifndef HAL_WITH_POSTYPE_DOUBLE
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
#endif

#define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON)
4 changes: 0 additions & 4 deletions libraries/AP_Math/control.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,6 @@
#include "vector2.h"
#include "vector3.h"

#ifndef HAL_WITH_POSTYPE_DOUBLE
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
#endif

#if HAL_WITH_POSTYPE_DOUBLE
typedef double postype_t;
typedef Vector2d Vector2p;
Expand Down
Loading