mirror of https://github.com/ArduPilot/ardupilot
AP_Common: add initialised() method to Location
Sometimes code paths are crossed when they shouldn't be. This method can help in the short term if a codepath is calling methods on a Location when it is not initialised, but generally a vehicle should be calling position_ok() and other methods rather than this one.
This commit is contained in:
parent
e3da6d69d5
commit
4e5842a150
|
@ -103,7 +103,7 @@ Location::AltFrame Location::get_alt_frame() const
|
||||||
bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
|
bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
|
||||||
{
|
{
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
if (lat == 0 && lng == 0) {
|
if (!initialised()) {
|
||||||
AP_HAL::panic("Should not be called on invalid location");
|
AP_HAL::panic("Should not be called on invalid location");
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -112,6 +112,8 @@ public:
|
||||||
*/
|
*/
|
||||||
float line_path_proportion(const Location &point1, const Location &point2) const;
|
float line_path_proportion(const Location &point1, const Location &point2) const;
|
||||||
|
|
||||||
|
bool initialised() const { return (lat !=0 || lng != 0); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static AP_Terrain *_terrain;
|
static AP_Terrain *_terrain;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue