location.cpp 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667
  1. /*
  2. * location.cpp
  3. * Copyright (C) Andrew Tridgell 2011
  4. *
  5. * This file is free software: you can redistribute it and/or modify it
  6. * under the terms of the GNU General Public License as published by the
  7. * Free Software Foundation, either version 3 of the License, or
  8. * (at your option) any later version.
  9. *
  10. * This file is distributed in the hope that it will be useful, but
  11. * WITHOUT ANY WARRANTY; without even the implied warranty of
  12. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  13. * See the GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along
  16. * with this program. If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. /*
  19. * this module deals with calculations involving struct Location
  20. */
  21. #include <stdlib.h>
  22. #include "AP_Math.h"
  23. #include "location.h"
  24. // return horizontal distance between two positions in cm
  25. float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
  26. {
  27. return norm(destination.x-origin.x,destination.y-origin.y);
  28. }
  29. // return bearing in centi-degrees between two positions
  30. float get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
  31. {
  32. float bearing = atan2f(destination.y-origin.y, destination.x-origin.x) * DEGX100;
  33. if (bearing < 0) {
  34. bearing += 36000.0f;
  35. }
  36. return bearing;
  37. }
  38. // return true when lat and lng are within range
  39. bool check_lat(float lat)
  40. {
  41. return fabsf(lat) <= 90;
  42. }
  43. bool check_lng(float lng)
  44. {
  45. return fabsf(lng) <= 180;
  46. }
  47. bool check_lat(int32_t lat)
  48. {
  49. return labs(lat) <= 90*1e7;
  50. }
  51. bool check_lng(int32_t lng)
  52. {
  53. return labs(lng) <= 180*1e7;
  54. }
  55. bool check_latlng(float lat, float lng)
  56. {
  57. return check_lat(lat) && check_lng(lng);
  58. }
  59. bool check_latlng(int32_t lat, int32_t lng)
  60. {
  61. return check_lat(lat) && check_lng(lng);
  62. }