AP_RSSI.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312
  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. #include <AP_RSSI/AP_RSSI.h>
  14. #include <GCS_MAVLink/GCS.h>
  15. #include <RC_Channel/RC_Channel.h>
  16. #include <utility>
  17. extern const AP_HAL::HAL& hal;
  18. #ifndef BOARD_RSSI_DEFAULT
  19. #define BOARD_RSSI_DEFAULT 0
  20. #endif
  21. #ifndef BOARD_RSSI_ANA_PIN
  22. #define BOARD_RSSI_ANA_PIN 0
  23. #endif
  24. #ifndef BOARD_RSSI_ANA_PIN_HIGH
  25. #define BOARD_RSSI_ANA_PIN_HIGH 5.0f
  26. #endif
  27. const AP_Param::GroupInfo AP_RSSI::var_info[] = {
  28. // @Param: TYPE
  29. // @DisplayName: RSSI Type
  30. // @Description: Radio Receiver RSSI type. If your radio receiver supports RSSI of some kind, set it here, then set its associated RSSI_XXXXX parameters, if any.
  31. // @Values: 0:Disabled,1:AnalogPin,2:RCChannelPwmValue,3:ReceiverProtocol,4:PWMInputPin
  32. // @User: Standard
  33. AP_GROUPINFO_FLAGS("TYPE", 0, AP_RSSI, rssi_type, BOARD_RSSI_DEFAULT, AP_PARAM_FLAG_ENABLE),
  34. // @Param: ANA_PIN
  35. // @DisplayName: Receiver RSSI sensing pin
  36. // @Description: Pin used to read the RSSI voltage or PWM value
  37. // @Values: 8:V5 Nano,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
  38. // @User: Standard
  39. AP_GROUPINFO("ANA_PIN", 1, AP_RSSI, rssi_analog_pin, BOARD_RSSI_ANA_PIN),
  40. // @Param: PIN_LOW
  41. // @DisplayName: RSSI pin's lowest voltage
  42. // @Description: RSSI pin's voltage received on the RSSI_ANA_PIN when the signal strength is the weakest. Some radio receivers put out inverted values so this value may be higher than RSSI_PIN_HIGH
  43. // @Units: V
  44. // @Increment: 0.01
  45. // @Range: 0 5.0
  46. // @User: Standard
  47. AP_GROUPINFO("PIN_LOW", 2, AP_RSSI, rssi_analog_pin_range_low, 0.0f),
  48. // @Param: PIN_HIGH
  49. // @DisplayName: RSSI pin's highest voltage
  50. // @Description: RSSI pin's voltage received on the RSSI_ANA_PIN when the signal strength is the strongest. Some radio receivers put out inverted values so this value may be lower than RSSI_PIN_LOW
  51. // @Units: V
  52. // @Increment: 0.01
  53. // @Range: 0 5.0
  54. // @User: Standard
  55. AP_GROUPINFO("PIN_HIGH", 3, AP_RSSI, rssi_analog_pin_range_high, BOARD_RSSI_ANA_PIN_HIGH),
  56. // @Param: CHANNEL
  57. // @DisplayName: Receiver RSSI channel number
  58. // @Description: The channel number where RSSI will be output by the radio receiver (5 and above).
  59. // @Range: 0 16
  60. // @User: Standard
  61. AP_GROUPINFO("CHANNEL", 4, AP_RSSI, rssi_channel, 0),
  62. // @Param: CHAN_LOW
  63. // @DisplayName: RSSI PWM low value
  64. // @Description: PWM value that the radio receiver will put on the RSSI_CHANNEL or RSSI_ANA_PIN when the signal strength is the weakest. Some radio receivers output inverted values so this value may be lower than RSSI_CHAN_HIGH
  65. // @Units: PWM
  66. // @Range: 0 2000
  67. // @User: Standard
  68. AP_GROUPINFO("CHAN_LOW", 5, AP_RSSI, rssi_channel_low_pwm_value, 1000),
  69. // @Param: CHAN_HIGH
  70. // @DisplayName: Receiver RSSI PWM high value
  71. // @Description: PWM value that the radio receiver will put on the RSSI_CHANNEL or RSSI_ANA_PIN when the signal strength is the strongest. Some radio receivers output inverted values so this value may be higher than RSSI_CHAN_LOW
  72. // @Units: PWM
  73. // @Range: 0 2000
  74. // @User: Standard
  75. AP_GROUPINFO("CHAN_HIGH", 6, AP_RSSI, rssi_channel_high_pwm_value, 2000),
  76. AP_GROUPEND
  77. };
  78. // Public
  79. // ------
  80. // constructor
  81. AP_RSSI::AP_RSSI()
  82. {
  83. AP_Param::setup_object_defaults(this, var_info);
  84. if (_singleton) {
  85. AP_HAL::panic("Too many RSSI sensors");
  86. }
  87. _singleton = this;
  88. }
  89. // destructor
  90. AP_RSSI::~AP_RSSI(void)
  91. {
  92. }
  93. /*
  94. * Get the AP_RSSI singleton
  95. */
  96. AP_RSSI *AP_RSSI::get_singleton()
  97. {
  98. return _singleton;
  99. }
  100. // Initialize the rssi object and prepare it for use
  101. void AP_RSSI::init()
  102. {
  103. // a pin for reading the receiver RSSI voltage. The scaling by 0.25
  104. // is to take the 0 to 1024 range down to an 8 bit range for MAVLink
  105. rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
  106. }
  107. // Read the receiver RSSI value as a float 0.0f - 1.0f.
  108. // 0.0 represents weakest signal, 1.0 represents maximum signal.
  109. float AP_RSSI::read_receiver_rssi()
  110. {
  111. switch (RssiType(rssi_type.get())) {
  112. case RssiType::TYPE_DISABLED:
  113. return 0.0f;
  114. case RssiType::ANALOG_PIN:
  115. return read_pin_rssi();
  116. case RssiType::RC_CHANNEL_VALUE:
  117. return read_channel_rssi();
  118. case RssiType::RECEIVER: {
  119. int16_t rssi = RC_Channels::get_receiver_rssi();
  120. if (rssi != -1) {
  121. return rssi / 255.0;
  122. }
  123. return 0.0f;
  124. }
  125. case RssiType::PWM_PIN:
  126. return read_pwm_pin_rssi();
  127. }
  128. // should never get to here
  129. return 0.0f;
  130. }
  131. // Read the receiver RSSI value as an 8-bit integer
  132. // 0 represents weakest signal, 255 represents maximum signal.
  133. uint8_t AP_RSSI::read_receiver_rssi_uint8()
  134. {
  135. return read_receiver_rssi() * 255;
  136. }
  137. // Private
  138. // -------
  139. // read the RSSI value from an analog pin - returns float in range 0.0 to 1.0
  140. float AP_RSSI::read_pin_rssi()
  141. {
  142. rssi_analog_source->set_pin(rssi_analog_pin);
  143. float current_analog_voltage = rssi_analog_source->voltage_average();
  144. return scale_and_constrain_float_rssi(current_analog_voltage, rssi_analog_pin_range_low, rssi_analog_pin_range_high);
  145. }
  146. // read the RSSI value from a PWM value on a RC channel
  147. float AP_RSSI::read_channel_rssi()
  148. {
  149. RC_Channel *c = rc().channel(rssi_channel-1);
  150. if (c == nullptr) {
  151. return 0.0f;
  152. }
  153. uint16_t rssi_channel_value = c->get_radio_in();
  154. float channel_rssi = scale_and_constrain_float_rssi(rssi_channel_value, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
  155. return channel_rssi;
  156. }
  157. void AP_RSSI::check_pwm_pin_rssi()
  158. {
  159. if (rssi_analog_pin == pwm_state.last_rssi_analog_pin) {
  160. return;
  161. }
  162. // detach last one
  163. if (pwm_state.last_rssi_analog_pin) {
  164. if (!hal.gpio->detach_interrupt(pwm_state.last_rssi_analog_pin)) {
  165. gcs().send_text(MAV_SEVERITY_WARNING,
  166. "RSSI: Failed to detach from pin %u",
  167. pwm_state.last_rssi_analog_pin);
  168. // ignore this failure or the user may be stuck
  169. }
  170. }
  171. pwm_state.last_rssi_analog_pin = rssi_analog_pin;
  172. if (!rssi_analog_pin) {
  173. // don't need to install handler
  174. return;
  175. }
  176. // install interrupt handler on rising and falling edge
  177. hal.gpio->pinMode(rssi_analog_pin, HAL_GPIO_INPUT);
  178. if (!hal.gpio->attach_interrupt(
  179. rssi_analog_pin,
  180. FUNCTOR_BIND_MEMBER(&AP_RSSI::irq_handler,
  181. void,
  182. uint8_t,
  183. bool,
  184. uint32_t),
  185. AP_HAL::GPIO::INTERRUPT_BOTH)) {
  186. // failed to attach interrupt
  187. gcs().send_text(MAV_SEVERITY_WARNING,
  188. "RSSI: Failed to attach to pin %u",
  189. (unsigned int)rssi_analog_pin);
  190. return;
  191. }
  192. }
  193. // read the PWM value from a pin
  194. float AP_RSSI::read_pwm_pin_rssi()
  195. {
  196. // check if pin has changed and configure interrupt handlers if required:
  197. check_pwm_pin_rssi();
  198. if (!pwm_state.last_rssi_analog_pin) {
  199. // disabled (either by configuration or failure to attach interrupt)
  200. return 0.0f;
  201. }
  202. // disable interrupts and grab state
  203. void *irqstate = hal.scheduler->disable_interrupts_save();
  204. const uint32_t irq_value_us = pwm_state.irq_value_us;
  205. pwm_state.irq_value_us = 0;
  206. hal.scheduler->restore_interrupts(irqstate);
  207. const uint32_t now = AP_HAL::millis();
  208. if (irq_value_us == 0) {
  209. // no reading; check for timeout:
  210. if (now - pwm_state.last_reading_ms > 1000) {
  211. // no reading for a second - something is broken
  212. pwm_state.rssi_value = 0.0f;
  213. }
  214. } else {
  215. // a new reading - convert pwm value to rssi value
  216. pwm_state.rssi_value = scale_and_constrain_float_rssi(irq_value_us, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
  217. pwm_state.last_reading_ms = now;
  218. }
  219. return pwm_state.rssi_value;
  220. }
  221. // Scale and constrain a float rssi value to 0.0 to 1.0 range
  222. float AP_RSSI::scale_and_constrain_float_rssi(float current_rssi_value, float low_rssi_range, float high_rssi_range)
  223. {
  224. float rssi_value_range = fabsf(high_rssi_range - low_rssi_range);
  225. if (is_zero(rssi_value_range)) {
  226. // User range isn't meaningful, return 0 for RSSI (and avoid divide by zero)
  227. return 0.0f;
  228. }
  229. // Note that user-supplied ranges may be inverted and we accommodate that here.
  230. // (Some radio receivers put out inverted ranges for RSSI-type values).
  231. bool range_is_inverted = (high_rssi_range < low_rssi_range);
  232. // Constrain to the possible range - values outside are clipped to ends
  233. current_rssi_value = constrain_float(current_rssi_value,
  234. range_is_inverted ? high_rssi_range : low_rssi_range,
  235. range_is_inverted ? low_rssi_range : high_rssi_range);
  236. if (range_is_inverted)
  237. {
  238. // Swap values so we can treat them as low->high uniformly in the code that follows
  239. current_rssi_value = high_rssi_range + fabsf(current_rssi_value - low_rssi_range);
  240. std::swap(low_rssi_range, high_rssi_range);
  241. }
  242. // Scale the value down to a 0.0 - 1.0 range
  243. float rssi_value_scaled = (current_rssi_value - low_rssi_range) / rssi_value_range;
  244. // Make absolutely sure the value is clipped to the 0.0 - 1.0 range. This should handle things if the
  245. // value retrieved falls outside the user-supplied range.
  246. return constrain_float(rssi_value_scaled, 0.0f, 1.0f);
  247. }
  248. // interrupt handler for reading pwm value
  249. void AP_RSSI::irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us)
  250. {
  251. if (pin_high) {
  252. pwm_state.pulse_start_us = timestamp_us;
  253. } else {
  254. if (pwm_state.pulse_start_us != 0) {
  255. pwm_state.irq_value_us = timestamp_us - pwm_state.pulse_start_us;
  256. pwm_state.pulse_start_us = 0;
  257. }
  258. }
  259. }
  260. AP_RSSI *AP_RSSI::_singleton = nullptr;
  261. namespace AP {
  262. AP_RSSI *rssi()
  263. {
  264. return AP_RSSI::get_singleton();
  265. }
  266. };