/
Tutorial 04 - Motor encoder

Tutorial 04 - Motor encoder

Objective

The objective of this tutorial is to understand how to connect, using a motor controller, a 12V motor to a CrcDuino. It also shows how to control, in the most basic way, said motor using a quadrature relative encoder (like the one built into goBilda motors). Using an encoder allows to precisely monitor a motor rotation in time.

Wiring schematics and complete presentation

Code

Download the Arduino IDE .ino file:

This is a transcript of the code:

//************************************************************************************************************************** // CrcDuino Tutorial 4 - Basic power motor control using an encoder // Inspired by: https://www.norwegiancreations.com/2017/09/arduino-tutorial-using-millis-instead-of-delay/ // and https://www.norwegiancreations.com/2018/10/arduino-tutorial-avoiding-the-overflow-issue-when-using-millis-and-micros/ // The code below uses the millis() native Arduino function, a command that returns the number of milliseconds since the board started running its current sketch, to measure elapsed time. // NOTE: To simplify code and focus on the encoder use, this version of the code does not cover the case where the BTN_RUN is still pressed when the encoder reaches its position. //************************************************************************************************************************** #include <CrcLib.h> //"Encoder" library by Paul Stoffregen must first be installed via "Arduino Library Manager") // How-to-use https://www.pjrc.com/teensy/td_libs_Encoder.html //#define ENCODER_OPTIMIZE_INTERRUPTS #include <Encoder.h> //Renaming pins with significant names #define MC_1 CRC_PWM_1 #define BTN_RUN CRC_DIG_1 //Motor1 encoder variable: "Encoder" library pre-requisite Encoder motor1Enco(CRC_ENCO_A, CRC_ENCO_B); //This encoder is plugged into these 2 pins on the board //Program execution variable bool motorRotating = LOW; // will allow Motor_1 rotation //Program constants const int STOP_POSITION = 1994; //Found by trial and error to correspond to a 360deg rotation on my setup. Some motor (like the Bilda) have this information in their specs sheets const int MOTOR_SPEED = 13; //127*0.10=13 //************************************************************************************************************************** void setup() { CrcLib::Initialize(); Serial.begin(2000000); //High baud rate for faster printing on screen CrcLib::SetDigitalPinMode(BTN_RUN,INPUT); CrcLib::InitializePwmOutput(MC_1); //Use CrcLib::InitializePwmOutput(MC_1,1); to rapidly reverse this motor rotation direction all over the code //At power-up, establish a known encoder position value // Best practice would be to instead assign a physical limit switch indicating the zero position, and have the robot search // that position itself at sequence start in the void loop() part. This is called "homing". motor1Enco.write(0); } void loop() { CrcLib::Update(); Serial.println(motor1Enco.read()); //Continuously print on screen the motor position if(CrcLib::GetDigitalInput(BTN_RUN) == 0) //Start rotation when button is pressed { motorRotating = HIGH; } if(motorRotating == HIGH && (motor1Enco.read() <= STOP_POSITION) ) //Encoder position not yet reached { CrcLib::SetPwmOutput(MC_1,MOTOR_SPEED); } else { CrcLib::SetPwmOutput(MC_1,0); } }

 

Want smoother, more precise control on a motor position?

This tutorial presents the most basic way to control the position; we run at a fixed rotation speed until the position is reached, and we stop abruptly. It's not really a nice way to do things; inertia will make the rotation stop a little over the desired position, and abrupt stops are not very good for motors.
For example, it's much nicer, when you're in a car approaching a red light, if the driver starts braking ahead of time, gradually reducing the speed until you reach the intersection. Wouldn't it be nice if there was a way for the CrcDuino to know that the motor is getting closer and closer to the desired position, and adjust the speed accordingly to gradually come to a smooth stop? A quite simple, and much documented, way to do so is by incorporating a PID control to your program. Search, as an example, "Arduino PID control position motor" in your favorite search engine to start your exploration of this popular technique.
As a short introduction, such a controller should compare the actual position of the motor (the controlled value) and the desired position (the setpoint). Using mathematical calculations (based on the P, I and D factor values you decide to use), the system will adjust the motor speed (the controlled value) depending on the difference between the two position (the error).

Related content

Tutorials - Intro Page
Tutorials - Intro Page
More like this
Tutorial 02 - Cleanly reproduce the Delay() function
Tutorial 02 - Cleanly reproduce the Delay() function
More like this
English Section - Introduction Page
English Section - Introduction Page
More like this
Tutorial 05 - Sequential program structure
Tutorial 05 - Sequential program structure
Read with this
Tutoriel 04 - Encodeur de moteur
Tutoriel 04 - Encodeur de moteur
More like this
CrcLib: How to access IO pins
CrcLib: How to access IO pins
Read with this