mirror of https://github.com/ArduPilot/ardupilot
AP_Common: move constructor to header to allow inlining
This commit is contained in:
parent
4773571525
commit
ed37ee821b
|
@ -9,12 +9,6 @@
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
|
||||||
/// constructors
|
|
||||||
Location::Location()
|
|
||||||
{
|
|
||||||
zero();
|
|
||||||
}
|
|
||||||
|
|
||||||
const Location definitely_zero{};
|
const Location definitely_zero{};
|
||||||
bool Location::is_zero(void) const
|
bool Location::is_zero(void) const
|
||||||
{
|
{
|
||||||
|
|
|
@ -28,7 +28,7 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
/// constructors
|
/// constructors
|
||||||
Location();
|
Location() { zero(); }
|
||||||
Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame);
|
Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame);
|
||||||
Location(const Vector3f &ekf_offset_neu, AltFrame frame);
|
Location(const Vector3f &ekf_offset_neu, AltFrame frame);
|
||||||
Location(const Vector3d &ekf_offset_neu, AltFrame frame);
|
Location(const Vector3d &ekf_offset_neu, AltFrame frame);
|
||||||
|
|
Loading…
Reference in New Issue