TI RSLK Library 0.2.2
Loading...
Searching...
No Matches
Public Member Functions
Romi_Motor_Power Class Reference

Represents a single motor. More...

#include <Romi_Motor_Power.h>

Public Member Functions

bool begin (uint8_t islp_pin, uint8_t idir_pin, uint8_t ipwm_pin)
 Initialize the motor and configures important pins.
 
void disableMotor ()
 Disable motor.
 
void enableMotor ()
 Enable motor.
 
void pauseMotor ()
 Pause motor.
 
void resumeMotor ()
 Resume motor.
 
void directionForward ()
 Set motor's direction to forward.
 
void directionBackward ()
 Set motor's direction to backwards.
 
void setSpeed (uint8_t speed)
 Set motor speed.
 
void setRawSpeed (uint8_t speed)
 Set motor's raw speed.
 

Detailed Description

Represents a single motor.

An instance of this class represents a single motor. The function begin() must be called before using any other function.

Parts:

Definition at line 14 of file Romi_Motor_Power.h.

Constructor & Destructor Documentation

◆ Romi_Motor_Power()

Romi_Motor_Power::Romi_Motor_Power ( )

Definition at line 3 of file Romi_Motor_Power.cpp.

Member Function Documentation

◆ begin()

bool Romi_Motor_Power::begin ( uint8_t  islp_pin,
uint8_t  idir_pin,
uint8_t  ipwm_pin 
)

Initialize the motor and configures important pins.

Parameters
[in]islp_pinpin number on Launchpad connected to motor's sleep pin
[in]idir_pinpin number on Launchpad connected to motor's direction pin
[in]ipwm_pinpin number on Launchpad connected to motor's PWM pin

Call this function to initialize motor

Definition at line 12 of file Romi_Motor_Power.cpp.

◆ disableMotor()

void Romi_Motor_Power::disableMotor ( )

Disable motor.

This function with disable the motor by putting it to sleep. The motor's speed is also set to 0. After calling this function the motor needs to be reenabled and be given a speed before it will start working again.

Definition at line 27 of file Romi_Motor_Power.cpp.

◆ enableMotor()

void Romi_Motor_Power::enableMotor ( )

Enable motor.

This function with enable the motor by taking it out of sleep. The motor's speed needs to be reenabled to start working again.

Definition at line 33 of file Romi_Motor_Power.cpp.

◆ pauseMotor()

void Romi_Motor_Power::pauseMotor ( )

Pause motor.

This function with stop the motor and acts just like disableMotor. However, the motor's speed when pause will be preserved and restored once resumeMotor is called.

Definition at line 48 of file Romi_Motor_Power.cpp.

◆ resumeMotor()

void Romi_Motor_Power::resumeMotor ( )

Resume motor.

This function with resume the motor's operation if pauseMotor was previously called. Unlike enableMotor the motor will start running based on the speed that was set when the motor was paused.

Definition at line 55 of file Romi_Motor_Power.cpp.

◆ directionForward()

void Romi_Motor_Power::directionForward ( )

Set motor's direction to forward.

Spins the wheel in the forward direction.

Definition at line 38 of file Romi_Motor_Power.cpp.

◆ directionBackward()

void Romi_Motor_Power::directionBackward ( )

Set motor's direction to backwards.

Spins the wheel in the backward direction.

Definition at line 43 of file Romi_Motor_Power.cpp.

◆ setSpeed()

void Romi_Motor_Power::setSpeed ( uint8_t  speed)

Set motor speed.

Parameters
[in]speedValid values are 0 - 100 mimicing percentage.
  • 0 to halt motor
  • ...
  • 100 run motor at its max speed

Sets the motor speed. This function may be easier for beginners to understand.

Definition at line 61 of file Romi_Motor_Power.cpp.

◆ setRawSpeed()

void Romi_Motor_Power::setRawSpeed ( uint8_t  speed)

Set motor's raw speed.

Parameters
[in]speedbetween 0 - 255
  • 0 to halt motor
  • ...
  • 255 run motor at its max speed

Sets the motor speed. Provides finer grain control of the motor's speed then setSpeed.

Definition at line 67 of file Romi_Motor_Power.cpp.


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