AP_Beacon_SITL.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114
  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_HAL/AP_HAL.h>
  14. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  15. #include "AP_Beacon_SITL.h"
  16. #include <stdio.h>
  17. extern const AP_HAL::HAL& hal;
  18. #define NUM_BEACONS 4
  19. /*
  20. * Define a rectangular pattern of beacons with the pattern centroid located at the beacon origin as defined by the following params:
  21. *
  22. * BCN_ALT - Height above the WGS-84 geoid (m)
  23. * BCN_LATITUDE - WGS-84 latitude (deg)
  24. * BCN_LONGITUDE - WGS-84 longitude (deg)
  25. *
  26. * The spacing between beacons in the North/South and East/West directions is defined by the following parameters:
  27. */
  28. #define BEACON_SPACING_NORTH 10.0
  29. #define BEACON_SPACING_EAST 20.0
  30. // The centroid of the pattern can be moved using using the following parameters:
  31. #define ORIGIN_OFFSET_NORTH 2.5 // shifts beacon pattern centroid North (m)
  32. #define ORIGIN_OFFSET_EAST 5.0 // shifts beacon pattern centroid East (m)
  33. // constructor
  34. AP_Beacon_SITL::AP_Beacon_SITL(AP_Beacon &frontend) :
  35. AP_Beacon_Backend(frontend),
  36. sitl(AP::sitl())
  37. {
  38. }
  39. // return true if sensor is basically healthy (we are receiving data)
  40. bool AP_Beacon_SITL::healthy()
  41. {
  42. // healthy if we have parsed a message within the past 300ms
  43. return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);
  44. }
  45. // update the state of the sensor
  46. void AP_Beacon_SITL::update(void)
  47. {
  48. uint32_t now = AP_HAL::millis();
  49. if (now - last_update_ms < 10) {
  50. return;
  51. }
  52. uint8_t beacon_id = next_beacon;
  53. next_beacon = (next_beacon+1) % NUM_BEACONS;
  54. // truth location of the flight vehicle
  55. Location current_loc;
  56. current_loc.lat = sitl->state.latitude * 1.0e7f;
  57. current_loc.lng = sitl->state.longitude * 1.0e7f;
  58. current_loc.alt = sitl->state.altitude * 1.0e2;
  59. // where the beacon system origin is located
  60. Location beacon_origin;
  61. beacon_origin.lat = get_beacon_origin_lat() * 1.0e7f;
  62. beacon_origin.lng = get_beacon_origin_lon() * 1.0e7f;
  63. beacon_origin.alt = get_beacon_origin_alt() * 1.0e2;
  64. // position of each beacon
  65. Location beacon_loc = beacon_origin;
  66. switch (beacon_id) {
  67. case 0:
  68. // NE corner
  69. beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
  70. break;
  71. case 1:
  72. // SE corner
  73. beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
  74. break;
  75. case 2:
  76. // SW corner
  77. beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
  78. break;
  79. case 3:
  80. // NW corner
  81. beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
  82. break;
  83. }
  84. const Vector2f beac_diff = beacon_origin.get_distance_NE(beacon_loc);
  85. const Vector2f veh_diff = beacon_origin.get_distance_NE(current_loc);
  86. Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (current_loc.alt - beacon_origin.alt)*1.0e-2f);
  87. Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_origin.alt - beacon_loc.alt)*1.0e-2f);
  88. Vector3f beac_veh_offset = veh_pos3d - beac_pos3d;
  89. set_beacon_position(beacon_id, beac_pos3d);
  90. set_beacon_distance(beacon_id, beac_veh_offset.length());
  91. set_vehicle_position(veh_pos3d, 0.5f);
  92. last_update_ms = now;
  93. }
  94. #endif // CONFIG_HAL_BOARD