AP_WheelEncoder.h 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122
  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 WheelEncoder measurement instances available on this platform
  19. #define WHEELENCODER_MAX_INSTANCES 2
  20. #define WHEELENCODER_CPR_DEFAULT 3200 // default encoder counts per full revolution of the wheel
  21. #define WHEELENCODER_RADIUS_DEFAULT 0.05f // default wheel radius of 5cm (0.05m)
  22. class AP_WheelEncoder_Backend;
  23. class AP_WheelEncoder
  24. {
  25. public:
  26. friend class AP_WheelEncoder_Backend;
  27. friend class AP_WheelEncoder_Quadrature;
  28. AP_WheelEncoder(void);
  29. /* Do not allow copies */
  30. AP_WheelEncoder(const AP_WheelEncoder &other) = delete;
  31. AP_WheelEncoder &operator=(const AP_WheelEncoder&) = delete;
  32. // WheelEncoder driver types
  33. enum WheelEncoder_Type : uint8_t {
  34. WheelEncoder_TYPE_NONE = 0,
  35. WheelEncoder_TYPE_QUADRATURE = 1
  36. };
  37. // The WheelEncoder_State structure is filled in by the backend driver
  38. struct WheelEncoder_State {
  39. uint8_t instance; // the instance number of this WheelEncoder
  40. int32_t distance_count; // cumulative number of forward + backwards events received from wheel encoder
  41. float distance; // total distance measured in meters
  42. uint32_t total_count; // total number of successful readings from sensor (used for sensor quality calcs)
  43. uint32_t error_count; // total number of errors reading from sensor (used for sensor quality calcs)
  44. uint32_t last_reading_ms; // time of last reading
  45. int32_t dist_count_change; // distance count change during the last update (used to calculating rate)
  46. uint32_t dt_ms; // time change (in milliseconds) for the previous period (used to calculating rate)
  47. };
  48. // detect and initialise any available rpm sensors
  49. void init(void);
  50. // update state of all sensors. Should be called from main loop
  51. void update(void);
  52. // log data to logger
  53. void Log_Write();
  54. // return the number of wheel encoder sensor instances
  55. uint8_t num_sensors(void) const { return num_instances; }
  56. // return true if healthy
  57. bool healthy(uint8_t instance) const;
  58. // return true if the instance is enabled
  59. bool enabled(uint8_t instance) const;
  60. // get the counts per revolution of the encoder
  61. uint16_t get_counts_per_revolution(uint8_t instance) const;
  62. // get the wheel radius in meters
  63. float get_wheel_radius(uint8_t instance) const;
  64. // return a 3D vector defining the position offset of the center of the wheel in meters relative to the body frame origin
  65. const Vector3f &get_pos_offset(uint8_t instance) const;
  66. // get total delta angle (in radians) measured by the wheel encoder
  67. float get_delta_angle(uint8_t instance) const;
  68. // get the total distance traveled in meters
  69. float get_distance(uint8_t instance) const;
  70. // get the instantaneous rate in radians/second
  71. float get_rate(uint8_t instance) const;
  72. // get the total number of sensor reading from the encoder
  73. uint32_t get_total_count(uint8_t instance) const;
  74. // get the total number of errors reading from the encoder
  75. uint32_t get_error_count(uint8_t instance) const;
  76. // get the signal quality for a sensor (0 = extremely poor quality, 100 = extremely good quality)
  77. float get_signal_quality(uint8_t instance) const;
  78. // get the system time (in milliseconds) of the last update
  79. uint32_t get_last_reading_ms(uint8_t instance) const;
  80. static const struct AP_Param::GroupInfo var_info[];
  81. protected:
  82. // parameters for each instance
  83. AP_Int8 _type[WHEELENCODER_MAX_INSTANCES];
  84. AP_Int16 _counts_per_revolution[WHEELENCODER_MAX_INSTANCES];
  85. AP_Float _wheel_radius[WHEELENCODER_MAX_INSTANCES];
  86. AP_Vector3f _pos_offset[WHEELENCODER_MAX_INSTANCES];
  87. AP_Int8 _pina[WHEELENCODER_MAX_INSTANCES];
  88. AP_Int8 _pinb[WHEELENCODER_MAX_INSTANCES];
  89. WheelEncoder_State state[WHEELENCODER_MAX_INSTANCES];
  90. AP_WheelEncoder_Backend *drivers[WHEELENCODER_MAX_INSTANCES];
  91. uint8_t num_instances;
  92. Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
  93. };