Loading...
Searching...
No Matches

High-level driver for DC motors. More...

Detailed Description

High-level driver for DC motors.

This API aims to handle DC motor analogic driver. Driver boards using serial communication protocols (I2C, UART, etc...) are not in the scope of this driver. Mainly designed for H-bridge, it could also drive some brushless drivers.

Some H-bridge driver circuits handle several motors. Maximum motor number by H-bridge is set to 2 with CONFIG_MOTOR_DRIVER_MAX macro. This macro can be overridden to support H-bridge drivers with more outputs. However, CONFIG_MOTOR_DRIVER_MAX should not exceed PWM channels number.

motor_driver_t structure represents an H-bridge. As several H-bridge can share a same PWM device, motor_driver_t can represent a group of H-bridge.

Most of H-bridge boards uses the following I/Os for each motor :

*
* Each motor direction is controlled (assuming it is enabled) according to
* the following truth table :
*  __________________________
* | DIR0 | DIR1 |  BEHAVIOR  |
* |--------------------------|
* |  0   |  0   | BRAKE LOW  |
* |  0   |  1   |     CW     |
* |  1   |  0   |     CCW    |
* |  1   |  1   | BRAKE HIGH |
* |______|______|____________|
*
* In case of single GPIO for direction, only DIR0 is used without brake
* capability :
*  ___________________
* | DIR0 |  BEHAVIOR  |
* |-------------------|
* |   0  |     CW     |
* |   1  |     CCW    |
* |______|____________|
*
* Some boards add a brake pin with single direction GPIO :
*  ________________________
* | DIR | BRAKE | BEHAVIOR |
* |------------------------|
* |  0  |   0   |    CW    |
* |  0  |   1   |   BRAKE  |
* |  1  |   0   |    CCW   |
* |  1  |   1   |   BRAKE  |
* |_____|_______|__________|
*
* 

From this truth tables we can extract two direction states :

BRAKE LOW is functionally the same than BRAKE HIGH but some H-bridge only brake on BRAKE HIGH due to hardware. In case of single direction GPIO, there is no BRAKE, PWM duty cycle is set to 0.

Modules

 Motor_Driver driver compile configuration
 

Files

file  motor_driver.h
 High-level driver for DC motors.
 

Data Structures

struct  motor_t
 Describe DC motor with PWM channel and GPIOs. More...
 
struct  motor_driver_config_t
 Describe DC motor driver with PWM device and motors array. More...
 

Macros

#define MOTOR_DRIVER_DEV(x)   (x)
 Macro to return motor driver id.
 

Typedefs

typedef unsigned int motor_driver_t
 Default motor driver type definition.
 
typedef void(* motor_driver_cb_t) (const motor_driver_t motor_driver, uint8_t motor_id, int32_t pwm_duty_cycle)
 Motor callback.
 

Enumerations

enum  motor_driver_mode_t { MOTOR_DRIVER_2_DIRS = 0 , MOTOR_DRIVER_1_DIR = 1 , MOTOR_DRIVER_1_DIR_BRAKE = 2 }
 Describe DC motor driver modes. More...
 
enum  motor_driver_mode_brake_t { MOTOR_BRAKE_LOW = 0 , MOTOR_BRAKE_HIGH = 1 }
 Describe DC motor driver brake modes. More...
 
enum  motor_direction_t { MOTOR_CW = 0 , MOTOR_CCW = 1 }
 Describe DC motor direction states. More...
 

Functions

int motor_driver_init (const motor_driver_t motor_driver)
 Initialize DC motor driver board.
 
int motor_set (const motor_driver_t motor_driver, uint8_t motor_id, int32_t pwm_duty_cycle)
 Set motor speed and direction.
 
int motor_brake (const motor_driver_t motor_driver, uint8_t motor_id)
 Brake the motor of a given motor driver.
 
void motor_enable (const motor_driver_t motor_driver, uint8_t motor_id)
 Enable a motor of a given motor driver.
 
void motor_disable (const motor_driver_t motor_driver, uint8_t motor_id)
 Disable a motor of a given motor driver.
 

Macro Definition Documentation

◆ MOTOR_DRIVER_DEV

#define MOTOR_DRIVER_DEV (   x)    (x)

Macro to return motor driver id.

Definition at line 110 of file motor_driver.h.

Typedef Documentation

◆ motor_driver_cb_t

typedef void(* motor_driver_cb_t) (const motor_driver_t motor_driver, uint8_t motor_id, int32_t pwm_duty_cycle)

Motor callback.

It is called at end of motor_set()

Definition at line 161 of file motor_driver.h.

◆ motor_driver_t

typedef unsigned int motor_driver_t

Default motor driver type definition.

Definition at line 156 of file motor_driver.h.

Enumeration Type Documentation

◆ motor_direction_t

Describe DC motor direction states.

Enumerator
MOTOR_CW 

clockwise

MOTOR_CCW 

counter clockwise

Definition at line 135 of file motor_driver.h.

◆ motor_driver_mode_brake_t

Describe DC motor driver brake modes.

Enumerator
MOTOR_BRAKE_LOW 

Low stage brake.

MOTOR_BRAKE_HIGH 

High stage brake.

Definition at line 127 of file motor_driver.h.

◆ motor_driver_mode_t

Describe DC motor driver modes.

Enumerator
MOTOR_DRIVER_2_DIRS 

2 GPIOS for direction, \ handling BRAKE

MOTOR_DRIVER_1_DIR 

Single GPIO for direction, \ no BRAKE.

MOTOR_DRIVER_1_DIR_BRAKE 

Single GPIO for direction, \ Single GPIO for BRAKE.

Definition at line 115 of file motor_driver.h.

Function Documentation

◆ motor_brake()

int motor_brake ( const motor_driver_t  motor_driver,
uint8_t  motor_id 
)

Brake the motor of a given motor driver.

Parameters
[in]motor_drivermotor driver to which motor is attached
[in]motor_idmotor ID on driver
Returns
0 on success
-1 on error with errno set

◆ motor_disable()

void motor_disable ( const motor_driver_t  motor_driver,
uint8_t  motor_id 
)

Disable a motor of a given motor driver.

Parameters
[in]motor_drivermotor driver to which motor is attached
[in]motor_idmotor ID on driver
Returns

◆ motor_driver_init()

int motor_driver_init ( const motor_driver_t  motor_driver)

Initialize DC motor driver board.

Parameters
[out]motor_drivermotor driver to initialize
Returns
0 on success
-1 on error with errno set

◆ motor_enable()

void motor_enable ( const motor_driver_t  motor_driver,
uint8_t  motor_id 
)

Enable a motor of a given motor driver.

Parameters
[in]motor_drivermotor driver to which motor is attached
[in]motor_idmotor ID on driver
Returns

◆ motor_set()

int motor_set ( const motor_driver_t  motor_driver,
uint8_t  motor_id,
int32_t  pwm_duty_cycle 
)

Set motor speed and direction.

Parameters
[in]motor_drivermotor driver to which motor is attached
[in]motor_idmotor ID on driver
[in]pwm_duty_cycleSigned PWM duty_cycle to set motor speed and direction
Returns
0 on success
-1 on error with errno set