AP_WheelEncoder.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333
  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_WheelEncoder.h"
  14. #include "WheelEncoder_Quadrature.h"
  15. #include <AP_Logger/AP_Logger.h>
  16. extern const AP_HAL::HAL& hal;
  17. // table of user settable parameters
  18. const AP_Param::GroupInfo AP_WheelEncoder::var_info[] = {
  19. // @Param: _TYPE
  20. // @DisplayName: WheelEncoder type
  21. // @Description: What type of WheelEncoder is connected
  22. // @Values: 0:None,1:Quadrature
  23. // @User: Standard
  24. AP_GROUPINFO_FLAGS("_TYPE", 0, AP_WheelEncoder, _type[0], 0, AP_PARAM_FLAG_ENABLE),
  25. // @Param: _CPR
  26. // @DisplayName: WheelEncoder counts per revolution
  27. // @Description: WheelEncoder counts per full revolution of the wheel
  28. // @Increment: 1
  29. // @User: Standard
  30. AP_GROUPINFO("_CPR", 1, AP_WheelEncoder, _counts_per_revolution[0], WHEELENCODER_CPR_DEFAULT),
  31. // @Param: _RADIUS
  32. // @DisplayName: Wheel radius
  33. // @Description: Wheel radius
  34. // @Units: m
  35. // @Increment: 0.001
  36. // @User: Standard
  37. AP_GROUPINFO("_RADIUS", 2, AP_WheelEncoder, _wheel_radius[0], WHEELENCODER_RADIUS_DEFAULT),
  38. // @Param: _POS_X
  39. // @DisplayName: Wheel's X position offset
  40. // @Description: X position of the center of the wheel in body frame. Positive X is forward of the origin.
  41. // @Units: m
  42. // @Increment: 0.01
  43. // @User: Standard
  44. // @Param: _POS_Y
  45. // @DisplayName: Wheel's Y position offset
  46. // @Description: Y position of the center of the wheel in body frame. Positive Y is to the right of the origin.
  47. // @Units: m
  48. // @Increment: 0.01
  49. // @User: Standard
  50. // @Param: _POS_Z
  51. // @DisplayName: Wheel's Z position offset
  52. // @Description: Z position of the center of the wheel in body frame. Positive Z is down from the origin.
  53. // @Units: m
  54. // @Increment: 0.01
  55. // @User: Standard
  56. AP_GROUPINFO("_POS", 3, AP_WheelEncoder, _pos_offset[0], 0.0f),
  57. // @Param: _PINA
  58. // @DisplayName: Input Pin A
  59. // @Description: Input Pin A
  60. // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
  61. // @User: Standard
  62. AP_GROUPINFO("_PINA", 4, AP_WheelEncoder, _pina[0], 55),
  63. // @Param: _PINB
  64. // @DisplayName: Input Pin B
  65. // @Description: Input Pin B
  66. // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
  67. // @User: Standard
  68. AP_GROUPINFO("_PINB", 5, AP_WheelEncoder, _pinb[0], 54),
  69. #if WHEELENCODER_MAX_INSTANCES > 1
  70. // @Param: 2_TYPE
  71. // @DisplayName: Second WheelEncoder type
  72. // @Description: What type of WheelEncoder sensor is connected
  73. // @Values: 0:None,1:Quadrature
  74. // @User: Standard
  75. AP_GROUPINFO("2_TYPE", 6, AP_WheelEncoder, _type[1], 0),
  76. // @Param: 2_CPR
  77. // @DisplayName: WheelEncoder 2 counts per revolution
  78. // @Description: WheelEncoder 2 counts per full revolution of the wheel
  79. // @Increment: 1
  80. // @User: Standard
  81. AP_GROUPINFO("2_CPR", 7, AP_WheelEncoder, _counts_per_revolution[1], WHEELENCODER_CPR_DEFAULT),
  82. // @Param: 2_RADIUS
  83. // @DisplayName: Wheel2's radius
  84. // @Description: Wheel2's radius
  85. // @Units: m
  86. // @Increment: 0.001
  87. // @User: Standard
  88. AP_GROUPINFO("2_RADIUS", 8, AP_WheelEncoder, _wheel_radius[1], WHEELENCODER_RADIUS_DEFAULT),
  89. // @Param: 2_POS_X
  90. // @DisplayName: Wheel2's X position offset
  91. // @Description: X position of the center of the second wheel in body frame. Positive X is forward of the origin.
  92. // @Units: m
  93. // @Increment: 0.01
  94. // @User: Standard
  95. // @Param: 2_POS_Y
  96. // @DisplayName: Wheel2's Y position offset
  97. // @Description: Y position of the center of the second wheel in body frame. Positive Y is to the right of the origin.
  98. // @Units: m
  99. // @Increment: 0.01
  100. // @User: Standard
  101. // @Param: 2_POS_Z
  102. // @DisplayName: Wheel2's Z position offset
  103. // @Description: Z position of the center of the second wheel in body frame. Positive Z is down from the origin.
  104. // @Units: m
  105. // @Increment: 0.01
  106. // @User: Standard
  107. AP_GROUPINFO("2_POS", 9, AP_WheelEncoder, _pos_offset[1], 0.0f),
  108. // @Param: 2_PINA
  109. // @DisplayName: Second Encoder Input Pin A
  110. // @Description: Second Encoder Input Pin A
  111. // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
  112. // @User: Standard
  113. AP_GROUPINFO("2_PINA", 10, AP_WheelEncoder, _pina[1], 53),
  114. // @Param: 2_PINB
  115. // @DisplayName: Second Encoder Input Pin B
  116. // @Description: Second Encoder Input Pin B
  117. // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
  118. // @User: Standard
  119. AP_GROUPINFO("2_PINB", 11, AP_WheelEncoder, _pinb[1], 52),
  120. #endif
  121. AP_GROUPEND
  122. };
  123. AP_WheelEncoder::AP_WheelEncoder(void)
  124. {
  125. AP_Param::setup_object_defaults(this, var_info);
  126. }
  127. // initialise the AP_WheelEncoder class.
  128. void AP_WheelEncoder::init(void)
  129. {
  130. if (num_instances != 0) {
  131. // init called a 2nd time?
  132. return;
  133. }
  134. for (uint8_t i=0; i<WHEELENCODER_MAX_INSTANCES; i++) {
  135. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  136. switch ((WheelEncoder_Type)_type[i].get()) {
  137. case WheelEncoder_TYPE_QUADRATURE:
  138. drivers[i] = new AP_WheelEncoder_Quadrature(*this, i, state[i]);
  139. break;
  140. case WheelEncoder_TYPE_NONE:
  141. break;
  142. }
  143. #endif
  144. if (drivers[i] != nullptr) {
  145. // we loaded a driver for this instance, so it must be
  146. // present (although it may not be healthy)
  147. num_instances = i+1; // num_instances is a high-water-mark
  148. }
  149. }
  150. }
  151. // update WheelEncoder state for all instances. This should be called by main loop
  152. void AP_WheelEncoder::update(void)
  153. {
  154. for (uint8_t i=0; i<num_instances; i++) {
  155. if (drivers[i] != nullptr && _type[i] != WheelEncoder_TYPE_NONE) {
  156. drivers[i]->update();
  157. }
  158. }
  159. }
  160. // log wheel encoder information
  161. void AP_WheelEncoder::Log_Write()
  162. {
  163. // return immediately if no wheel encoders are enabled
  164. if (!enabled(0) && !enabled(1)) {
  165. return;
  166. }
  167. struct log_WheelEncoder pkt = {
  168. LOG_PACKET_HEADER_INIT(LOG_WHEELENCODER_MSG),
  169. time_us : AP_HAL::micros64(),
  170. distance_0 : get_distance(0),
  171. quality_0 : (uint8_t)get_signal_quality(0),
  172. distance_1 : get_distance(1),
  173. quality_1 : (uint8_t)get_signal_quality(1),
  174. };
  175. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  176. }
  177. // check if an instance is healthy
  178. bool AP_WheelEncoder::healthy(uint8_t instance) const
  179. {
  180. if (instance >= num_instances) {
  181. return false;
  182. }
  183. return true;
  184. }
  185. // check if an instance is activated
  186. bool AP_WheelEncoder::enabled(uint8_t instance) const
  187. {
  188. if (instance >= num_instances) {
  189. return false;
  190. }
  191. // if no sensor type is selected, the sensor is not activated.
  192. if (_type[instance] == WheelEncoder_TYPE_NONE) {
  193. return false;
  194. }
  195. return true;
  196. }
  197. // get the counts per revolution of the encoder
  198. uint16_t AP_WheelEncoder::get_counts_per_revolution(uint8_t instance) const
  199. {
  200. // for invalid instances return zero vector
  201. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  202. return 0;
  203. }
  204. return (uint16_t)_counts_per_revolution[instance];
  205. }
  206. // get the wheel radius in meters
  207. float AP_WheelEncoder::get_wheel_radius(uint8_t instance) const
  208. {
  209. // for invalid instances return zero vector
  210. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  211. return 0.0f;
  212. }
  213. return _wheel_radius[instance];
  214. }
  215. // return a 3D vector defining the position offset of the center of the wheel in meters relative to the body frame origin
  216. const Vector3f &AP_WheelEncoder::get_pos_offset(uint8_t instance) const
  217. {
  218. // for invalid instances return zero vector
  219. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  220. return pos_offset_zero;
  221. }
  222. return _pos_offset[instance];
  223. }
  224. // get total delta angle (in radians) measured by the wheel encoder
  225. float AP_WheelEncoder::get_delta_angle(uint8_t instance) const
  226. {
  227. // for invalid instances return zero
  228. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  229. return 0.0f;
  230. }
  231. // protect against divide by zero
  232. if (_counts_per_revolution[instance] == 0) {
  233. return 0.0f;
  234. }
  235. return M_2PI * state[instance].distance_count / _counts_per_revolution[instance];
  236. }
  237. // get the total distance traveled in meters
  238. float AP_WheelEncoder::get_distance(uint8_t instance) const
  239. {
  240. // for invalid instances return zero
  241. return get_delta_angle(instance) * _wheel_radius[instance];
  242. }
  243. // get the instantaneous rate in radians/second
  244. float AP_WheelEncoder::get_rate(uint8_t instance) const
  245. {
  246. // for invalid instances return zero
  247. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  248. return 0.0f;
  249. }
  250. // protect against divide by zero
  251. if ((state[instance].dt_ms == 0) || _counts_per_revolution[instance] == 0) {
  252. return 0;
  253. }
  254. // calculate delta_angle (in radians) per second
  255. return M_2PI * (state[instance].dist_count_change / ((float)_counts_per_revolution[instance])) / (state[instance].dt_ms * 1e-3f);
  256. }
  257. // get the total number of sensor reading from the encoder
  258. uint32_t AP_WheelEncoder::get_total_count(uint8_t instance) const
  259. {
  260. // for invalid instances return zero
  261. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  262. return 0;
  263. }
  264. return state[instance].total_count;
  265. }
  266. // get the total distance traveled in meters
  267. uint32_t AP_WheelEncoder::get_error_count(uint8_t instance) const
  268. {
  269. // for invalid instances return zero
  270. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  271. return 0;
  272. }
  273. return state[instance].error_count;
  274. }
  275. // get the signal quality for a sensor
  276. float AP_WheelEncoder::get_signal_quality(uint8_t instance) const
  277. {
  278. // protect against divide by zero
  279. if (state[instance].total_count == 0) {
  280. return 0.0f;
  281. }
  282. return constrain_float((1.0f - ((float)state[instance].error_count / (float)state[instance].total_count)) * 100.0f, 0.0f, 100.0f);
  283. }
  284. // get the system time (in milliseconds) of the last update
  285. uint32_t AP_WheelEncoder::get_last_reading_ms(uint8_t instance) const
  286. {
  287. // for invalid instances return zero
  288. if (instance >= WHEELENCODER_MAX_INSTANCES) {
  289. return 0;
  290. }
  291. return state[instance].last_reading_ms;
  292. }