RedBot
RedBot Arduino Library for the Sparkfun RedBot
 All Classes Functions Variables
RedBotMotor Class Reference

#include <RedBot.h>

Public Member Functions

 RedBotMotor ()
 
void drive (int speed)
 
void leftDrive (int speed)
 
void rightDrive (int speed)
 
void pivot (int speed)
 
void stop ()
 
void leftStop ()
 
void rightStop ()
 
void brake ()
 
void leftBrake ()
 
void rightBrake ()
 

Detailed Description

A class for controlling the RedBot's motors. A single object of the RedBotMotor class controls both the left and right motors of the RedBot.

Constructor & Destructor Documentation

RedBotMotor::RedBotMotor ( )

Create a new object of the RedBotMotor class.

A single RedBotMotor instance is used for both motors on the RedBot.

Member Function Documentation

void RedBotMotor::brake ( )

Immediately stop both motors and hold their current positions.

The RedBotMotor::brake() method effectively shorts the terminals of the motors and therefore results in the motors stopping much more quickly than the RedBotMotor::stop() method. After a call to RedBotMotor::brake(), the motors will be much harder to turn, which will allow the RedBot to hold its position on a slope.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop() {

// Drive for a bit

for (int x = 0; x < 1000; x++) {

motor.drive (200);

}

// Stop the motors and hold current position

motor.brake();

}

void RedBotMotor::drive ( int  speed)

Run both motors at a given speed.

If speed is a positive integer, drives both motors forward, and if speed is a negative integer, drives both motors backward. In either case, the motors are driven at the absolute value at speed. Allowable values for speed are -255 to 255 inclusive, however values in -75 to 0 and 0 to 75 inclusive may not provide enough torque to start the motor turning.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop () {

// Drive forward at a speed of 200

motor.drive (200);

// Drive backward at a speed of 150

motor.drive (-150)

}

void RedBotMotor::leftBrake ( )

Immediately stop the left motor and hold its current position.

The RedBotMotor::leftBrake() method effectively shorts the terminals of * the left motor and therefore results in the motor stopping much more quickly than the RedBotMotor::leftRtop() method. After a call to RedBotMotor::leftBrake(), the motor will be much harder to turn, which will allow the RedBot to hold its position on a slope. The right motor will still be able to be driven via RedBotMotor::rightDrive() method.

void RedBotMotor::leftDrive ( int  speed)

Run the left motor at a given speed.

If speed is a positive integer, drives the motor forward, and if speed is a negative integer, drives motor backward. In either case, the motor is driven at the absolute value at speed. Allowable values for speed are -255 to 255 inclusive, however values in -75 to 0 and 0 to 75 inclusive may not provide enough torque to start the motor turning.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop () {

// Drive the left motor forward at a speed of 200

motor.LeftDrive (200);

// Drive the left motor backward at a speed of 150

motor.leftDrive (-150)

}

void RedBotMotor::leftStop ( )

Discontinue PWM output to the left motor.

This method turns off the left motor by stopping PWM output to the motor. After a call to this method, the left motor will continue to coast for a short time. In order to continue driving just the right motor, use RedBotMotor::rightDrive(int speed)

void RedBotMotor::pivot ( int  speed)

Pivot the RedBot to either the left or right.

If speed is a positive integer, the RedBot pivots to the left. If speed is a negative integer, the RedBot pivots to the right. In either case, the motors are driven in their respective directions at the absolute value of speed. When pivoting left, the left motor drives backwards and the right motor drives forward; when pivoting right, the motors drive in the opposite directions. Allowable values for speed are -255 to 255 inclusive, however values in -75 to 0 and 0 to 75 inclusive may not provide enough torque to start the motor turning.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop() {

// Pivot to the left at a speed of 150

motor.pivot (150);

// Pivot to the right at a speed of 75

motor.pivot (-75);

}

void RedBotMotor::rightBrake ( )

Immediately stop the right motor and hold its current position.

The RedBotMotor::rightBrake() method effectively shorts the terminals of the right motor and therefore results in the motor stopping much more quickly than the RedBotMotor::rightRtop() method. After a call to RedBotMotor::rightBrake(), the motor will be much harder to turn, which will allow the RedBot to hold its position on a slope. The left motor will still be able to be driven via RedBotMotor::leftDrive() method.

void RedBotMotor::rightDrive ( int  speed)

Run the right motor at a given speed.

If speed is a positive integer, drives the motor forward, and if speed is a negative integer, drives motor backward. In either case, the motor is driven at the absolute value at speed. Allowable values for speed are -255 to 255 inclusive, however values in -75 to 0 and 0 to 75 inclusive may not provide enough torque to start the motor turning.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop () {

// Drive the right motor forward at a speed of 200

motor.RightDrive (200);

// Drive the right motor backward at a speed of 150

motor.rightDrive (-150)

}

void RedBotMotor::rightStop ( )

Discontinue PWM output to the right motor.

This method turns off the right motor by stopping PWM output to the motor. After a call to this method, the right motor will continue to coast for a short time. In order to continue driving just the left motor, use RedBotMotor::leftDrive(int speed)

void RedBotMotor::stop ( )

Discontinue PWM output to both motors.

This method turns off both motors by stopping PWM output to the motors. After a call to this method, the motors will continue to coast for a short time.

Usage Example:

#include <RedBot.h>

RedBotMotor motor;

void setup() {

}

void loop() {

// Drive for a bit

for (int x = 0; x < 1000; x++) {

motor.drive (200);

}

// Stop the motors

motor.stop();

}


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