AP_Beacon_Marvelmind.h 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  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. /*
  14. Original C Code by Marvelmind (https://github.com/MarvelmindRobotics/marvelmind.c)
  15. Adapted into Ardupilot by Karthik Desai, Amilcar Lucas
  16. April 2017
  17. */
  18. #pragma once
  19. #include "AP_Beacon_Backend.h"
  20. #define AP_BEACON_MARVELMIND_BUF_SIZE 255
  21. class AP_Beacon_Marvelmind : public AP_Beacon_Backend
  22. {
  23. public:
  24. // constructor
  25. AP_Beacon_Marvelmind(AP_Beacon &frontend, AP_SerialManager &serial_manager);
  26. // return true if sensor is basically healthy (we are receiving data)
  27. bool healthy() override;
  28. // update
  29. void update() override;
  30. private:
  31. // Variables for Marvelmind
  32. struct PositionValue
  33. {
  34. uint8_t address;
  35. uint32_t timestamp;
  36. int32_t x__mm, y__mm, z__mm;
  37. bool high_resolution;
  38. };
  39. struct StationaryBeaconPosition
  40. {
  41. uint8_t address;
  42. int32_t x__mm, y__mm, z__mm;
  43. bool high_resolution;
  44. float distance__m; // Distance between beacon and hedge
  45. };
  46. struct StationaryBeaconsPositions
  47. {
  48. uint8_t num_beacons;
  49. StationaryBeaconPosition beacons[AP_BEACON_MAX_BEACONS];
  50. bool updated;
  51. };
  52. struct MarvelmindHedge
  53. {
  54. StationaryBeaconsPositions positions_beacons;
  55. PositionValue cur_position;
  56. bool _have_new_values;
  57. };
  58. enum {
  59. RECV_HDR,
  60. RECV_DGRAM
  61. } parse_state; // current state of receive data
  62. MarvelmindHedge hedge;
  63. uint8_t input_buffer[AP_BEACON_MARVELMIND_BUF_SIZE];
  64. uint16_t num_bytes_in_block_received;
  65. uint16_t data_id;
  66. StationaryBeaconPosition* get_or_alloc_beacon(uint8_t address);
  67. void process_beacons_positions_datagram();
  68. void process_beacons_positions_highres_datagram();
  69. void process_position_highres_datagram();
  70. void process_position_datagram();
  71. void process_beacons_distances_datagram();
  72. void set_stationary_beacons_positions();
  73. void order_stationary_beacons();
  74. int8_t find_beacon_instance(uint8_t address) const;
  75. // Variables for Ardupilot
  76. AP_HAL::UARTDriver *uart;
  77. uint32_t last_update_ms;
  78. // cache the vehicle position in NED coordinates [m]
  79. Vector3f vehicle_position_NED__m;
  80. bool vehicle_position_initialized;
  81. // cache the beacon positions in NED coordinates [m]
  82. Vector3f beacon_position_NED__m[AP_BEACON_MAX_BEACONS];
  83. bool beacon_position_initialized;
  84. };