SRV_Channels.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290
  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. SRV_Channel.cpp - object to separate input and output channel
  15. ranges, trim and reversal
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_Math/AP_Math.h>
  19. #include <AP_Vehicle/AP_Vehicle.h>
  20. #include "SRV_Channel.h"
  21. #if HAL_WITH_UAVCAN
  22. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  23. #include <AP_UAVCAN/AP_UAVCAN.h>
  24. // To be replaced with macro saying if KDECAN library is included
  25. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  26. #include <AP_KDECAN/AP_KDECAN.h>
  27. #endif
  28. #include <AP_ToshibaCAN/AP_ToshibaCAN.h>
  29. #endif
  30. extern const AP_HAL::HAL& hal;
  31. SRV_Channel *SRV_Channels::channels;
  32. SRV_Channels *SRV_Channels::_singleton;
  33. AP_Volz_Protocol *SRV_Channels::volz_ptr;
  34. AP_SBusOut *SRV_Channels::sbus_ptr;
  35. AP_RobotisServo *SRV_Channels::robotis_ptr;
  36. #if HAL_SUPPORT_RCOUT_SERIAL
  37. AP_BLHeli *SRV_Channels::blheli_ptr;
  38. #endif
  39. uint16_t SRV_Channels::disabled_mask;
  40. uint16_t SRV_Channels::digital_mask;
  41. uint16_t SRV_Channels::reversible_mask;
  42. bool SRV_Channels::disabled_passthrough;
  43. bool SRV_Channels::initialised;
  44. bool SRV_Channels::emergency_stop;
  45. Bitmask<SRV_Channel::k_nr_aux_servo_functions> SRV_Channels::function_mask;
  46. SRV_Channels::srv_function SRV_Channels::functions[SRV_Channel::k_nr_aux_servo_functions];
  47. const AP_Param::GroupInfo SRV_Channels::var_info[] = {
  48. // @Group: 1_
  49. // @Path: SRV_Channel.cpp
  50. AP_SUBGROUPINFO(obj_channels[0], "1_", 1, SRV_Channels, SRV_Channel),
  51. // @Group: 2_
  52. // @Path: SRV_Channel.cpp
  53. AP_SUBGROUPINFO(obj_channels[1], "2_", 2, SRV_Channels, SRV_Channel),
  54. // @Group: 3_
  55. // @Path: SRV_Channel.cpp
  56. AP_SUBGROUPINFO(obj_channels[2], "3_", 3, SRV_Channels, SRV_Channel),
  57. // @Group: 4_
  58. // @Path: SRV_Channel.cpp
  59. AP_SUBGROUPINFO(obj_channels[3], "4_", 4, SRV_Channels, SRV_Channel),
  60. // @Group: 5_
  61. // @Path: SRV_Channel.cpp
  62. AP_SUBGROUPINFO(obj_channels[4], "5_", 5, SRV_Channels, SRV_Channel),
  63. // @Group: 6_
  64. // @Path: SRV_Channel.cpp
  65. AP_SUBGROUPINFO(obj_channels[5], "6_", 6, SRV_Channels, SRV_Channel),
  66. // @Group: 7_
  67. // @Path: SRV_Channel.cpp
  68. AP_SUBGROUPINFO(obj_channels[6], "7_", 7, SRV_Channels, SRV_Channel),
  69. // @Group: 8_
  70. // @Path: SRV_Channel.cpp
  71. AP_SUBGROUPINFO(obj_channels[7], "8_", 8, SRV_Channels, SRV_Channel),
  72. // @Group: 9_
  73. // @Path: SRV_Channel.cpp
  74. AP_SUBGROUPINFO(obj_channels[8], "9_", 9, SRV_Channels, SRV_Channel),
  75. // @Group: 10_
  76. // @Path: SRV_Channel.cpp
  77. AP_SUBGROUPINFO(obj_channels[9], "10_", 10, SRV_Channels, SRV_Channel),
  78. // @Group: 11_
  79. // @Path: SRV_Channel.cpp
  80. AP_SUBGROUPINFO(obj_channels[10], "11_", 11, SRV_Channels, SRV_Channel),
  81. // @Group: 12_
  82. // @Path: SRV_Channel.cpp
  83. AP_SUBGROUPINFO(obj_channels[11], "12_", 12, SRV_Channels, SRV_Channel),
  84. // @Group: 13_
  85. // @Path: SRV_Channel.cpp
  86. AP_SUBGROUPINFO(obj_channels[12], "13_", 13, SRV_Channels, SRV_Channel),
  87. // @Group: 14_
  88. // @Path: SRV_Channel.cpp
  89. AP_SUBGROUPINFO(obj_channels[13], "14_", 14, SRV_Channels, SRV_Channel),
  90. // @Group: 15_
  91. // @Path: SRV_Channel.cpp
  92. AP_SUBGROUPINFO(obj_channels[14], "15_", 15, SRV_Channels, SRV_Channel),
  93. // @Group: 16_
  94. // @Path: SRV_Channel.cpp
  95. AP_SUBGROUPINFO(obj_channels[15], "16_", 16, SRV_Channels, SRV_Channel),
  96. // @Param: _AUTO_TRIM
  97. // @DisplayName: Automatic servo trim
  98. // @Description: This enables automatic servo trim in flight. Servos will be trimed in stabilized flight modes when the aircraft is close to level. Changes to servo trim will be saved every 10 seconds and will persist between flights.
  99. // @Values: 0:Disable,1:Enable
  100. // @User: Advanced
  101. AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
  102. // @Param: _RATE
  103. // @DisplayName: Servo default output rate
  104. // @Description: This sets the default output rate in Hz for all outputs.
  105. // @Range: 25 400
  106. // @User: Advanced
  107. // @Units: Hz
  108. AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
  109. // @Group: _VOLZ_
  110. // @Path: ../AP_Volz_Protocol/AP_Volz_Protocol.cpp
  111. AP_SUBGROUPINFO(volz, "_VOLZ_", 19, SRV_Channels, AP_Volz_Protocol),
  112. // @Group: _SBUS_
  113. // @Path: ../AP_SBusOut/AP_SBusOut.cpp
  114. AP_SUBGROUPINFO(sbus, "_SBUS_", 20, SRV_Channels, AP_SBusOut),
  115. #if HAL_SUPPORT_RCOUT_SERIAL
  116. // @Group: _BLH_
  117. // @Path: ../AP_BLHeli/AP_BLHeli.cpp
  118. AP_SUBGROUPINFO(blheli, "_BLH_", 21, SRV_Channels, AP_BLHeli),
  119. #endif
  120. // @Group: _ROB_
  121. // @Path: ../AP_RobotisServo/AP_RobotisServo.cpp
  122. AP_SUBGROUPINFO(robotis, "_ROB_", 22, SRV_Channels, AP_RobotisServo),
  123. AP_GROUPEND
  124. };
  125. /*
  126. constructor
  127. */
  128. SRV_Channels::SRV_Channels(void)
  129. {
  130. _singleton = this;
  131. channels = obj_channels;
  132. // set defaults from the parameter table
  133. AP_Param::setup_object_defaults(this, var_info);
  134. // setup ch_num on channels
  135. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  136. channels[i].ch_num = i;
  137. }
  138. volz_ptr = &volz;
  139. sbus_ptr = &sbus;
  140. robotis_ptr = &robotis;
  141. #if HAL_SUPPORT_RCOUT_SERIAL
  142. blheli_ptr = &blheli;
  143. #endif
  144. }
  145. /*
  146. save adjusted trims
  147. */
  148. void SRV_Channels::save_trim(void)
  149. {
  150. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  151. if (trimmed_mask & (1U<<i)) {
  152. channels[i].servo_trim.set_and_save(channels[i].servo_trim.get());
  153. }
  154. }
  155. trimmed_mask = 0;
  156. }
  157. void SRV_Channels::setup_failsafe_trim_all_non_motors(void)
  158. {
  159. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  160. if (!SRV_Channel::is_motor(channels[i].get_function())) {
  161. hal.rcout->set_failsafe_pwm(1U<<channels[i].ch_num, channels[i].servo_trim);
  162. }
  163. }
  164. }
  165. /*
  166. run calc_pwm for all channels
  167. */
  168. void SRV_Channels::calc_pwm(void)
  169. {
  170. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  171. channels[i].calc_pwm(functions[channels[i].function].output_scaled);
  172. }
  173. }
  174. // set output value for a specific function channel as a pwm value
  175. void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value)
  176. {
  177. if (chan < NUM_SERVO_CHANNELS) {
  178. channels[chan].set_output_pwm(value);
  179. }
  180. }
  181. /*
  182. wrapper around hal.rcout->cork()
  183. */
  184. void SRV_Channels::cork()
  185. {
  186. hal.rcout->cork();
  187. }
  188. /*
  189. wrapper around hal.rcout->push()
  190. */
  191. void SRV_Channels::push()
  192. {
  193. hal.rcout->push();
  194. // give volz library a chance to update
  195. volz_ptr->update();
  196. // give sbus library a chance to update
  197. sbus_ptr->update();
  198. // give robotis library a chance to update
  199. robotis_ptr->update();
  200. #if HAL_SUPPORT_RCOUT_SERIAL
  201. // give blheli telemetry a chance to update
  202. blheli_ptr->update_telemetry();
  203. #endif
  204. #if HAL_WITH_UAVCAN
  205. // push outputs to CAN
  206. uint8_t can_num_drivers = AP::can().get_num_drivers();
  207. for (uint8_t i = 0; i < can_num_drivers; i++) {
  208. switch (AP::can().get_protocol_type(i)) {
  209. case AP_BoardConfig_CAN::Protocol_Type_UAVCAN: {
  210. AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
  211. if (ap_uavcan == nullptr) {
  212. continue;
  213. }
  214. ap_uavcan->SRV_push_servos();
  215. break;
  216. }
  217. case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
  218. // To be replaced with macro saying if KDECAN library is included
  219. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  220. AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
  221. if (ap_kdecan == nullptr) {
  222. continue;
  223. }
  224. ap_kdecan->update();
  225. break;
  226. #endif
  227. }
  228. case AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN: {
  229. AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i);
  230. if (ap_tcan == nullptr) {
  231. continue;
  232. }
  233. ap_tcan->update();
  234. break;
  235. }
  236. case AP_BoardConfig_CAN::Protocol_Type_None:
  237. default:
  238. break;
  239. }
  240. }
  241. #endif // HAL_WITH_UAVCAN
  242. }