APM:Libraries
AP_WheelEncoder.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
21 
22 // Maximum number of WheelEncoder measurement instances available on this platform
23 #define WHEELENCODER_MAX_INSTANCES 2
24 #define WHEELENCODER_CPR_DEFAULT 3200 // default encoder counts per full revolution of the wheel
25 #define WHEELENCODER_RADIUS_DEFAULT 0.05f // default wheel radius of 5cm (0.05m)
26 
28 
30 {
31 public:
34 
35  AP_WheelEncoder(void);
36 
37  // WheelEncoder driver types
41  };
42 
43  // The WheelEncoder_State structure is filled in by the backend driver
45  uint8_t instance; // the instance number of this WheelEncoder
46  int32_t distance_count; // cumulative number of forward + backwards events received from wheel encoder
47  float distance; // total distance measured
48  uint32_t total_count; // total number of successful readings from sensor (used for sensor quality calcs)
49  uint32_t error_count; // total number of errors reading from sensor (used for sensor quality calcs)
50  uint32_t last_reading_ms; // time of last reading
51  };
52 
53  // detect and initialise any available rpm sensors
54  void init(void);
55 
56  // update state of all sensors. Should be called from main loop
57  void update(void);
58 
59  // return the number of wheel encoder sensor instances
60  uint8_t num_sensors(void) const { return num_instances; }
61 
62  // return true if healthy
63  bool healthy(uint8_t instance) const;
64 
65  // return true if the instance is enabled
66  bool enabled(uint8_t instance) const;
67 
68  // get the counts per revolution of the encoder
69  uint16_t get_counts_per_revolution(uint8_t instance) const;
70 
71  // get the wheel radius in meters
72  float get_wheel_radius(uint8_t instance) const;
73 
74  // get the position of the wheel associated with the wheel encoder
75  Vector3f get_position(uint8_t instance) const;
76 
77  // get total delta angle (in radians) measured by the wheel encoder
78  float get_delta_angle(uint8_t instance) const;
79 
80  // get the total distance traveled in meters
81  float get_distance(uint8_t instance) const;
82 
83  // get the total number of sensor reading from the encoder
84  uint32_t get_total_count(uint8_t instance) const;
85 
86  // get the total number of errors reading from the encoder
87  uint32_t get_error_count(uint8_t instance) const;
88 
89  // get the signal quality for a sensor (0 = extremely poor quality, 100 = extremely good quality)
90  float get_signal_quality(uint8_t instance) const;
91 
92  // get the system time (in milliseconds) of the last update
93  uint32_t get_last_reading_ms(uint8_t instance) const;
94 
95  static const struct AP_Param::GroupInfo var_info[];
96 
97 protected:
98  // parameters for each instance
105 
108  uint8_t num_instances;
109 };
AP_Int8 _type[WHEELENCODER_MAX_INSTANCES]
WheelEncoder_State state[WHEELENCODER_MAX_INSTANCES]
float get_wheel_radius(uint8_t instance) const
AP_Int8 _pinb[WHEELENCODER_MAX_INSTANCES]
uint32_t get_total_count(uint8_t instance) const
AP_Int16 _counts_per_revolution[WHEELENCODER_MAX_INSTANCES]
uint32_t get_last_reading_ms(uint8_t instance) const
#define WHEELENCODER_MAX_INSTANCES
static const struct AP_Param::GroupInfo var_info[]
A system for managing and storing variables that are of general interest to the system.
uint32_t get_error_count(uint8_t instance) const
float get_distance(uint8_t instance) const
Vector3f get_position(uint8_t instance) const
bool healthy(uint8_t instance) const
bool enabled(uint8_t instance) const
AP_Float _wheel_radius[WHEELENCODER_MAX_INSTANCES]
float get_signal_quality(uint8_t instance) const
uint8_t num_sensors(void) const
Common definitions and utility routines for the ArduPilot libraries.
uint16_t get_counts_per_revolution(uint8_t instance) const
AP_Vector3f _pos_offset[WHEELENCODER_MAX_INSTANCES]
AP_WheelEncoder_Backend * drivers[WHEELENCODER_MAX_INSTANCES]
AP_Int8 _pina[WHEELENCODER_MAX_INSTANCES]
float get_delta_angle(uint8_t instance) const