TI RSLK Library 0.2.2
Loading...
Searching...
No Matches
Functions
Encoder.h File Reference
#include <stdint.h>

Go to the source code of this file.

Functions

void setupEncoder (uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin)
 Initialize the wheel encoder.
 
uint32_t getEncoderLeftCnt ()
 Return number of encoder ticks from the left wheel.
 
uint32_t getEncoderRightCnt ()
 Return number of encoder ticks from the right wheel.
 
void resetLeftEncoderCnt ()
 Set the left encoder tick count to 0.
 
void resetRightEncoderCnt ()
 Set the right encoder tick count to 0.
 
uint8_t getLeftWheelDir ()
 Determines if the left wheel is going forward or backwards.
 
uint8_t getRightWheelDir ()
 Determines if the right wheel is going forward or backwards.
 

Function Documentation

◆ setupEncoder()

void setupEncoder ( uint8_t  ela_pin,
uint8_t  elb_pin,
uint8_t  era_pin,
uint8_t  erb_pin 
)

Initialize the wheel encoder.

Parameters
[in]ela_pinpin number on Launchpad connected to ELA pin on encoder.
[in]elb_pinpin number on Launchpad connected to ELB pin on encoder.
[in]era_pinpin number on Launchpad connected to ERA pin on encoder.
[in]erb_pinpin number on Launchpad connected to ERB pin on encoder.

This function needs to be called before any other encoder function is used.

Definition at line 33 of file Encoder.cpp.