AP_RangeFinder_analog.cpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121
  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. * AP_RangeFinder_analog.cpp - rangefinder for analog source
  15. *
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_Common/AP_Common.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include "RangeFinder.h"
  21. #include "AP_RangeFinder_Params.h"
  22. #include "AP_RangeFinder_analog.h"
  23. extern const AP_HAL::HAL& hal;
  24. /*
  25. The constructor also initialises the rangefinder. Note that this
  26. constructor is not called until detect() returns true, so we
  27. already know that we should setup the rangefinder
  28. */
  29. AP_RangeFinder_analog::AP_RangeFinder_analog(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
  30. AP_RangeFinder_Backend(_state, _params)
  31. {
  32. source = hal.analogin->channel(_params.pin);
  33. if (source == nullptr) {
  34. // failed to allocate a ADC channel? This shouldn't happen
  35. set_status(RangeFinder::RangeFinder_NotConnected);
  36. return;
  37. }
  38. set_status(RangeFinder::RangeFinder_NoData);
  39. }
  40. /*
  41. detect if an analog rangefinder is connected. The only thing we
  42. can do is check if the pin number is valid. If it is, then assume
  43. that the device is connected
  44. */
  45. bool AP_RangeFinder_analog::detect(AP_RangeFinder_Params &_params)
  46. {
  47. if (_params.pin != -1) {
  48. return true;
  49. }
  50. return false;
  51. }
  52. /*
  53. update raw voltage state
  54. */
  55. void AP_RangeFinder_analog::update_voltage(void)
  56. {
  57. if (source == nullptr) {
  58. state.voltage_mv = 0;
  59. return;
  60. }
  61. // cope with changed settings
  62. source->set_pin(params.pin);
  63. if (params.ratiometric) {
  64. state.voltage_mv = source->voltage_average_ratiometric() * 1000U;
  65. } else {
  66. state.voltage_mv = source->voltage_average() * 1000U;
  67. }
  68. }
  69. /*
  70. update distance_cm
  71. */
  72. void AP_RangeFinder_analog::update(void)
  73. {
  74. update_voltage();
  75. float v = state.voltage_mv * 0.001f;
  76. float dist_m = 0;
  77. float scaling = params.scaling;
  78. float offset = params.offset;
  79. RangeFinder::RangeFinder_Function function = (RangeFinder::RangeFinder_Function)params.function.get();
  80. int16_t _max_distance_cm = params.max_distance_cm;
  81. switch (function) {
  82. case RangeFinder::FUNCTION_LINEAR:
  83. dist_m = (v - offset) * scaling;
  84. break;
  85. case RangeFinder::FUNCTION_INVERTED:
  86. dist_m = (offset - v) * scaling;
  87. break;
  88. case RangeFinder::FUNCTION_HYPERBOLA:
  89. if (v <= offset) {
  90. dist_m = 0;
  91. } else {
  92. dist_m = scaling / (v - offset);
  93. }
  94. if (dist_m > _max_distance_cm * 0.01f) {
  95. dist_m = _max_distance_cm * 0.01f;
  96. }
  97. break;
  98. }
  99. if (dist_m < 0) {
  100. dist_m = 0;
  101. }
  102. state.distance_cm = dist_m * 100.0f;
  103. state.last_reading_ms = AP_HAL::millis();
  104. // update range_valid state based on distance measured
  105. update_status();
  106. }