AP_RangeFinder_PWM.cpp 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185
  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_RangeFinder_PWM.h"
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <GCS_MAVLink/GCS.h>
  16. extern const AP_HAL::HAL& hal;
  17. /*
  18. The constructor also initialises the rangefinder.
  19. */
  20. AP_RangeFinder_PWM::AP_RangeFinder_PWM(RangeFinder::RangeFinder_State &_state,
  21. AP_RangeFinder_Params &_params,
  22. float &_estimated_terrain_height) :
  23. AP_RangeFinder_Backend(_state, _params),
  24. estimated_terrain_height(_estimated_terrain_height)
  25. {
  26. }
  27. /*
  28. There's no sensible way of detecting a PWM rangefinder as the pins are configurable
  29. */
  30. bool AP_RangeFinder_PWM::detect()
  31. {
  32. return true;
  33. }
  34. // interrupt handler for reading pwm value
  35. void AP_RangeFinder_PWM::irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us)
  36. {
  37. if (pin_high) {
  38. irq_pulse_start_us = timestamp_us;
  39. } else {
  40. if (irq_pulse_start_us != 0) {
  41. irq_value_us += timestamp_us - irq_pulse_start_us;
  42. irq_pulse_start_us = 0;
  43. irq_sample_count++;
  44. }
  45. }
  46. }
  47. // read - return last value measured by sensor
  48. bool AP_RangeFinder_PWM::get_reading(uint16_t &reading_cm)
  49. {
  50. // disable interrupts and grab state
  51. void *irqstate = hal.scheduler->disable_interrupts_save();
  52. const uint32_t value_us = irq_value_us;
  53. const uint16_t sample_count = irq_sample_count;
  54. irq_value_us = 0;
  55. irq_sample_count = 0;
  56. hal.scheduler->restore_interrupts(irqstate);
  57. if (value_us == 0 || sample_count == 0) {
  58. return false;
  59. }
  60. reading_cm = value_us/(sample_count * 10); // correct for LidarLite. Parameter needed? Converts from decimetres -> cm here
  61. return true;
  62. }
  63. void AP_RangeFinder_PWM::check_pin()
  64. {
  65. if (params.pin == last_pin) {
  66. return;
  67. }
  68. // detach last one
  69. if (last_pin > 0) {
  70. if (!hal.gpio->detach_interrupt(last_pin)) {
  71. gcs().send_text(MAV_SEVERITY_WARNING,
  72. "RangeFinder_PWM: Failed to detach from pin %u",
  73. last_pin);
  74. // ignore this failure or the user may be stuck
  75. }
  76. }
  77. // set last pin to params.pin so we don't continually try to attach
  78. // to it if the attach is failing
  79. last_pin = params.pin;
  80. if (params.pin <= 0) {
  81. // don't need to install handler
  82. return;
  83. }
  84. // install interrupt handler on rising and falling edge
  85. hal.gpio->pinMode(params.pin, HAL_GPIO_INPUT);
  86. if (!hal.gpio->attach_interrupt(
  87. params.pin,
  88. FUNCTOR_BIND_MEMBER(&AP_RangeFinder_PWM::irq_handler,
  89. void,
  90. uint8_t,
  91. bool,
  92. uint32_t),
  93. AP_HAL::GPIO::INTERRUPT_BOTH)) {
  94. // failed to attach interrupt
  95. gcs().send_text(MAV_SEVERITY_WARNING,
  96. "RangeFinder_PWM: Failed to attach to pin %u",
  97. (unsigned int)params.pin);
  98. return;
  99. }
  100. }
  101. void AP_RangeFinder_PWM::check_stop_pin()
  102. {
  103. if (params.stop_pin == last_stop_pin) {
  104. return;
  105. }
  106. hal.gpio->pinMode(params.stop_pin, HAL_GPIO_OUTPUT);
  107. last_stop_pin = params.stop_pin;
  108. }
  109. void AP_RangeFinder_PWM::check_pins()
  110. {
  111. check_pin();
  112. check_stop_pin();
  113. }
  114. /*
  115. update the state of the sensor
  116. */
  117. void AP_RangeFinder_PWM::update(void)
  118. {
  119. // check if pin has changed and configure interrupt handlers if required:
  120. check_pins();
  121. if (last_pin <= 0) {
  122. // disabled (by configuration)
  123. return;
  124. }
  125. if (params.stop_pin != -1) {
  126. const bool oor = out_of_range();
  127. if (oor) {
  128. if (!was_out_of_range) {
  129. // we are above the power saving range. Disable the sensor
  130. hal.gpio->write(params.stop_pin, false);
  131. set_status(RangeFinder::RangeFinder_NoData);
  132. state.distance_cm = 0;
  133. state.voltage_mv = 0;
  134. was_out_of_range = oor;
  135. }
  136. return;
  137. }
  138. // re-enable the sensor:
  139. if (!oor && was_out_of_range) {
  140. hal.gpio->write(params.stop_pin, true);
  141. was_out_of_range = oor;
  142. }
  143. }
  144. if (!get_reading(state.distance_cm)) {
  145. // failure; consider changing our state
  146. if (AP_HAL::millis() - state.last_reading_ms > 200) {
  147. set_status(RangeFinder::RangeFinder_NoData);
  148. }
  149. return;
  150. }
  151. // update range_valid state based on distance measured
  152. state.last_reading_ms = AP_HAL::millis();
  153. update_status();
  154. }
  155. // return true if we are beyond the power saving range
  156. bool AP_RangeFinder_PWM::out_of_range(void) const {
  157. return params.powersave_range > 0 && estimated_terrain_height > params.powersave_range;
  158. }