AP_SBusOut.cpp 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191
  1. /*
  2. * AP_SBusOut.cpp
  3. *
  4. * Created on: Aug 19, 2017
  5. * Author: Mark Whitehorn
  6. *
  7. * method sbus1_out was ported from ardupilot/modules/PX4Firmware/src/lib/rc/sbus.c
  8. * which has the following license:
  9. *
  10. * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
  11. *
  12. * Redistribution and use in source and binary forms, with or without
  13. * modification, are permitted provided that the following conditions
  14. * are met:
  15. *
  16. * 1. Redistributions of source code must retain the above copyright
  17. * notice, this list of conditions and the following disclaimer.
  18. * 2. Redistributions in binary form must reproduce the above copyright
  19. * notice, this list of conditions and the following disclaimer in
  20. * the documentation and/or other materials provided with the
  21. * distribution.
  22. * 3. Neither the name PX4 nor the names of its contributors may be
  23. * used to endorse or promote products derived from this software
  24. * without specific prior written permission.
  25. *
  26. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  27. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  28. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  29. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  30. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  31. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  32. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  33. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  34. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  35. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  36. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  37. * POSSIBILITY OF SUCH DAMAGE.
  38. *
  39. */
  40. #include "AP_SBusOut.h"
  41. #include <AP_Math/AP_Math.h>
  42. #include <AP_SerialManager/AP_SerialManager.h>
  43. #include <SRV_Channel/SRV_Channel.h>
  44. extern const AP_HAL::HAL& hal;
  45. #define SBUS_DEBUG 0
  46. // SBUS1 constant definitions
  47. // pulse widths measured using FrSky Sbus/PWM converter
  48. #define SBUS_BSIZE 25
  49. #define SBUS_CHANNELS 16
  50. #define SBUS_MIN 880.0f
  51. #define SBUS_MAX 2156.0f
  52. #define SBUS_SCALE (2048.0f / (SBUS_MAX - SBUS_MIN))
  53. const AP_Param::GroupInfo AP_SBusOut::var_info[] = {
  54. // @Param: RATE
  55. // @DisplayName: SBUS default output rate
  56. // @Description: This sets the SBUS output frame rate in Hz.
  57. // @Range: 25 250
  58. // @User: Advanced
  59. // @Units: Hz
  60. AP_GROUPINFO("RATE", 1, AP_SBusOut, sbus_rate, 50),
  61. AP_GROUPEND
  62. };
  63. // constructor
  64. AP_SBusOut::AP_SBusOut(void)
  65. {
  66. // set defaults from the parameter table
  67. AP_Param::setup_object_defaults(this, var_info);
  68. }
  69. /*
  70. format a SBUS output frame into a 25 byte buffer
  71. */
  72. void AP_SBusOut::sbus_format_frame(uint16_t *channels, uint8_t num_channels, uint8_t buffer[SBUS_BSIZE])
  73. {
  74. uint8_t index = 1;
  75. uint8_t offset = 0;
  76. memset(buffer, 0, SBUS_BSIZE);
  77. buffer[0] = 0x0f;
  78. /* construct sbus frame representing channels 1 through 16 (max) */
  79. uint8_t nchan = MIN(num_channels, SBUS_CHANNELS);
  80. for (unsigned i = 0; i < nchan; ++i) {
  81. /*protect from out of bounds values and limit to 11 bits*/
  82. uint16_t pwmval = MAX(channels[i], SBUS_MIN);
  83. uint16_t value = (uint16_t)((pwmval - SBUS_MIN) * SBUS_SCALE);
  84. if (value > 0x07ff) {
  85. value = 0x07ff;
  86. }
  87. #if SBUS_DEBUG
  88. static uint16_t lastch9 = 0;
  89. if ((i==8) && (pwmval != lastch9)) {
  90. lastch9 = pwmval;
  91. hal.console->printf("channel 9 pwm: %04d\n", pwmval);
  92. }
  93. #endif
  94. while (offset >= 8) {
  95. ++index;
  96. offset -= 8;
  97. }
  98. buffer[index] |= (value << (offset)) & 0xff;
  99. buffer[index + 1] |= (value >> (8 - offset)) & 0xff;
  100. buffer[index + 2] |= (value >> (16 - offset)) & 0xff;
  101. offset += 11;
  102. }
  103. }
  104. /*
  105. * build and send sbus1 frame representing first 16 servo channels
  106. * input arg is pointer to uart
  107. */
  108. void
  109. AP_SBusOut::update()
  110. {
  111. if (!initialised) {
  112. initialised = true;
  113. init();
  114. }
  115. if (sbus1_uart == nullptr) {
  116. return;
  117. }
  118. // constrain output rate using sbus_frame_interval
  119. static uint32_t last_micros = 0;
  120. uint32_t now = AP_HAL::micros();
  121. if ((now - last_micros) <= sbus_frame_interval) {
  122. return;
  123. }
  124. last_micros = now;
  125. /* construct sbus frame representing channels 1 through 16 (max) */
  126. uint8_t nchan = MIN(NUM_SERVO_CHANNELS, SBUS_CHANNELS);
  127. uint16_t channels[SBUS_CHANNELS] {};
  128. for (unsigned i = 0; i < nchan; ++i) {
  129. SRV_Channel *c = SRV_Channels::srv_channel(i);
  130. if (c == nullptr) {
  131. continue;
  132. }
  133. channels[i] = c->get_output_pwm();
  134. }
  135. uint8_t buffer[SBUS_BSIZE];
  136. sbus_format_frame(channels, nchan, buffer);
  137. #if SBUS_DEBUG
  138. hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
  139. hal.gpio->write(55, 1);
  140. #endif
  141. sbus1_uart->write(buffer, sizeof(buffer));
  142. #if SBUS_DEBUG
  143. hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
  144. hal.gpio->write(55, 0);
  145. #endif
  146. }
  147. void AP_SBusOut::init() {
  148. uint16_t rate = sbus_rate.get();
  149. #if SBUS_DEBUG
  150. hal.console->printf("AP_SBusOut: init %d Hz\n", rate);
  151. #endif
  152. // subtract 500usec from requested frame interval to allow for latency
  153. sbus_frame_interval = (1000UL * 1000UL) / rate - 500;
  154. // at 100,000 bps, a 300 bit sbus frame takes 3msec to transfer
  155. // require a minimum 700usec interframe gap
  156. if (sbus_frame_interval < 3700) {
  157. sbus_frame_interval = 3700;
  158. }
  159. AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
  160. if (!serial_manager) {
  161. return;
  162. }
  163. sbus1_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_Sbus1,0);
  164. }