Emakefun Encoder Motor Arduino Lib 1.1.1
Loading...
Searching...
No Matches
em::EncoderMotor Class Reference

Encoder Motor Class. More...

#include <encoder_motor.h>

Public Types

enum  PhaseRelation : uint8_t { kAPhaseLeads , kBPhaseLeads }
 Used to clarify the phase relationship between phase A and phase B of the encoder when the motor is rotating forward, so that the correct phase relationship can be used in operations such as pulse counting and subsequent speed calculation. More...
 

Public Member Functions

 EncoderMotor (const uint8_t positive_pin, const uint8_t negative_pin, const uint8_t a_pin, const uint8_t b_pin, const uint32_t ppr, const uint32_t reduction_ration, const PhaseRelation phase_relation)
 Constructor for creating an EncoderMotor object.
 
 EncoderMotor (const uint8_t positive_pin, const uint8_t positive_pin_ledc_channel, const uint8_t negative_pin, const uint8_t negative_pin_ledc_channel, const uint8_t a_pin, const uint8_t b_pin, const uint32_t ppr, const uint32_t reduction_ration, const PhaseRelation phase_relation)
 Constructor for creating an EncoderMotor object.
 
void Init ()
 Initialize.
 
void SetSpeedPid (const float p, const float i, const float d)
 Set the parameters of the speed PID controller with the given Proportional (P), Integral (I), and Derivative (D) parameter values.
 
void GetSpeedPid (float *const p, float *const i, float *const d) const
 Get the Proportional (P), Integral (I), and Derivative (D) parameter values of the speed PID controller through pointers.
 
void RunPwmDuty (const int16_t pwm_duty)
 Set motor PWM directly.
 
void RunSpeed (const int16_t speed_rpm)
 Run motor at speed setpoint.
 
void Stop ()
 Stop motor.
 
int64_t EncoderPulseCount () const
 Get encoder pulse count. The count value is incremented by one during forward rotation and decremented by one during reverse rotation, counted at the falling edge of phase A.
 
void ResetPulseCount ()
 Reset the encoder pulse count to 0.
 
int32_t SpeedRpm () const
 Get the current speed of the motor.
 
int16_t PwmDuty () const
 Get the PWM pwm_duty cycle of the motor driver.
 
int32_t TargetRpm () const
 Get the target speed of the motor in RPM.
 

Detailed Description

Encoder Motor Class.

The main functions of this class are as follows:

  1. Supports encoded motors with encoder output signals of A and B phases and a phase difference of 90 degrees between the signal sequences of A and B channels.
  2. Supports driving the motor at a specified speed (RPM) or directly driving the motor with a specified PWM duty cycle.
  3. Supports obtaining the current speed information of the motor in RPM.
  4. Supports obtaining the encoder pulse count value. This count value is updated at the falling edge of phase A, incremented by 1 during forward rotation and decremented by 1 during reverse rotation.
  5. Supports obtaining the PWM duty cycle currently set on the motor driver.
Examples
detect_phase_relation.ino, forward_stop_backward.ino, run_pwm.ino, run_rpm_with_analog_input.ino, and run_speed.ino.

Definition at line 50 of file encoder_motor.h.

Member Enumeration Documentation

◆ PhaseRelation

Used to clarify the phase relationship between phase A and phase B of the encoder when the motor is rotating forward, so that the correct phase relationship can be used in operations such as pulse counting and subsequent speed calculation.

Enumerator
kAPhaseLeads 

Represents the situation where phase A leads phase B when the motor is rotating forward.

kBPhaseLeads 

Represents the situation where phase B leads phase A when the motor is rotating forward.

Definition at line 62 of file encoder_motor.h.

Constructor & Destructor Documentation

◆ EncoderMotor() [1/2]

em::EncoderMotor::EncoderMotor ( const uint8_t positive_pin,
const uint8_t negative_pin,
const uint8_t a_pin,
const uint8_t b_pin,
const uint32_t ppr,
const uint32_t reduction_ration,
const PhaseRelation phase_relation )

Constructor for creating an EncoderMotor object.

Note
This constructor is only valid when the ESP32 Arduino Core version is greater than or equal to 3.0.0. For versions below 3.0.0, please use EncoderMotor(const uint8_t, const uint8_t, const uint8_t, const uint8_t, const uint8_t, const uint8_t, const uint32_t, const uint32_t, const PhaseRelation)
Parameters
[in]positive_pinThe pin number of the motor's positive pole.
[in]negative_pinThe pin number of the motor's negative pole.
[in]a_pinThe pin number of the encoder's A phase.
[in]b_pinThe pin number of the encoder's B phase.
[in]pprPulses per revolution.
[in]reduction_rationReduction ratio.
[in]phase_relationPhase relationship (A phase leads or B phase leads, referring to the situation when the motor is rotating forward), PhaseRelation.

If the user is unsure about the value of the phase_relation parameter for the encoded motor they are using, they can use the example program detect_phase_relation.ino to help detect and determine the value of this parameter.

Definition at line 28 of file encoder_motor.cpp.

◆ EncoderMotor() [2/2]

em::EncoderMotor::EncoderMotor ( const uint8_t positive_pin,
const uint8_t positive_pin_ledc_channel,
const uint8_t negative_pin,
const uint8_t negative_pin_ledc_channel,
const uint8_t a_pin,
const uint8_t b_pin,
const uint32_t ppr,
const uint32_t reduction_ration,
const PhaseRelation phase_relation )

Constructor for creating an EncoderMotor object.

Note
This class will use the LED Control (LEDC) of ESP32 to generate PWM waveforms to driver the motor. When the ESP32 Arduino Core version is less than 3.0.0, the ESP32 Arduino Core will not manage the LEDC channels, and the user needs to specify the LEDC channels corresponding to each pin. Therefore, it is necessary to use this constructor to construct the object and specify the LEDC channels corresponding to the positive and negative pins of the motor. Each pin can only correspond to one LEDC channel, and please do not reuse the LEDC channels. For the description of LEDC, please refer to the official website: https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html
Parameters
[in]positive_pinThe pin number of the motor's positive pole.
[in]positive_pin_ledc_channelThe LED Control (LEDC) channel corresponding to the motor's positive pole pin, which has a total of 16 channels ranging from 0 to 15. Each pin can only correspond to one channel and is used to configure functions such as the PWM (Pulse Width Modulation) signal related to the positive pole pin of the motor. For more details, please refer to the official documentation: https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html
[in]negative_pinThe pin number of the motor's negative pole.
[in]negative_pin_ledc_channelThe LED Control (LEDC) channel corresponding to the motor's negative pole pin, which has a total of 16 channels ranging from 0 to 15. Each pin can only correspond to one channel and is used to configure functions such as the PWM (Pulse Width Modulation) signal related to the negative pole pin of the motor. For more details, please refer to the official documentation: https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html
[in]a_pinThe pin number of the encoder's A phase.
[in]b_pinThe pin number of the encoder's B phase.
[in]pprPulses per revolution.
[in]reduction_rationReduction ratio.
[in]phase_relationPhase relationship (A phase leads or B phase leads, referring to the situation when the motor is rotating forward), PhaseRelation.

If the user is unsure about the value of the phase_relation parameter for the encoded motor they are using, they can use the example program detect_phase_relation.ino to help detect and determine the value of this parameter.

Definition at line 48 of file encoder_motor.cpp.

◆ ~EncoderMotor()

em::EncoderMotor::~EncoderMotor ( )

Definition at line 110 of file encoder_motor.cpp.

Member Function Documentation

◆ EncoderPulseCount()

int64_t em::EncoderMotor::EncoderPulseCount ( ) const

Get encoder pulse count. The count value is incremented by one during forward rotation and decremented by one during reverse rotation, counted at the falling edge of phase A.

Returns
int32_t Encoder pulses.

Definition at line 152 of file encoder_motor.cpp.

◆ GetSpeedPid()

void em::EncoderMotor::GetSpeedPid ( float *const p,
float *const i,
float *const d ) const

Get the Proportional (P), Integral (I), and Derivative (D) parameter values of the speed PID controller through pointers.

Parameters
[out]pPointer used to get the value of the Proportional coefficient (P). After the function is executed, the memory location pointed to by this pointer will store the corresponding parameter value.
[out]iPointer used to get the value of the Integral coefficient (I). After the function is executed, the memory location pointed to by this pointer will store the corresponding parameter value.
[out]dPointer used to get the value of the Derivative coefficient (D). After the function is executed, the memory location pointed to by this pointer will store the corresponding parameter value.

Definition at line 97 of file encoder_motor.cpp.

◆ Init()

void em::EncoderMotor::Init ( )

Initialize.

Definition at line 69 of file encoder_motor.cpp.

◆ PwmDuty()

int16_t em::EncoderMotor::PwmDuty ( ) const

Get the PWM pwm_duty cycle of the motor driver.

Returns
The duty cycle of PWM (the value range is from -1023 to 1023). A positive number represents forward rotation, and a negative number represents reverse rotation.

Definition at line 165 of file encoder_motor.cpp.

◆ ResetPulseCount()

void em::EncoderMotor::ResetPulseCount ( )

Reset the encoder pulse count to 0.

Definition at line 156 of file encoder_motor.cpp.

◆ RunPwmDuty()

void em::EncoderMotor::RunPwmDuty ( const int16_t pwm_duty)

Set motor PWM directly.

Parameters
[in]pwm_dutyThe duty cycle of PWM (the value range is from -1023 to 1023). A positive number represents forward rotation, and a negative number represents reverse rotation.

Definition at line 116 of file encoder_motor.cpp.

◆ RunSpeed()

void em::EncoderMotor::RunSpeed ( const int16_t speed_rpm)

Run motor at speed setpoint.

Parameters
[in]speed_rpmSpeed setpoint(RPM).

Definition at line 128 of file encoder_motor.cpp.

◆ SetSpeedPid()

void em::EncoderMotor::SetSpeedPid ( const float p,
const float i,
const float d )

Set the parameters of the speed PID controller with the given Proportional (P), Integral (I), and Derivative (D) parameter values.

Parameters
[in]pThe value of the Proportional coefficient (P).
[in]iThe value of the Integral coefficient (I).
[in]dThe value of the Derivative coefficient (D).

Definition at line 84 of file encoder_motor.cpp.

◆ SpeedRpm()

int32_t em::EncoderMotor::SpeedRpm ( ) const

Get the current speed of the motor.

Returns
The current speed of the motor in RPM.

Definition at line 160 of file encoder_motor.cpp.

◆ Stop()

void em::EncoderMotor::Stop ( )

Stop motor.

Definition at line 144 of file encoder_motor.cpp.

◆ TargetRpm()

int32_t em::EncoderMotor::TargetRpm ( ) const

Get the target speed of the motor in RPM.

Returns
The target speed of the motor in RPM.

Definition at line 170 of file encoder_motor.cpp.


The documentation for this class was generated from the following files: