AP_RCProtocol_DSM.h 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  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. * Code by Andrew Tridgell and Siddharth Bharat Purohit
  16. */
  17. #pragma once
  18. #include "AP_RCProtocol.h"
  19. #include "SoftSerial.h"
  20. #define AP_DSM_MAX_CHANNELS 12
  21. class AP_RCProtocol_DSM : public AP_RCProtocol_Backend {
  22. public:
  23. AP_RCProtocol_DSM(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) {}
  24. void process_pulse(uint32_t width_s0, uint32_t width_s1) override;
  25. void process_byte(uint8_t byte, uint32_t baudrate) override;
  26. void start_bind(void) override;
  27. void update(void) override;
  28. private:
  29. void _process_byte(uint32_t timestamp_ms, uint8_t byte);
  30. void dsm_decode();
  31. bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
  32. void dsm_guess_format(bool reset, const uint8_t dsm_frame[16]);
  33. bool dsm_parse_byte(uint32_t frame_time_ms, uint8_t b, uint16_t *values,
  34. uint16_t *num_values, uint16_t max_channels);
  35. bool dsm_decode(uint32_t frame_time_ms, const uint8_t dsm_frame[16],
  36. uint16_t *values, uint16_t *num_values, uint16_t max_values);
  37. /**< Channel resolution, 0=unknown, 10=10 bit, 11=11 bit */
  38. uint8_t channel_shift;
  39. // format guessing state
  40. uint32_t cs10;
  41. uint32_t cs11;
  42. uint32_t samples;
  43. // bind state machine
  44. enum {
  45. BIND_STATE_NONE,
  46. BIND_STATE1,
  47. BIND_STATE2,
  48. BIND_STATE3,
  49. BIND_STATE4,
  50. } bind_state;
  51. uint32_t bind_last_ms;
  52. uint16_t last_values[AP_DSM_MAX_CHANNELS];
  53. struct {
  54. uint8_t buf[16];
  55. uint8_t ofs;
  56. } byte_input;
  57. enum DSM_DECODE_STATE {
  58. DSM_DECODE_STATE_DESYNC = 0,
  59. DSM_DECODE_STATE_SYNC
  60. } dsm_decode_state;
  61. uint32_t last_frame_time_ms;
  62. uint32_t last_rx_time_ms;
  63. uint16_t chan_count;
  64. SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
  65. };