AP_Beacon_Backend.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_Beacon_Backend.h"
  14. // debug
  15. #include <stdio.h>
  16. /*
  17. base class constructor.
  18. This incorporates initialisation as well.
  19. */
  20. AP_Beacon_Backend::AP_Beacon_Backend(AP_Beacon &frontend) :
  21. _frontend(frontend)
  22. {
  23. }
  24. // set vehicle position:
  25. // pos should be in the beacon's local frame in meters
  26. // accuracy_estimate is also in meters
  27. void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy_estimate)
  28. {
  29. _frontend.veh_pos_update_ms = AP_HAL::millis();
  30. _frontend.veh_pos_accuracy = accuracy_estimate;
  31. _frontend.veh_pos_ned = correct_for_orient_yaw(pos);
  32. }
  33. // set individual beacon distance in meters
  34. void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
  35. {
  36. // sanity check instance
  37. if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
  38. return;
  39. }
  40. // setup new beacon
  41. if (beacon_instance >= _frontend.num_beacons) {
  42. _frontend.num_beacons = beacon_instance+1;
  43. }
  44. _frontend.beacon_state[beacon_instance].distance_update_ms = AP_HAL::millis();
  45. _frontend.beacon_state[beacon_instance].distance = distance;
  46. _frontend.beacon_state[beacon_instance].healthy = true;
  47. }
  48. // configure beacon's position in meters from origin
  49. // pos should be in the beacon's local frame (meters)
  50. void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
  51. {
  52. // sanity check instance
  53. if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
  54. return;
  55. }
  56. // setup new beacon
  57. if (beacon_instance >= _frontend.num_beacons) {
  58. _frontend.num_beacons = beacon_instance+1;
  59. }
  60. // set position after correcting yaw
  61. _frontend.beacon_state[beacon_instance].position = correct_for_orient_yaw(pos);
  62. }
  63. // rotate vector (meters) to correct for beacon system yaw orientation
  64. Vector3f AP_Beacon_Backend::correct_for_orient_yaw(const Vector3f &vector)
  65. {
  66. // exit immediately if no correction
  67. if (_frontend.orient_yaw == 0) {
  68. return vector;
  69. }
  70. // check for change in parameter value and update constants
  71. if (orient_yaw_deg != _frontend.orient_yaw) {
  72. _frontend.orient_yaw = wrap_180(_frontend.orient_yaw.get());
  73. // calculate rotation constants
  74. orient_yaw_deg = _frontend.orient_yaw;
  75. orient_cos_yaw = cosf(radians(orient_yaw_deg));
  76. orient_sin_yaw = sinf(radians(orient_yaw_deg));
  77. }
  78. // rotate x,y by -orient_yaw
  79. Vector3f vec_rotated;
  80. vec_rotated.x = vector.x*orient_cos_yaw - vector.y*orient_sin_yaw;
  81. vec_rotated.y = vector.x*orient_sin_yaw + vector.y*orient_cos_yaw;
  82. vec_rotated.z = vector.z;
  83. return vec_rotated;
  84. }