Simon Krogedal / Karbot_wheel_control

Dependencies:   mbed ros_lib_melodic

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers encoder.h Source File

encoder.h

Go to the documentation of this file.
00001 /**
00002  * @file encoder.h
00003  * This class is based upon the QEI class by Aaron Berk and the encoder class I wrote during ESP in 2nd year.
00004  *
00005  * @author Simon Krogedal
00006  *
00007  * @version 0.1
00008  */
00009 
00010 #ifndef KARBOT_ENCODER_H
00011 #define KARBOT_ENCODER_H
00012 
00013 
00014 #include "mbed.h"
00015  
00016  
00017 #define PREV_MASK 0x1 //Mask for the previous state in determining direction
00018 //of rotation.
00019 #define CURR_MASK 0x2 //Mask for the current state in determining direction
00020 //of rotation.
00021 #define INVALID   0x3 //XORing two states where both bits have changed.
00022 
00023 /** encoder Class
00024  *
00025  * Class for measuring quadrature magnetic encoders requiring internal pullups
00026  *
00027  * @author Simon Krogedal
00028  *
00029  * 27/05/2021
00030  *
00031  * Team 9 4th Year project
00032  * 
00033  *
00034  * for NUCLEO-F401RE
00035  * 
00036  * @version 0.2
00037  *
00038  */
00039 class encoder {
00040     
00041     public:
00042     
00043         /** Direction enumerator
00044          */
00045         typedef enum  {
00046             Left,         // Left side motor, CCW rotation is forward
00047             Right         // Right side motor, CW rotation is forward
00048         } Side;
00049     
00050         /** Create an instance
00051          *
00052          * @param chanA Encoder channel A pin
00053          * @param chanB Encoder channel B pin
00054          * @param CPR Encoder clicks per revolution
00055          * @param side Left side or right side motor, defines whether counter-clockwise rotation is forwards (left) or backwards (right) (when looking at the robot from outside)
00056          * @param Period Sampling period of the wheel speed
00057          * @note Too short samling period gives a noisy reading, too long and dynamics are lost
00058          * @param diameter Wheel diameter in meters
00059          */
00060         encoder(PinName chanA, PinName chanB, int CPR, Side side, double Period, double diameter);
00061         
00062         /** Get wheel speed
00063          * @returns Wheel speed in meters/second
00064          */
00065         double getSpeed(void);
00066         
00067         /** Get distance travelled
00068          * @returns Distance travelled in meters
00069          */
00070         double getDistance(void);
00071         
00072         /** Get distance travelled
00073          * @returns Distance travelled in meters since last reset
00074          */
00075         double tempDist(void);
00076         
00077         /// Reset distance measurement
00078         void distRst(void);
00079         
00080         /// Reset distance measurement
00081         void tempRst(void);
00082         
00083         /// Start encoder reading
00084         void start(void);
00085         
00086         /// Stop encoder reading
00087         void reset(void);
00088         
00089         /**
00090          * Read the state of the encoder.
00091          *
00092          * @return The current state of the encoder as a 2-bit number, where:
00093          *         bit 1 = The reading from channel B
00094          *         bit 2 = The reading from channel A
00095          */
00096         int getCurrentState(void);
00097     
00098         /**
00099          * Read the number of pulses recorded by the encoder.
00100          *
00101          * @return Number of pulses which have occured.
00102          */
00103         int getPulses(void);
00104     
00105     private:
00106         int         tot_clicks, temp_tot;   // clicks since last distance reset
00107         double      click_rate, click_store;// clickrate
00108         bool        c_d;                    // left or right bool
00109         
00110         /**
00111          * Update the pulse count.
00112          *
00113          * Called on every rising/falling edge of channels A/B.
00114          *
00115          * Reads the state of the channels and determines whether a pulse forward
00116          * or backward has occured, updating the count appropriately.
00117          */
00118         void encode(void);
00119     
00120         InterruptIn channelA_;
00121         InterruptIn channelB_;
00122     
00123         int          pulsesPerRev_;
00124         int          prevState_;
00125         int          currState_;
00126     
00127         volatile int pulses_;
00128         
00129         Side         side_;
00130 
00131     protected:
00132     
00133         Ticker      sampler;                /// ticker object to sample speed
00134         double      period, enc_const;      /// sampling period and wheel constant
00135         
00136         /// Sample function called by ticker object
00137         void sample_func(void);
00138         
00139         /** Get wheel speed
00140          * @returns Wheel speed in clicks/second
00141          */
00142         double getClicks(void);
00143     
00144 };
00145 
00146 #endif