Obsługa enkodera inkrementalnego

Kolejny artykuł z serii sterowania napędami będzie opisywał czujniki obrotu jakimi są enkodery inkrementalne. W materiale postaram się przedstawić budowę i zasadę działania enkodera z czujnikami Halla oraz implementację odczytu sygnałów na zestawie Nucelo-L476RG.

Jest to drugi artykuł z serii. Jeżeli jeszcze nie zapoznałeś się z poradnikiem „Sterowanie silnikiem DC”, zachęcam do tego przed przeczytaniem poniższego tekstu. Artykuł będzie bazował na opisanym tam sterowaniu oraz wykorzystywał zastosowane w nim podzespoły: silnik Micro Pololu, moduł ze sterownikiem DRV8835 oraz płytkę Nucelo-L476RG.

Enkoder inkrementalny

Enkoder to rodzaj czujnika obrotu, który generuje sygnał elektryczny na podstawie ruchu obrotowego elementu mechanicznego. Enkoder daje informację zwrotną do układu sterowania, na podstawie której możemy zmierzyć takie wielkości, jak kąt i ilość obrotów wału silnika, prędkość obrotową oraz kierunek obrotu.

Podstawowy podział zakłada dwa rodzaje enkoderów:

  • inkrementalny – generuje dwa sygnały (A i B) przesunięte w fazie o 90o, a zliczane impulsy odpowiadają ruchowi obrotowemu. Enkoder ma określoną rozdzielczość, która informuje o tym, ile impulsów na jeden obrót generuje czujnik. Przesunięcie sygnałów w fazie pozwala natomiast na odczyt kierunku obrotu. Po zaniku zasilania informacja o kącie obrotu jest tracona, a wartość położenia naliczana jest od zera. Enkodery inkrementalne dzielimy na:
    • magnetyczne – czujnik wykorzystuje tarczę generującą pole magnetyczne oraz czujniki Halla
    • optyczne – czujnik wykorzystuje tarczę z polami przezroczystymi i nieprzezroczystymi oraz czujnik optyczny (diodę emitującą światło, które zatrzymuje się na polach nieprzezroczystych, a przechodzi przez pola przezroczyste i odbiornik przekształcający światło w sygnał elektryczny)
  • absolutny – do każdej wartości kąta przyporządkowana jest kodowana wartość liczbowa. Na tarczy enkodera umieszczony jest kod, który pozwala na odczyt aktualnej pozycji, dzięki czemu nie tracimy informacji po zaniku zasilania. Enkodery absolutne wykorzystują do kodowania liczb kod binarny lub kod Gray’a.

W artykule wykorzystamy enkoder inkrementalny z czujnikami Halla firmy Pololu.

Moduł jest przystosowany do współpracy z silnikami z serii Micro Pololu. Wykorzystuje dwa czujniki Halla w obudowie SOT-23 oraz tarczę magnetyczną o 6 polach (co oznacza, że każdy czujnik będzie generował 3 impulsy na obrót). Na płytce umieszczono dwa otwory do przylutowania styków silnika oraz złącze JST SH o rastrze 1.0 mm.

Jak wspomniałem wcześniej, czujnik inkrementalny generuje dwa sygnały prostokątne przesunięte w fazie o 90o. Jeżeli sygnał A pojawi się prze sygnałem B, oznacza to, że obrót następuje w jednym kierunku, natomiast jeżeli sygnał B pojawi się przed sygnałem A, oznacza to obrót w drugi kierunku. Zmiana położenia wału silnika jest obliczana na podstawie ilości impulsów generowanych przez wyjścia. Warto zauważyć, że na każdy obrót tarczy enkodera przypada tyle samo impulsów na kanale A, jak i na kanale B.

Złącze na płytce enkodera, którego użyjemy w ćwiczeniu, ma 6 wyjść.

WyjściaOpis
GNDmasa zasilania
OUT Bwyjście B enkodera
OUT Awyjście A enkodera
VCCzasilanie enkodera w zakresie od 2,7 V do 18 V
M2wyjście B silnika
M1wyjścia A silnika

Do pinów M1 i M2 podłączamy wyjście ze sterownika silników, VCC i GND zasilanie enkodera, a OUT A i OUT B podłączamy do mikrokontrolera obsługującego odczyt sygnałów.

Tryb „Encoder Mode”

Opisany wyżej enkoder wykorzystamy do odczytu prędkości obrotowej silnika micro Pololu. W projekcie wykorzystamy moduł ze sterownikiem DRV8835 oraz zestaw Nucelo-L476RG.

Pierwszym etapem jest zaimplementowanie odczytu sygnałów enkodera (OUT A oraz OUT B) w taki sposób, aby mikrokontroler zliczał nam impulsy oraz analizował kierunek obrotu silnika. Moglibyśmy wykorzystać tutaj np. przerwania od wejść cyfrowych i analizować ich stan przy każdym wystąpieniu impulsu. Na tej podstawie określilibyśmy zarówno kąt obrotu tarczy enkodera, jak i jego kierunek. Układy STM32 oferują jednak bardzo wygodne rozwiązanie, które zrobi to wszystko za nas, a na wyjściu otrzymamy gotowe impulsy wraz z kierunkiem. Jest to możliwe dzięki funkcji TIMER-a, jaką jest tryb „Encoder Mode”.

Na wstępie zapoznajmy się z zasadą działania tego trybu. Niezbędne informacje możemy znaleźć oczywiście w dokumentacji układu, a konkretnie w „Reference Manual-u” naszego uC na stronie 1047. Jak działa tryb Encoder mode? TIMER w tym trybie wykorzystuje dwa wejścia mikrokontrolera, do którego podłączamy sygnały z enkodera. Pracę TIMER-a możemy skonfigurować tak, aby reagował na impulsy z pierwszego kanału (TI1), drugiego kanału (TI2) lub obu kanałów jednocześnie (TI1 and TI2). Od tego, jak skonfigurujemy tryb Encoder Mode będzie zależało, o ile wartość licznika TIMER-a będzie inkrementowana w trakcie obrotu tarczy enkodera. Dokładne informacje znajdziemy w tabeli poniżej.

Jak widzimy, w przypadku konfiguracji w trybie „TI1” lub „TI2”, mikrokontroler będzie zliczał impulsy tylko z danego kanału reagując na oba zbocza, czyli po wystąpieniu każdego impulsu wartość licznika zmieni się o 2. W przypadku konfiguracji w trybie „TI1 and TI2”, zliczane będą impulsy z obu kanałów, a wartość licznika będzie zmieniała się o 4. Niezależnie od tego, jaki tryb pracy wybierzemy, podłączone muszą być oba kanały, ponieważ dopiero na podstawie przesunięcia impulsów względem siebie na obu kanałach TIMER jest w stanie określić kierunek obrotu.

Teraz przeanalizujmy, jak TIMER odczytuje dane z enkodera i jaką informację nam dostarcza. W przejrzysty sposób zostało to przedstawione na poniższym wykresie dostępnym w dokumentacji. Przedstawia on pracę TIMER-a w trybie „Encoder Mode TI1 and TI2„.

Możemy zauważyć, że przy każdym zboczu układ analizuje stan na drugim kanale. Jeżeli na wejściu TI1 pojawi się zbocze narastające, a na wejściu TI2 mamy stan niski, licznik jest zwiększany. Podobnie licznik reaguje, jeśli przy zboczu opadającym na TI1 stan TI2 jest wysoki. Licznik jest zwiększany także, jeśli przy zboczu narastającym TI2 na TI1 jest stan wysoki oraz przy zboczu opadającym TI2 na TI1 jest stan niski. Możemy to zaobserwować na samym początku wykresu. Jak pisałem wcześniej, obrót generujący po jednym impulsie na każdym z kanałów zwiększa licznik TIMER-a o 4. Odwrotnie reaguje układ na pozostałe przypadki, kiedy przy zboczu narastającym TI1 i stanie wysokim TI2, opadającym TI1 i stanie niskim TI2 oraz przy zboczu narastającym TI2 i stanie niskim TI1, opadającym TI2 i stanie wysokim TI1 wartość licznika będzie zmniejszana. W ten sposób odczytując rejestr licznika mamy gotową informację o zliczonych impulsach. Kierunek obrotu możemy otrzymać na podstawie danych z bitu DIR w rejestrze CR1 układu czasowego.

Warto zaznaczyć, że nie każdy TIMER dostępny w mikrokontrolerze posiada tryb „Encoder Mode” Zawsze przed podłączeniem układu należy sprawdzić, czy wejścia, które wybraliśmy, oferują taką funkcjonalność.

Implementacja

Przejdźmy teraz do konfiguracji projektu i odpowiednich układów peryferyjnych mikrokontrolera. Projekt zaimplementujemy w środowisku STM32CubeIDE. Jeżeli nie używałeś jeszcze tego narzędzia, zachęcam do zapoznania się z moim poradnikiem „STM32CubeIDE – pierwszy projekt„.

Tworzymy zatem nowy projekt wybierając „File->New->STM32 Project”. Przechodzimy przez wstępną konfigurację projektu i zabieramy się za konfigurację wyjść mikrokontrolera. Ja wygenerowałem projekt z domyślną konfiguracją dla płytki Nucleo, dlatego zegary i część pinów mam już skonfigurowane. Żeby odczytać sygnały z enkodera musimy najpierw uruchomić silnik. Poniżej przedstawiam tylko pobieżnie konfigurację mikrokontrolera do sterowania silnikiem DC i sterownikiem DRV8835. Dokładny opis dostępny jest w pierwszej części poradnika „Sterowanie silnikiem DC”.

Do sterowania w trybie PHASE/ENABLE będziemy potrzebowali trzech wyjść: dwóch wyjść cyfrowych (do sterowanie pinem MODE oraz pinem PHASE) oraz wyjścia PWM. Wykorzystamy piny PA8 i PA9 jako wyjścia GPIO oraz pin PB10 jako wyjście PWM (TIMER 2, kanał 3). Przypiszemy im również etykiety zgodnie z ilustracją poniżej, co ułatwi nam pracę z kodem.

Następnie ustawiamy parametry pracy TIMER 2 tak, aby na wyjściu generowany sygnał PWM miał częstotliwość 20 kHz, a prędkością będziemy mogli sterować z rozdzielczością 100.

Do obsługi enkodera wykorzystamy TIMER 3. Aby go skonfigurować, wybieramy TIMER 3 w trybie „Combined Channels -> Encoder Mode”.

Następnie przechodzimy do konfiguracji parametrów TIMER-a. Żeby tryb „Encoder mode” pracował poprawnie, musimy ustawić:

  • Prescaler – dzielnik zegara, wartość 16-bitowa, należy pamiętać, że wpisujemy tutaj wartość, jaką chcemy osiągnąć pomniejszoną o 1, czyli np. dla 100 wpisujemy 99 (wynika to z faktu, że w momencie kasowania zawartości rejestru przeskakuje nam dodatkowy takt zegara, bo liczmy od 0 – szczegóły w „Reference Manual” na stronie 1077)
  • Counter Mode – tryb zliczania: w górę (Up) lub w dół (Down), określa, czy licznik będzie zwiększał się wraz z obrotem enkodera w danym kierunku, czy zmniejszał
  • Counter Period (AutoReload Register) – wartość, do jakiej (w tybie Up) lub od jakiej (w trybie Down) nasz licznik będzie liczył
  • Encoder Mode – określa, czy układ będzie zliczał impulsy z pierwszego kanału (TI1), drugiego kanału (TI2) lub obu kanałów jednocześnie (TI1 and TI2)
  • Polarity – określa, na które zbocze reaguje TIMER, w przypadku „Encoder Mode” i tak zawsze mamy reakcję na oba zbocza impulsu
  • Input Filter – określa długość próbkowania wejść sygnałów przed aktualizacją stanu licznika, pomaga wyeliminować np. efekt drgania styków w przypadku mniej dokładnych enkoderów

W przypadku trybu „Encoder Mode”, dzielenie zegara nie będzie nam potrzebne, dlatego wartość Prescaler-a ustawiamy na 0. Counter Period, czy wartość do jakiej będzie zliczał TIMER zostawimy na wartości maksymalnej. Przy odczycie prędkości będziemy samodzielnie resetowali licznik. Dodatkowo chcemy, aby układ reagował na impulsy z obu kanałów, zatem ustawiamy tryb „Encoder Mode TI1 and TI2” oraz Polarity jako „Rising Edge”. Wykorzystamy najwyższy poziom filtracji, zatem „Input Filter” ustawimy na 15.

Wybierając tryb „Encoder Mode” na pinach PA6 oraz PA7 naszego mikrokontrolera pojawiły się wyjścia TIM3_CH1 i TIM3_CH2 (jeżeli Tobie wejścia ustawiły się na innych pinach, możesz to zmienić klikając przycisk Ctrl + lewy przycisk myszy na pinie TIM3_CH1/TIM_3_CH2 i przenieść je na PA6 i PA7). Możemy też ustawić etykiety na pinach (prawy przycisk myszy + Enter User Label) – OUT_A i OUT_B.

Pomiar prędkości obrotowej silnika chcemy zrealizować w ten sposób, że co określony odcinek czasu (w naszym przypadku co 100 ms) odczytamy wartość zliczoną przez TIMER 3 pracujący w trybie „Encoder Mode” i odpowiednio przeliczymy ją na prędkość obrotową silnika. Potrzebujemy zatem jeszcze jednego TIMER-a, który będzie generował nam przerwanie z częstotliwością 10 Hz. Do tego celu użyjemy dodatkowego TIMER-a. W takim przypadku, gdzie nie potrzebujemy żadnych wejść ani wyjść, a jedynie precyzyjnego zliczania czasu, najlepiej sprawdzi się bazowy TIMER bez dodatkowych funkcjonalności. Dzięki temu nie będziemy niepotrzebnie wykorzystywać bardziej zaawansowanego układu zliczającego, który może nam się przydać do innych celów. W STM32L476RG mamy do dyspozycji dwa takie TIMER-y: TIMER 6 i TIMER 7. W dzisiejszym projekcie wykorzystamy TIMER 6.

Zgodnie z dokumentacją (Datasheet) mikrokontrolera na stronie 17, TIM6 podłączony jest do szyny taktującej APB1 i zgodnie z konfiguracją zegara, taktowany będzie z częstotliwością 80 MHz.

Zgodnie ze wzorem:

TIM_Freq = APB1_Freq / (Prescaler * Counter Period )

Aby uzyskać częstotliwość 10 Hz musimy podzielić zegar przez 8 000 000. Biorąc pod uwagę maksymalne wartości, jakie możemy wpisać do ustawień Prescaler i Counter Period, konfiguracja TIMER 6 będzie wyglądała następująco:

Dodatkowo w zakładce NVIC Settings ustawiamy przerwania od TIM6.

Tak skonfigurowany projekt powinien pozwolić nam zrealizować postawione zadanie. Możemy wygenerować projekt („Project->Generate Code” lub „Alt+K„) i przejść do napisania kodu programu do obsługi enkodera inkrementalnego.

Tworzymy dwa pliki do obsługi silnika: motor.c (w folderze Core->Src) oraz motor.h (w folderze Core->Inc), które będą stanowiły naszą bibliotekę z funkcjami obsługującymi właściwą analizę sygnałów z enkodera.

W pierwszej kolejności w pliku motor.h stworzymy strukturę typu motor_str, która będzie zawierała najważniejsze parametry obsługi enkodera.

typedef struct
{
	TIM_HandleTypeDef *timer;	//timer obsługujący enkoder silnika

	uint16_t resolution;		//rozdzielczość silnika

	int32_t pulse_count;		//zliczone impulsy
	int32_t speed;			//obliczona prędkość silnika
}motor_str;

Następnie zdefiniujemy sobie kilka stałych, które pomogą nam w obliczeniach prędkości obrotowej. Jak opisywałem wcześniej, zastosowany przeze mnie enkoder ma 6 pól, co oznacza że będzie generował 3 impulsy na obrót na każdym kanale (rozdzielczość enkodera). Ustawienie trybu „Encoder Mode TI1 and TI2” powoduje, że uC reaguje na oba zbocza na dwóch kanałach, licznik przy jednym przejściu enkodera zwiększy się o 4 (stała TIMER_CONF_BOTH_EDGE_T1T2). Zastosowany silnik ma przekładnię150:1. Bierzemy to pod uwagę, ponieważ zależy nam na obliczaniu prędkości obrotowej na wale wyjściowym silnika za przekładnią, gdzie będzie podłączone koło robota. Dodatkowo tworzymy dwie stałe określające częstotliwość TIMER-a bazowego (TIM6) oraz ilość sekund w minucie, ponieważ najczęściej prędkość obrotową silnika podajemy w obrotach na minutę.

#define ENCODER_RESOLUTION			3
#define TIMER_CONF_BOTH_EDGE_T1T2	        4
#define MOTOR_GEAR				150

#define	TIMER_FREQENCY				10
#define	SECOND_IN_MINUTE			60

Teraz tworzymy funkcję inicjalizującą zmienne struktury silnika:

void motor_str_init(motor_str *m, TIM_HandleTypeDef *tim)
{
	m->timer = tim;
	m->resolution = ENCODER_RESOLUTION * TIMER_CONF_BOTH_EDGE_T1T2 * MOTOR_GEAR;

	m->pulse_count = 0;
	m->speed = 0;
}

Jak widzimy, rozdzielczość, czyli ilość impulsów na jeden obrót wału silnika będzie iloczynem trzech wartości: rozdzielczości enkodera, stałej 4 definiującej wartość, o jaką zwiększy się licznik w trybie TI1TI2 oraz przekładni silnika.

Następnie definiujemy funkcję odpowiedzialną za obliczenia prędkości obrotowej w obrotach na minutę , którą wywołamy w przerwaniu od TIMER 6.

void motor_calculate_speed(motor_str *m)
{
	motor_update_count(m);
	m->speed = (m->pulse_count * TIMER_FREQENCY * SECOND_IN_MINUTE) / m->resolution;
}

Wewnątrz funkcji motor_calculate_speed wywołujemy jeszcze jedną funkcję, która aktualizuje nam wartość licznika pulse_count. W funkcji odczytujemy wartość licznika TIM3, która określa ilość zliczonych impulsów.

void motor_update_count(motor_str *m)
{
	m->pulse_count = (int16_t)__HAL_TIM_GET_COUNTER(m->timer);
	__HAL_TIM_SET_COUNTER(m->timer, 0);
}

Ważną rzeczą jest tutaj rzutowanie odczytanych danych na int16, ponieważ pozwala nam to wyeliminować problem ujemnych wartości. Normalnie w rejestrze licznika po zliczeniu 100 impulsów pojawia nam się wartość 100 w przypadku zliczania w górę i 65435, gdy obrót jest w przeciwną stronę i TIMER zlicza w dół. Wartość 65435 jest problematyczna w dalszej obróbce bo nie odnosi się w żaden sposób do zliczonej ilości impulsów. Rzutowanie na int16 sprawia, że zamiast 65435 otrzymujemy wartość -100, co daje nam jednocześnie informację o zliczonych impulsach oraz o kierunku obrotu.

Funkcję motor_calculate_speed chcemy wywoływać w przerwaniu od TIM6. W pliku main.c w sekcji USER CODE BEGIN 4 umieszczamy Callback do obsługi przerwania.

/* USER CODE BEGIN 4 */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
	if(htim->Instance == TIM6)
	{
		motor_calculate_speed(&motorA);
	}
}
/* USER CODE END 4 */

W pliku main.c przed funkcją main() jako zmienną globalna deklarujemy:

/* USER CODE BEGIN 0 */
motor_str motorA;
/* USER CODE END 0 */

W funkcji main() po inicjalizacji układów peryferyjnych mikrokontrolera wywołujemy inicjalizację struktury silnika oraz uruchamiamy tryb „Encoder Mode” i przerwania od TIMER 6.

motor_str_init(&motorA, &htim3);
HAL_TIM_Encoder_Start(&htim3, TIM_CHANNEL_ALL);
HAL_TIM_Base_Start_IT(&htim6);

Do projektu dodajemy też pliki „drv8835.h” i „drv8835.c” do sterowania silnikiem, które opisane są szczegółowo w pierwszej części poradnika „Sterowanie silnikiem DC”. Wywołujemy funkcję drv8835_init() i wrzucamy do pętli while(1) sterowanie prędkością silnika podobnie, jak w poprzednim artykule. Dodajemy małą modyfikację – w momencie osiągnięcia maksymalnej wartości wypełnienia PWM, czekamy ze zmianą wypełnienia 2 s, aby lepiej zaobserwować maksymalną prędkość na wykresie. Funkcja main() będzie wyglądała następująco:

int main(void)
{
  /* USER CODE BEGIN 1 */

  /* USER CODE END 1 */

  /* MCU Configuration--------------------------------------------------------*/

  /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
  HAL_Init();

  /* USER CODE BEGIN Init */

  /* USER CODE END Init */

  /* Configure the system clock */
  SystemClock_Config();

  /* USER CODE BEGIN SysInit */

  /* USER CODE END SysInit */

  /* Initialize all configured peripherals */
  MX_GPIO_Init();
  MX_USART2_UART_Init();
  MX_TIM3_Init();
  MX_TIM2_Init();
  MX_TIM6_Init();
  /* USER CODE BEGIN 2 */
  drv8835_init();
  motor_str_init(&motorA, &htim3);
  HAL_TIM_Encoder_Start(&htim3, TIM_CHANNEL_ALL);
  HAL_TIM_Base_Start_IT(&htim6);

  int pwm = 0, dir = CCW, inc_dec = 1;
  uint32_t time_tick = HAL_GetTick();
  uint32_t max_time = 20;

  drv8835_set_motorA_direction(dir);
  drv8835_set_motorA_speed(pwm);
  /* USER CODE END 2 */

  /* Infinite loop */
  /* USER CODE BEGIN WHILE */
  while (1)
  {
	  if((HAL_GetTick() - time_tick) > max_time )
	  {
                  time_tick = HAL_GetTick();

		  pwm += inc_dec;
		  drv8835_set_motorA_speed(pwm);

		  if(pwm >= 100)
		  {
			  inc_dec = -1;
			  max_time = 2000;
		  }
		  else if(pwm <= 0)
		  {
			  inc_dec = 1;

			  if(dir == CCW)
				  dir = CW;
			  else if(dir == CW)
				  dir = CCW;

			  drv8835_set_motorA_direction(dir);
		  }
		  else
		  {
			  max_time = 20;
		  }
	  }

    /* USER CODE END WHILE */

    /* USER CODE BEGIN 3 */
  }
  /* USER CODE END 3 */
}

Na koniec dodamy jeszcze nagłówek „drv8835.h” i „motor.h” w pliku main.h, aby nasze biblioteki były widoczne w pliku main.c.

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "drv8835.h"
#include "motor.h"
/* USER CODE END Includes */

Przed uruchomieniem projektu powinniśmy jeszcze połączyć sterownik i enkoder z zestawem Nucleo i podłączyć silnik. Robimy to według poniższego schematu.

Teraz możemy skompilować kod (Project->Build Project) i go uruchomić (Run->Run). Jeżeli masz jeszcze problem z obsługą tych funkcji środowiska, zachęcam do zapoznania się z moim poradnikiem „STM32CubeIDE – pierwszy projekt„.

Dla sprawdzenia działania napisanego programu warto byłoby podejrzeć, jak zmienia się prędkość w trakcie działa programu oraz jakie wartości przyjmuje. Do tego celu znakomitym narzędziem jest STM32CubeMonitor. Jest to dość rozubudowany program do akwizycji danych. Dzisiaj przedstawię tylko prostą konfigurację prowadzącą do ustawienia podglądu zmiennej z impulsami oraz prędkością obrotową. Więcej o tym programie na pewno pojawi się w przyszłych artykułach.

Po uruchomieniu programu otrzymujemy ekran startowy. Tworzymy schemat przepływu danych analogicznie to przedstawionego poniżej. Do prezentacji danych wybieramy obiekt „chart”, czyli wykres liniowy.

Następnie konfigurujemy zmienne, jakie chcemy wyświetlić. Klikamy dwa razy w pole „myVariables” i ustawiamy plik „Executable” klikając podając ścieżkę i plik „*.elf”. Wybieramy zmienne motorA.pulse_count oraz motorA.speed. Następnie w polu „my_Probe_Out” i „myProbe_In” ustawiamy nasz programator. Zatwierdzamy wszystko przyciskiem „Deploy” i otwieramy klikając w „Dashboard”.

Po wgraniu programu na płytkę Nucleo możemy uruchomić akwizycję danych (należy pamiętać, że STM32CubeIDE i STM32CubeMonitor korzystając z tego samego programatora i nie mogą robić tego jednocześnie).

Efekt działania został przedstawiony na wykresie poniżej. Jak możemy zauważyć, prędkość obrotowa osiąga maksymalnie ok. 208 obrotów na minutę, co pokrywa się z wartością 210 obrotów na minutę deklarowaną przez producenta silnika (dla napędu z przekładnią 150:1).

Efekt działania programu wraz z odczytem danych w STM32CubeMonitor przedstawia poniższy film.

Podsumowanie

W tym poradniku zapoznaliśmy się z budową i zasadą działania enkodera inkrementalnego. Jest to najczęściej stosowany czujnik obrotu w robotyce, który umożliwia odczyt prędkości obrotowej silnika, ale także pomiar odległości przebytej przez robota. Jest to bardzo użyteczna informacja niezbędna w takich algorytmach, jak poruszanie się robota po planszy czy mapowanie otoczenia.

Do pobrania

Repozytorium GitHub

Dodaj komentarz

Twój adres e-mail nie zostanie opublikowany. Wymagane pola są oznaczone *