satnogs-rotator-firmware
Loading...
Searching...
No Matches
motor Class Reference

Class that functions for interacting with a Motor Driver Carrier. More...

#include <motor.h>

Public Member Functions

 motor (uint8_t pwm_pin1, uint8_t pwm_pin2, uint8_t fb_pin, uint8_t en_pin, uint8_t sf_pin, uint16_t maxSpeed, uint16_t minSpeed)
 
void init_pin ()
 Initialize pins of DC motor driver.
 
void init_timer (uint8_t timer, uint16_t divisor)
 Set timer frequency, for timers 0, 1, 2.
 
void enable ()
 Enable motor driver.
 
void disenable ()
 Disable motor driver.
 
uint16_t get_load ()
 Calculate the load of DC motor.
 
uint8_t get_fault ()
 Get the status flag of motor driver.
 
void move (int16_t speed)
 Move the DC motor with constant voltage (~speed)
 
void stop ()
 Stop moving the DC motor.
 
void set_min (uint16_t min)
 Update the minimum speed of DC motor.
 
void set_max (uint16_t max)
 Update the maximum speed of DC motor.
 

Private Attributes

uint8_t _pwm_pin1
 
uint8_t _pwm_pin2
 
uint8_t _fb_pin
 
uint8_t _en_pin
 
uint8_t _sf_pin
 
int16_t _maxSpeed
 
int16_t _minSpeed
 

Detailed Description

Class that functions for interacting with a Motor Driver Carrier.

Parameters
pwm_pin1PWM pin, regulate the duty cycle
pwm_pin2PWM pin, regulate the duty cycle
fb_pinAnalog pin that measure the analog current-sense feedback
en_pinDigital pin that enable and disable the motor driver
sf_pinDigital pin that read if the motor driver works properly or not
maxSpeedSet the maximum PWM value that the DC motor can handle, e.g. max 255 (8 bit timer)
minSpeedSet the minimum PWM value that the DC motor can handle, e.g. min 5 (8-bit timer)

Definition at line 37 of file motor.h.

Constructor & Destructor Documentation

◆ motor()

motor::motor ( uint8_t pwm_pin1,
uint8_t pwm_pin2,
uint8_t fb_pin,
uint8_t en_pin,
uint8_t sf_pin,
uint16_t maxSpeed,
uint16_t minSpeed )
inline

Definition at line 40 of file motor.h.

References _en_pin, _fb_pin, _maxSpeed, _minSpeed, _pwm_pin1, _pwm_pin2, _sf_pin, and stop().

Here is the call graph for this function:

Member Function Documentation

◆ disenable()

void motor::disenable ( )
inline

Disable motor driver.

Definition at line 157 of file motor.h.

References _en_pin.

Referenced by loop().

◆ enable()

void motor::enable ( )
inline

Enable motor driver.

Definition at line 148 of file motor.h.

References _en_pin.

Referenced by setup().

◆ get_fault()

uint8_t motor::get_fault ( )
inline

Get the status flag of motor driver.

Returns
HIGH the motor driver is working properly LOW an over-current (short circuit) or over-temperature event

Definition at line 178 of file motor.h.

References _sf_pin.

Referenced by loop().

◆ get_load()

uint16_t motor::get_load ( )
inline

Calculate the load of DC motor.

Returns
Return an analog read value 0-1023

Definition at line 167 of file motor.h.

References _fb_pin.

◆ init_pin()

void motor::init_pin ( )
inline

Initialize pins of DC motor driver.

Definition at line 57 of file motor.h.

References _en_pin, _fb_pin, _pwm_pin1, _pwm_pin2, and _sf_pin.

Referenced by setup().

◆ init_timer()

void motor::init_timer ( uint8_t timer,
uint16_t divisor )
inline

Set timer frequency, for timers 0, 1, 2.

Parameters
timerPWM frequency for D5 & D6, set timer 0 PWM frequency for D9 & D10, set timer 1 PWM frequency for D3 & D11, set timer 2
divisorFor timer 0 divisor to 1 for PWM frequency of 62500.00 Hz divisor to 8 for PWM frequency of 7812.50 Hz divisor to 64 for PWM frequency of 976.56 Hz (The DEFAULT) divisor to 256 for PWM frequency of 244.14 Hz divisor to 1024 for PWM frequency of 61.04 Hz For timer 1 divisor to 1 for PWM frequency of 31372.55 Hz divisor to 8 for PWM frequency of 3921.16 Hz divisor to 64 for PWM frequency of 490.20 Hz (The DEFAULT) divisor to 256 for PWM frequency of 122.55 Hz divisor to 1024 for PWM frequency of 30.64 Hz For timer 2 divisor to 1 for PWM frequency of 31372.55 Hz divisor to 8 for PWM frequency of 3921.16 Hz divisor to 32 for PWM frequency of 980.39 Hz divisor to 64 for PWM frequency of 490.20 Hz (The DEFAULT) divisor to 128 for PWM frequency of 245.10 Hz divisor to 256 for PWM frequency of 122.55 Hz divisor to 1024 for PWM frequency of 30.64 Hz

Definition at line 97 of file motor.h.

Referenced by setup().

◆ move()

void motor::move ( int16_t speed)
inline

Move the DC motor with constant voltage (~speed)

Parameters
speedRange minSpeed - maxSpeed, -255 - +255

Definition at line 190 of file motor.h.

References _maxSpeed, _minSpeed, _pwm_pin1, _pwm_pin2, speed, and stop().

Referenced by homing(), and loop().

Here is the call graph for this function:

◆ set_max()

void motor::set_max ( uint16_t max)
inline

Update the maximum speed of DC motor.

Parameters
maxMaximum speed, e.g. a range of 170 - 255

Definition at line 239 of file motor.h.

References _maxSpeed.

◆ set_min()

void motor::set_min ( uint16_t min)
inline

Update the minimum speed of DC motor.

Parameters
minMinimum speed, e.g. a range of 0 - 40

Definition at line 228 of file motor.h.

References _minSpeed.

◆ stop()

void motor::stop ( )
inline

Stop moving the DC motor.

Definition at line 216 of file motor.h.

References _pwm_pin1, and _pwm_pin2.

Referenced by homing(), loop(), motor(), and move().

Member Data Documentation

◆ _en_pin

uint8_t motor::_en_pin
private

Definition at line 244 of file motor.h.

Referenced by disenable(), enable(), init_pin(), and motor().

◆ _fb_pin

uint8_t motor::_fb_pin
private

Definition at line 244 of file motor.h.

Referenced by get_load(), init_pin(), and motor().

◆ _maxSpeed

int16_t motor::_maxSpeed
private

Definition at line 245 of file motor.h.

Referenced by motor(), move(), and set_max().

◆ _minSpeed

int16_t motor::_minSpeed
private

Definition at line 245 of file motor.h.

Referenced by motor(), move(), and set_min().

◆ _pwm_pin1

uint8_t motor::_pwm_pin1
private

Definition at line 244 of file motor.h.

Referenced by init_pin(), motor(), move(), and stop().

◆ _pwm_pin2

uint8_t motor::_pwm_pin2
private

Definition at line 244 of file motor.h.

Referenced by init_pin(), motor(), move(), and stop().

◆ _sf_pin

uint8_t motor::_sf_pin
private

Definition at line 244 of file motor.h.

Referenced by get_fault(), init_pin(), and motor().


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