TinyRobotics
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
BrushedMotor< T > Class Template Reference

High-level H-Bridge motor driver class for bidirectional DC motor control. More...

#include <BrushedMotor.h>

Inheritance diagram for BrushedMotor< T >:
Inheritance graph
[legend]
Collaboration diagram for BrushedMotor< T >:
Collaboration graph
[legend]

Public Member Functions

 BrushedMotor (uint8_t id=0)
 Empty constructor for late pin assignment.
 
void setPins (int pin1, int pin2, int pwmFreq=20000)
 Set the pins for the HBridge after construction.
 
bool begin ()
 
void setConstraints (T minSpeed, T maxSpeed)
 
void setReverse (bool reverse)
 Invert the direction logic.
 
bool setValuePercent (T percent) override
 
getValuePercent () const override
 
void end () override
 
bool isPinsSet () const
 Check if the control pins have been set (i.e., not -1).
 
- Public Member Functions inherited from IMotor< T >
virtual bool begin ()=0
 
virtual void end ()=0
 
virtual bool isPinsSet () const =0
 
virtual bool setValuePercent (T percent)=0
 
virtual T getValuePercent () const =0
 
void setID (uint8_t id)
 
uint8_t getID () const
 

Protected Member Functions

bool stop ()
 
void setSpeedValue (float speed)
 

Protected Attributes

int pinIn1 = -1
 
int pinIn2 = -1
 
minSpeed = -255
 
maxSpeed = 255
 
int pwmFreq = 20000
 
bool is_reverse = false
 
lastValuePercent = 0.0f
 
- Protected Attributes inherited from IMotor< T >
uint8_t id = 0
 

Detailed Description

template<typename T = float>
class tinyrobotics::BrushedMotor< T >

High-level H-Bridge motor driver class for bidirectional DC motor control.

This class provides an easy interface for controlling a DC motor using a standard H-Bridge driver (e.g., L298N, L293D, TB6612FNG). It supports:

Usage Example:

HBridge motor(5, 6); // IN1=5, IN2=6,
motor.setConstraints(-200, 200); // Limit speed range
motor.setSpeed(50); // Half speed forward
motor.setSpeed(-50); // Half speed reverse
motor.stop(); // Brake
Note
If your platform does not support analogWriteFreq, the default PWM frequency will be used.

Member Function Documentation

◆ begin()

bool begin ( )
inlinevirtual

Implements IMotor< T >.

◆ end()

void end ( )
inlineoverridevirtual

Stop the motor (brake)

Implements IMotor< T >.

◆ getValuePercent()

T getValuePercent ( ) const
inlineoverridevirtual

Implements IMotor< T >.

◆ isPinsSet()

bool isPinsSet ( ) const
inlinevirtual

Check if the control pins have been set (i.e., not -1).

Implements IMotor< T >.

◆ setConstraints()

void setConstraints ( minSpeed,
maxSpeed 
)
inline

Constrain the speed range to a subset of -255..255. This can be used to limit the maximum speed for safety or to match the characteristics of a specific motor.

◆ setSpeedValue()

void setSpeedValue ( float  speed)
inlineprotected

Set motor speed and direction. Speed: -255 (full reverse) to 255 (full forward)

◆ setValuePercent()

bool setValuePercent ( percent)
inlineoverridevirtual

Set motor speed as a percentage (-100 to 100).

Parameters
percentSpeed percentage: -100 (full reverse) to 100 (full forward)

Implements IMotor< T >.


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