AP_RCProtocol_IBUS.cpp 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. */
  16. #include "AP_RCProtocol_IBUS.h"
  17. // constructor
  18. AP_RCProtocol_IBUS::AP_RCProtocol_IBUS(AP_RCProtocol &_frontend) :
  19. AP_RCProtocol_Backend(_frontend)
  20. {}
  21. // decode a full IBUS frame
  22. bool AP_RCProtocol_IBUS::ibus_decode(const uint8_t frame[IBUS_FRAME_SIZE], uint16_t *values, bool *ibus_failsafe)
  23. {
  24. uint32_t chksum = 96;
  25. /* check frame boundary markers to avoid out-of-sync cases */
  26. if ((frame[0] != 0x20) || (frame[1] != 0x40)) {
  27. return false;
  28. }
  29. /* use the decoder matrix to extract channel data */
  30. for (uint8_t channel = 0, pick=2; channel < IBUS_INPUT_CHANNELS; channel++, pick+=2) {
  31. values[channel]=frame[pick]|(frame[pick+1] & 0x0F)<<8;
  32. chksum+=frame[pick]+frame[pick+1];
  33. }
  34. chksum += frame[IBUS_FRAME_SIZE-2]|frame[IBUS_FRAME_SIZE-1]<<8;
  35. if (chksum!=0xFFFF) {
  36. return false;
  37. }
  38. if ((frame[3]&0xF0) || (frame[9]&0xF0)) {
  39. *ibus_failsafe = true;
  40. } else {
  41. *ibus_failsafe = false;
  42. }
  43. return true;
  44. }
  45. /*
  46. process an IBUS input pulse of the given width
  47. */
  48. void AP_RCProtocol_IBUS::process_pulse(uint32_t w0, uint32_t w1)
  49. {
  50. uint8_t b;
  51. if (ss.process_pulse(w0, w1, b)) {
  52. _process_byte(ss.get_byte_timestamp_us(), b);
  53. }
  54. }
  55. // support byte input
  56. void AP_RCProtocol_IBUS::_process_byte(uint32_t timestamp_us, uint8_t b)
  57. {
  58. const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 2000U);
  59. byte_input.last_byte_us = timestamp_us;
  60. if (have_frame_gap) {
  61. // if we have a frame gap then this must be the start of a new
  62. // frame
  63. byte_input.ofs = 0;
  64. }
  65. if (b != 0x20 && byte_input.ofs == 0) {
  66. // definately not IBUS, missing header byte
  67. return;
  68. }
  69. if (byte_input.ofs == 0 && !have_frame_gap) {
  70. // must have a frame gap before the start of a new IBUS frame
  71. return;
  72. }
  73. byte_input.buf[byte_input.ofs++] = b;
  74. if (byte_input.ofs == sizeof(byte_input.buf)) {
  75. uint16_t values[IBUS_INPUT_CHANNELS];
  76. bool ibus_failsafe = false;
  77. if (ibus_decode(byte_input.buf, values, &ibus_failsafe)) {
  78. add_input(IBUS_INPUT_CHANNELS, values, ibus_failsafe);
  79. }
  80. byte_input.ofs = 0;
  81. }
  82. }
  83. // support byte input
  84. void AP_RCProtocol_IBUS::process_byte(uint8_t b, uint32_t baudrate)
  85. {
  86. if (baudrate != 115200) {
  87. return;
  88. }
  89. _process_byte(AP_HAL::micros(), b);
  90. }