RCProtocolTest.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235
  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. test for RC input protocols
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_RCProtocol/AP_RCProtocol.h>
  20. #include <stdio.h>
  21. void setup();
  22. void loop();
  23. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  24. static AP_RCProtocol *rcprot;
  25. // setup routine
  26. void setup()
  27. {
  28. // introduction
  29. hal.console->printf("ArduPilot RC protocol test\n");
  30. hal.scheduler->delay(100);
  31. }
  32. static bool check_result(const char *name, bool bytes, const uint16_t *values, uint8_t nvalues)
  33. {
  34. char label[20];
  35. snprintf(label, 20, "%s(%s)", name, bytes?"bytes":"pulses");
  36. if (!rcprot->new_input()) {
  37. printf("%s: No new input\n", label);
  38. return false;
  39. }
  40. const char *pname = rcprot->protocol_name();
  41. if (strncmp(pname, name, strlen(pname)) != 0) {
  42. printf("%s: wrong protocol detected %s\n", label, rcprot->protocol_name());
  43. return false;
  44. }
  45. uint8_t n = rcprot->num_channels();
  46. if (n != nvalues) {
  47. printf("%s: wrong number of channels %u should be %u\n", label, n, nvalues);
  48. return false;
  49. }
  50. for (uint8_t i=0; i<n; i++) {
  51. uint16_t v = rcprot->read(i);
  52. if (values[i] != v) {
  53. printf("%s: chan %u wrong value %u should be %u\n", label, i+1, v, values[i]);
  54. return false;
  55. }
  56. }
  57. printf("%s OK\n", label);
  58. return true;
  59. }
  60. /*
  61. test a byte protocol handler
  62. */
  63. static bool test_byte_protocol(const char *name, uint32_t baudrate,
  64. const uint8_t *bytes, uint8_t nbytes,
  65. const uint16_t *values, uint8_t nvalues,
  66. uint8_t repeats)
  67. {
  68. bool ret = true;
  69. for (uint8_t repeat=0; repeat<repeats+4; repeat++) {
  70. for (uint8_t i=0; i<nbytes; i++) {
  71. rcprot->process_byte(bytes[i], baudrate);
  72. }
  73. hal.scheduler->delay(10);
  74. if (repeat > repeats) {
  75. ret &= check_result(name, true, values, nvalues);
  76. }
  77. }
  78. return ret;
  79. }
  80. static void send_bit(uint8_t bit, uint32_t baudrate)
  81. {
  82. static uint16_t bits_0, bits_1;
  83. if (baudrate == 115200) {
  84. // yes, this is backwards ...
  85. bit = !bit;
  86. }
  87. if (bit == 0) {
  88. if (bits_1 > 0) {
  89. uint32_t w0=(bits_0 * (uint32_t)1000000) / baudrate;
  90. uint32_t w1=(bits_1 * (uint32_t)1000000) / baudrate;
  91. //printf("%u %u\n", w0, w1);
  92. rcprot->process_pulse(w0, w1);
  93. bits_0 = 1;
  94. bits_1 = 0;
  95. } else {
  96. bits_0++;
  97. }
  98. } else {
  99. bits_1++;
  100. }
  101. }
  102. /*
  103. call process_pulse() for a byte of input
  104. */
  105. static void send_byte(uint8_t b, uint32_t baudrate)
  106. {
  107. send_bit(0, baudrate); // start bit
  108. uint8_t parity = 0;
  109. for (uint8_t i=0; i<8; i++) {
  110. uint8_t bit = (b & (1U<<i))?1:0;
  111. send_bit(bit, baudrate);
  112. if (bit) {
  113. parity = !parity;
  114. }
  115. }
  116. if (baudrate == 100000) {
  117. // assume SBUS, send parity
  118. send_bit(parity, baudrate);
  119. }
  120. send_bit(1, baudrate); // stop bit
  121. if (baudrate == 100000) {
  122. send_bit(1, baudrate); // 2nd stop bit
  123. }
  124. }
  125. /*
  126. test a byte protocol handler
  127. */
  128. static bool test_pulse_protocol(const char *name, uint32_t baudrate,
  129. const uint8_t *bytes, uint8_t nbytes,
  130. const uint16_t *values, uint8_t nvalues,
  131. uint8_t repeats)
  132. {
  133. bool ret = true;
  134. for (uint8_t repeat=0; repeat<repeats+4; repeat++) {
  135. for (uint16_t i=0; i<8000; i++) {
  136. send_bit(1, baudrate);
  137. }
  138. for (uint8_t i=0; i<nbytes; i++) {
  139. send_byte(bytes[i], baudrate);
  140. }
  141. for (uint16_t i=0; i<8000; i++) {
  142. send_bit(1, baudrate);
  143. }
  144. if (repeat > repeats) {
  145. ret &= check_result(name, false, values, nvalues);
  146. }
  147. }
  148. return ret;
  149. }
  150. /*
  151. test a protocol handler
  152. */
  153. static bool test_protocol(const char *name, uint32_t baudrate,
  154. const uint8_t *bytes, uint8_t nbytes,
  155. const uint16_t *values, uint8_t nvalues,
  156. uint8_t repeats=1)
  157. {
  158. bool ret = true;
  159. rcprot = new AP_RCProtocol();
  160. rcprot->init();
  161. ret &= test_byte_protocol(name, baudrate, bytes, nbytes, values, nvalues, repeats);
  162. delete rcprot;
  163. rcprot = new AP_RCProtocol();
  164. rcprot->init();
  165. ret &= test_pulse_protocol(name, baudrate, bytes, nbytes, values, nvalues, repeats);
  166. delete rcprot;
  167. return ret;
  168. }
  169. //Main loop where the action takes place
  170. void loop()
  171. {
  172. const uint8_t srxl_bytes[] = { 0xa5, 0x03, 0x0c, 0x04, 0x2f, 0x6c, 0x10, 0xb4, 0x26,
  173. 0x16, 0x34, 0x01, 0x04, 0x76, 0x1c, 0x40, 0xf5, 0x3b };
  174. const uint16_t srxl_output[] = { 1567, 1502, 1019, 1536, 1804, 2000, 1500 };
  175. const uint8_t sbus_bytes[] = {0x0F, 0x4C, 0x1C, 0x5F, 0x32, 0x34, 0x38, 0xDD, 0x89,
  176. 0x83, 0x0F, 0x7C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
  177. 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
  178. const uint16_t sbus_output[] = {1562, 1496, 1000, 1530, 1806, 2006, 1494, 1494, 874,
  179. 874, 874, 874, 874, 874, 874, 874};
  180. const uint8_t dsm_bytes[] = {0x00, 0xab, 0x00, 0xae, 0x08, 0xbf, 0x10, 0xd0, 0x18,
  181. 0xe1, 0x20, 0xf2, 0x29, 0x03, 0x31, 0x14, 0x00, 0xab,
  182. 0x39, 0x25, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
  183. 0xff, 0xff, 0xff, 0xff, 0xff};
  184. const uint16_t dsm_output[] = {1010, 1020, 1000, 1030, 1040, 1050, 1060, 1070};
  185. const uint8_t sumd_bytes[] = {0xA8, 0x01, 0x08, 0x2F, 0x50, 0x31, 0xE8, 0x21, 0xA0,
  186. 0x2F, 0x50, 0x22, 0x60, 0x22, 0x60, 0x2E, 0xE0, 0x2E,
  187. 0xE0, 0x87, 0xC6};
  188. const uint8_t sumd_bytes2[] = {0xA8, 0x01, 0x0C, 0x22, 0x60, 0x2F, 0x60, 0x2E, 0xE0, 0x2E, 0xE0, 0x3B,
  189. 0x60, 0x3B, 0x60, 0x3B, 0x60, 0x3B, 0x60, 0x3B, 0x60, 0x3B, 0x60, 0x3B, 0x60, 0x3B,
  190. 0x60, 0x17, 0x02};
  191. const uint8_t sumd_bytes3[] = {0xA8, 0x01, 0x10, 0x1F, 0x40, 0x2E, 0xE8, 0x2E, 0xE0, 0x2E, 0xE0, 0x2E, 0xE0,
  192. 0x2E, 0xE0, 0x2E, 0xE0, 0x22, 0x60, 0x2E, 0xE0, 0x2E, 0xE0, 0x2E, 0xE0, 0x2E,
  193. 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3B, 0x20, 0x4F, 0x10};
  194. const uint16_t sumd_output[] = {1597, 1076, 1514, 1514, 1100, 1100, 1500, 1500};
  195. const uint16_t sumd_output2[] = {1516, 1500, 1100, 1500, 1900, 1900, 1900, 1900, 1900, 1900, 1900, 1900};
  196. const uint16_t sumd_output3[] = {1501, 1500, 1000, 1500, 1500, 1500, 1500, 1100, 1500, 1500, 1500, 1500, 0, 0, 0, 1892};
  197. const uint8_t ibus_bytes[] = {0x20, 0x40, 0xdc, 0x05, 0xdc, 0x05, 0xe8, 0x03, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0xdc, 0x05, 0x47, 0xf3};
  198. const uint16_t ibus_output[] = {1500, 1500, 1000, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
  199. test_protocol("SRXL", 115200, srxl_bytes, sizeof(srxl_bytes), srxl_output, ARRAY_SIZE(srxl_output), 1);
  200. test_protocol("SUMD", 115200, sumd_bytes, sizeof(sumd_bytes), sumd_output, ARRAY_SIZE(sumd_output), 1);
  201. test_protocol("SUMD2", 115200, sumd_bytes2, sizeof(sumd_bytes2), sumd_output2, ARRAY_SIZE(sumd_output2), 1);
  202. test_protocol("SUMD3", 115200, sumd_bytes3, sizeof(sumd_bytes3), sumd_output3, ARRAY_SIZE(sumd_output3), 1);
  203. test_protocol("IBUS", 115200, ibus_bytes, sizeof(ibus_bytes), ibus_output, ARRAY_SIZE(ibus_output), 1);
  204. // SBUS needs 3 repeats to pass the RCProtocol 3 frames test
  205. test_protocol("SBUS", 100000, sbus_bytes, sizeof(sbus_bytes), sbus_output, ARRAY_SIZE(sbus_output), 3);
  206. // DSM needs 8 repeats, 5 to guess the format, then 3 to pass the RCProtocol 3 frames test
  207. test_protocol("DSM", 115200, dsm_bytes, sizeof(dsm_bytes), dsm_output, ARRAY_SIZE(dsm_output), 9);
  208. }
  209. AP_HAL_MAIN();