APM:Libraries
WheelEncoder_Quadrature.cpp
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 
16 #include <AP_HAL/AP_HAL.h>
17 
18 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
20 #include <board_config.h>
22 #include <stdio.h>
23 
24 extern const AP_HAL::HAL& hal;
26 
27 // constructor
29  AP_WheelEncoder_Backend(frontend, instance, state)
30 {
31 }
32 
34 {
35  uint8_t instance = _state.instance;
36 
37  // check if pin a has changed and initialise gpio event callback
38  if (last_pin_a != get_pin_a()) {
40 
41  // remove old gpio event callback if present
42  if (irq_state[instance].last_gpio_a != 0) {
43  stm32_gpiosetevent(irq_state[instance].last_gpio_a, false, false, false, nullptr);
44  irq_state[instance].last_gpio_a = 0;
45  }
46 
47  // install interrupt handler on rising or falling edge of gpio for pin a
49  if (irq_state[instance].last_gpio_a != 0) {
50  stm32_gpiosetevent(irq_state[instance].last_gpio_a, true, true, false, _state.instance==0 ? irq_handler0_pina : irq_handler1_pina);
51  }
52 
53  }
54 
55  // check if pin b has changed and initialise gpio event callback
56  if (last_pin_b != get_pin_b()) {
58 
59  // remove old gpio event callback if present
60  if (irq_state[instance].last_gpio_b != 0) {
61  stm32_gpiosetevent(irq_state[instance].last_gpio_b, false, false, false, nullptr);
62  irq_state[instance].last_gpio_b = 0;
63  }
64 
65  // install interrupt handler on rising or falling edge of gpio for pin b
67  if (irq_state[instance].last_gpio_b != 0) {
68  stm32_gpiosetevent(irq_state[instance].last_gpio_b, true, true, false, _state.instance==0 ? irq_handler0_pinb : irq_handler1_pinb);
69  }
70 
71  }
72 
73  // disable interrupts to prevent race with irq_handler
74  irqstate_t istate = irqsave();
75 
76  // copy distance and error count so it is accessible to front end
81 
82  // restore interrupts
83  irqrestore(istate);
84 }
85 
86 // interrupt handler for instance 0, pin a
88 {
89  irq_handler(0, true);
90  return 0;
91 }
92 
93 // interrupt handler for instance 0, pin b
95 {
96  irq_handler(0, false);
97  return 0;
98 }
99 
100 // interrupt handler for instance 1, pin a
102 {
103  irq_handler(1, true);
104  return 0;
105 }
106 
107 // interrupt handler for instance 1, pin b
109 {
110  irq_handler(1, false);
111  return 0;
112 }
113 
114 // get gpio id from pin number
115 uint32_t AP_WheelEncoder_Quadrature::get_gpio(uint8_t pin_number)
116 {
117 #ifdef GPIO_GPIO0_INPUT
118  switch (pin_number) {
119  case 50:
120  return GPIO_GPIO0_INPUT;
121  case 51:
122  return GPIO_GPIO1_INPUT;
123  case 52:
124  return GPIO_GPIO2_INPUT;
125  case 53:
126  return GPIO_GPIO3_INPUT;
127  case 54:
128  return GPIO_GPIO4_INPUT;
129  case 55:
130  return GPIO_GPIO5_INPUT;
131  }
132 #endif
133  return 0;
134 }
135 
136 // convert pin a and pin b state to a wheel encoder phase
137 uint8_t AP_WheelEncoder_Quadrature::pin_ab_to_phase(bool pin_a, bool pin_b)
138 {
139  if (!pin_a) {
140  if (!pin_b) {
141  // A = 0, B = 0
142  return 0;
143  } else {
144  // A = 0, B = 1
145  return 1;
146  }
147  } else {
148  if (!pin_b) {
149  // A = 1, B = 0
150  return 3;
151  } else {
152  // A = 1, B = 1
153  return 2;
154  }
155  }
156  return (uint8_t)pin_a << 1 | (uint8_t)pin_b;
157 }
158 
159 void AP_WheelEncoder_Quadrature::update_phase_and_error_count(bool pin_a_now, bool pin_b_now, uint8_t &phase, int32_t &distance_count, uint32_t &total_count, uint32_t &error_count)
160 {
161  // convert pin state before and after to phases
162  uint8_t phase_after = pin_ab_to_phase(pin_a_now, pin_b_now);
163 
164  // look for invalid changes
165  uint8_t step_forward = phase < 3 ? phase+1 : 0;
166  uint8_t step_back = phase > 0 ? phase-1 : 3;
167  if (phase_after == step_forward) {
168  phase = phase_after;
169  distance_count++;
170  } else if (phase_after == step_back) {
171  phase = phase_after;
172  distance_count--;
173  } else {
174  error_count++;
175  }
176  total_count++;
177 }
178 
179 // combined irq handler
180 void AP_WheelEncoder_Quadrature::irq_handler(uint8_t instance, bool pin_a)
181 {
182  // sanity check
183  if (irq_state[instance].last_gpio_a == 0 || irq_state[instance].last_gpio_b == 0) {
184  return;
185  }
186 
187  // read value of pin-a and pin-b
188  bool pin_a_high = stm32_gpioread(irq_state[instance].last_gpio_a);
189  bool pin_b_high = stm32_gpioread(irq_state[instance].last_gpio_b);
190 
191  // update distance and error counts
192  update_phase_and_error_count(pin_a_high, pin_b_high, irq_state[instance].phase, irq_state[instance].distance_count, irq_state[instance].total_count, irq_state[instance].error_count);
193 
194  // record update time
196 }
197 
198 #endif // CONFIG_HAL_BOARD
static uint32_t get_gpio(uint8_t pin_number)
#define WHEELENCODER_MAX_INSTANCES
AP_WheelEncoder_Quadrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state)
static int irq_handler0_pina(int irq, void *context)
static int irq_handler1_pinb(int irq, void *context)
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
static struct IrqState irq_state[WHEELENCODER_MAX_INSTANCES]
static int irq_handler0_pinb(int irq, void *context)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static void irq_handler(uint8_t instance, bool pin_a)
static uint8_t pin_ab_to_phase(bool pin_a, bool pin_b)
static int irq_handler1_pina(int irq, void *context)
static void update_phase_and_error_count(bool pin_a_now, bool pin_b_now, uint8_t &phase, int32_t &distance_count, uint32_t &total_count, uint32_t &error_count)
AP_WheelEncoder::WheelEncoder_State & _state