RC_Channels.cpp 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212
  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. * RC_Channels.cpp - class containing an array of RC_Channel objects
  15. *
  16. */
  17. #include <stdlib.h>
  18. #include <cmath>
  19. #include <AP_HAL/AP_HAL.h>
  20. extern const AP_HAL::HAL& hal;
  21. #include <AP_Math/AP_Math.h>
  22. #include <AP_Logger/AP_Logger.h>
  23. #include "RC_Channel.h"
  24. /*
  25. channels group object constructor
  26. */
  27. RC_Channels::RC_Channels(void)
  28. {
  29. // set defaults from the parameter table
  30. AP_Param::setup_object_defaults(this, var_info);
  31. if (_singleton != nullptr) {
  32. AP_HAL::panic("RC_Channels must be singleton");
  33. }
  34. _singleton = this;
  35. }
  36. void RC_Channels::init(void)
  37. {
  38. // setup ch_in on channels
  39. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  40. channel(i)->ch_in = i;
  41. }
  42. init_aux_all();
  43. }
  44. uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
  45. {
  46. memset(chans, 0, num_channels*sizeof(*chans));
  47. const uint8_t read_channels = MIN(num_channels, NUM_RC_CHANNELS);
  48. for (uint8_t i = 0; i < read_channels; i++) {
  49. chans[i] = channel(i)->get_radio_in();
  50. }
  51. return read_channels;
  52. }
  53. // update all the input channels
  54. bool RC_Channels::read_input(void)
  55. {
  56. if (!hal.rcin->new_input() && !has_new_overrides) {
  57. return false;
  58. }
  59. has_new_overrides = false;
  60. bool success = false;
  61. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  62. success |= channel(i)->update();
  63. }
  64. return success;
  65. }
  66. uint8_t RC_Channels::get_valid_channel_count(void)
  67. {
  68. return MIN(NUM_RC_CHANNELS, hal.rcin->num_channels());
  69. }
  70. int16_t RC_Channels::get_receiver_rssi(void)
  71. {
  72. return hal.rcin->get_rssi();
  73. }
  74. void RC_Channels::clear_overrides(void)
  75. {
  76. RC_Channels &_rc = rc();
  77. for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
  78. _rc.channel(i)->clear_override();
  79. }
  80. // we really should set has_new_overrides to true, and rerun read_input from
  81. // the vehicle code however doing so currently breaks the failsafe system on
  82. // copter and plane, RC_Channels needs to control failsafes to resolve this
  83. }
  84. void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms)
  85. {
  86. RC_Channels &_rc = rc();
  87. if (chan < NUM_RC_CHANNELS) {
  88. _rc.channel(chan)->set_override(value, timestamp_ms);
  89. }
  90. }
  91. bool RC_Channels::has_active_overrides()
  92. {
  93. RC_Channels &_rc = rc();
  94. for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
  95. if (_rc.channel(i)->has_override()) {
  96. return true;
  97. }
  98. }
  99. return false;
  100. }
  101. bool RC_Channels::receiver_bind(const int dsmMode)
  102. {
  103. return hal.rcin->rc_bind(dsmMode);
  104. }
  105. // support for auxillary switches:
  106. // read_aux_switches - checks aux switch positions and invokes configured actions
  107. void RC_Channels::read_aux_all()
  108. {
  109. if (!has_valid_input()) {
  110. // exit immediately when no RC input
  111. return;
  112. }
  113. bool need_log = false;
  114. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  115. RC_Channel *c = channel(i);
  116. if (c == nullptr) {
  117. continue;
  118. }
  119. need_log |= c->read_aux();
  120. }
  121. if (need_log) {
  122. // guarantee that we log when a switch changes
  123. AP::logger().Write_RCIN();
  124. }
  125. }
  126. void RC_Channels::init_aux_all()
  127. {
  128. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  129. RC_Channel *c = channel(i);
  130. if (c == nullptr) {
  131. continue;
  132. }
  133. c->init_aux();
  134. }
  135. reset_mode_switch();
  136. }
  137. //
  138. // Support for mode switches
  139. //
  140. RC_Channel *RC_Channels::flight_mode_channel()
  141. {
  142. const int8_t num = flight_mode_channel_number();
  143. if (num <= 0) {
  144. return nullptr;
  145. }
  146. if (num >= NUM_RC_CHANNELS) {
  147. return nullptr;
  148. }
  149. return channel(num-1);
  150. }
  151. void RC_Channels::reset_mode_switch()
  152. {
  153. RC_Channel *c = flight_mode_channel();
  154. if (c == nullptr) {
  155. return;
  156. }
  157. c->reset_mode_switch();
  158. }
  159. void RC_Channels::read_mode_switch()
  160. {
  161. if (!has_valid_input()) {
  162. // exit immediately when no RC input
  163. return;
  164. }
  165. RC_Channel *c = flight_mode_channel();
  166. if (c == nullptr) {
  167. return;
  168. }
  169. c->read_mode_switch();
  170. }
  171. // singleton instance
  172. RC_Channels *RC_Channels::_singleton;
  173. RC_Channels &rc()
  174. {
  175. return *RC_Channels::get_singleton();
  176. }