ardupilot/libraries/AP_Math/location.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

62 lines
1.6 KiB
C++
Raw Permalink Normal View History

/*
* location.cpp
* Copyright (C) Andrew Tridgell 2011
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* this module deals with calculations involving locations
*/
#include <stdlib.h>
#include "AP_Math.h"
#include "location.h"
// return bearing in centi-degrees between two positions
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination)
{
float bearing = atan2f(destination.y-origin.y, destination.x-origin.x) * DEGX100;
if (bearing < 0) {
bearing += 36000.0f;
}
return bearing;
}
2016-06-01 18:43:01 -03:00
// return true when lat and lng are within range
bool check_lat(float lat)
{
return fabsf(lat) <= 90;
}
bool check_lng(float lng)
{
return fabsf(lng) <= 180;
}
bool check_lat(int32_t lat)
{
return labs(lat) <= 90*1e7;
}
bool check_lng(int32_t lng)
{
return labs(lng) <= 180*1e7;
}
2016-06-01 18:43:01 -03:00
bool check_latlng(float lat, float lng)
{
return check_lat(lat) && check_lng(lng);
2016-06-01 18:43:01 -03:00
}
bool check_latlng(int32_t lat, int32_t lng)
{
return check_lat(lat) && check_lng(lng);
2016-06-01 18:43:01 -03:00
}
2019-04-08 10:51:24 -03:00