AP_Devo_Telem.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135
  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. DEVO Telemetry library
  15. */
  16. #define DEVOM_SYNC_BYTE 0xAA
  17. #define AP_SERIALMANAGER_DEVO_TELEM_BAUD 38400
  18. #define AP_SERIALMANAGER_DEVO_BUFSIZE_RX 0
  19. #define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
  20. #include "AP_Devo_Telem.h"
  21. #include <AP_AHRS/AP_AHRS.h>
  22. #include <AP_GPS/AP_GPS.h>
  23. #include <AP_BattMonitor/AP_BattMonitor.h>
  24. #include <GCS_MAVLink/GCS.h>
  25. extern const AP_HAL::HAL& hal;
  26. void AP_DEVO_Telem::init()
  27. {
  28. const AP_SerialManager& serial_manager = AP::serialmanager();
  29. // check for DEVO_DPort
  30. if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Devo_Telem, 0))) {
  31. _port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  32. // initialise uart
  33. _port->begin(AP_SERIALMANAGER_DEVO_TELEM_BAUD, AP_SERIALMANAGER_DEVO_BUFSIZE_RX, AP_SERIALMANAGER_DEVO_BUFSIZE_TX);
  34. hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_DEVO_Telem::tick, void));
  35. }
  36. }
  37. uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(float ddm)
  38. {
  39. int32_t deg = (int32_t)ddm;
  40. float mm = (ddm - deg) * 60.0f;
  41. mm = ((float)deg * 100.0f + mm) /100.0f;
  42. if ((mm < -180.0f) || (mm > 180.0f)) {
  43. mm = 0.0f;
  44. }
  45. return mm * 1.0e7f;
  46. }
  47. /*
  48. send_frames - sends updates down telemetry link
  49. should be called at 1hz
  50. */
  51. #define DEVO_SPEED_FACTOR 0.0194384f
  52. void AP_DEVO_Telem::send_frames()
  53. {
  54. // return immediately if not initialised
  55. if (_port == nullptr) {
  56. return;
  57. }
  58. struct PACKED {
  59. uint8_t header; ///< 0xAA for a valid packet
  60. int32_t lon;
  61. int32_t lat;
  62. int32_t alt;
  63. int16_t speed;
  64. int16_t temp;
  65. int16_t volt;
  66. uint8_t checksum8;
  67. } devoPacket{};
  68. devoPacket.header = DEVOM_SYNC_BYTE;
  69. const AP_AHRS &_ahrs = AP::ahrs();
  70. const AP_GPS &gps = AP::gps();
  71. Location loc;
  72. if (_ahrs.get_position(loc)) {
  73. devoPacket.lat = gpsDdToDmsFormat(loc.lat);
  74. devoPacket.lon = gpsDdToDmsFormat(loc.lng);
  75. devoPacket.speed = (int16_t)(gps.ground_speed() * DEVO_SPEED_FACTOR * 100.0f); // * 100 for cm
  76. /*
  77. Note that this isn't actually barometric altitude, it is the
  78. inertial nav estimate of altitude above home.
  79. */
  80. float alt;
  81. _ahrs.get_relative_position_D_home(alt);
  82. devoPacket.alt = alt * -100.0f; // coordinates was in NED, so it needs to change sign. Protocol requires in cm!
  83. }
  84. devoPacket.volt = roundf(AP::battery().voltage() * 10.0f);
  85. devoPacket.temp = gcs().custom_mode(); // Send mode as temperature
  86. // emit the packet to the port byte-by-byte, calculating checksum
  87. // as we go. Note we are stepping backwards through the structure
  88. // - presumably to get endianness correct on the entries!
  89. uint8_t *b = (uint8_t *)&devoPacket;
  90. for (uint8_t i = sizeof(devoPacket)-1; i !=0; i--) {
  91. _port->write(b, 1);
  92. devoPacket.checksum8 += *b++; // Add Checksum
  93. }
  94. _port->write(&devoPacket.checksum8, 1);
  95. }
  96. void AP_DEVO_Telem::tick(void)
  97. {
  98. uint32_t now = AP_HAL::millis();
  99. if (now - _last_frame_ms > 1000) {
  100. _last_frame_ms = now;
  101. send_frames();
  102. }
  103. }