AP_RPM.h 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include <AP_Param/AP_Param.h>
  17. #include <AP_Math/AP_Math.h>
  18. // Maximum number of RPM measurement instances available on this platform
  19. #define RPM_MAX_INSTANCES 2
  20. class AP_RPM_Backend;
  21. class AP_RPM
  22. {
  23. friend class AP_RPM_Backend;
  24. public:
  25. AP_RPM();
  26. /* Do not allow copies */
  27. AP_RPM(const AP_RPM &other) = delete;
  28. AP_RPM &operator=(const AP_RPM&) = delete;
  29. // RPM driver types
  30. enum RPM_Type {
  31. RPM_TYPE_NONE = 0,
  32. RPM_TYPE_PX4_PWM = 1,
  33. RPM_TYPE_PIN = 2
  34. };
  35. // The RPM_State structure is filled in by the backend driver
  36. struct RPM_State {
  37. uint8_t instance; // the instance number of this RPM
  38. float rate_rpm; // measured rate in revs per minute
  39. uint32_t last_reading_ms; // time of last reading
  40. float signal_quality; // synthetic quality metric
  41. };
  42. // parameters for each instance
  43. AP_Int8 _type[RPM_MAX_INSTANCES];
  44. AP_Int8 _pin[RPM_MAX_INSTANCES];
  45. AP_Float _scaling[RPM_MAX_INSTANCES];
  46. AP_Float _maximum[RPM_MAX_INSTANCES];
  47. AP_Float _minimum[RPM_MAX_INSTANCES];
  48. AP_Float _quality_min[RPM_MAX_INSTANCES];
  49. static const struct AP_Param::GroupInfo var_info[];
  50. // Return the number of rpm sensor instances
  51. uint8_t num_sensors(void) const {
  52. return num_instances;
  53. }
  54. // detect and initialise any available rpm sensors
  55. void init(void);
  56. // update state of all rpm sensors. Should be called from main loop
  57. void update(void);
  58. /*
  59. return RPM for a sensor. Return -1 if not healthy
  60. */
  61. float get_rpm(uint8_t instance) const {
  62. if (!healthy(instance)) {
  63. return -1;
  64. }
  65. return state[instance].rate_rpm;
  66. }
  67. /*
  68. return signal quality for a sensor.
  69. */
  70. float get_signal_quality(uint8_t instance) const {
  71. return state[instance].signal_quality;
  72. }
  73. bool healthy(uint8_t instance) const;
  74. bool enabled(uint8_t instance) const;
  75. static AP_RPM *get_singleton() { return _singleton; }
  76. private:
  77. static AP_RPM *_singleton;
  78. RPM_State state[RPM_MAX_INSTANCES];
  79. AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
  80. uint8_t num_instances:2;
  81. void detect_instance(uint8_t instance);
  82. };
  83. namespace AP {
  84. AP_RPM *rpm();
  85. };