RIT VEXU Core API
Loading...
Searching...
No Matches
TankDrive Class Reference

#include <tank_drive.h>

Public Types

enum class  BrakeType { None , ZeroVelocity , Smart }
 

Public Member Functions

 TankDrive (motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL)
 
void stop ()
 
void drive_tank (double left, double right, int power=1, BrakeType bt=BrakeType::None)
 
void drive_tank_raw (double left, double right)
 
void drive_arcade (double forward_back, double left_right, int power=1, BrakeType bt=BrakeType::None)
 
bool drive_forward (double inches, directionType dir, Feedback &feedback, double max_speed=1, double end_speed=0)
 
bool drive_forward (double inches, directionType dir, double max_speed=1, double end_speed=0)
 
bool turn_degrees (double degrees, Feedback &feedback, double max_speed=1, double end_speed=0)
 
bool turn_degrees (double degrees, double max_speed=1, double end_speed=0)
 
bool drive_to_point (double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1, double end_speed=0)
 
bool drive_to_point (double x, double y, vex::directionType dir, double max_speed=1, double end_speed=0)
 
bool turn_to_heading (double heading_deg, Feedback &feedback, double max_speed=1, double end_speed=0)
 
bool turn_to_heading (double heading_deg, double max_speed=1, double end_speed=0)
 
void reset_auto ()
 
bool pure_pursuit (PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed=1, double end_speed=0)
 
bool pure_pursuit (PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0)
 

Static Public Member Functions

static double modify_inputs (double input, int power=2)
 

Detailed Description

TankDrive is a class to run a tank drive system. A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side

Member Enumeration Documentation

◆ BrakeType

enum class TankDrive::BrakeType
strong
Enumerator
None 

just send 0 volts to the motors

ZeroVelocity 

try to bring the robot to rest. But don't try to hold position

Smart 

bring the robot to rest and once it's stopped, try to hold that position

Constructor & Destructor Documentation

◆ TankDrive()

TankDrive::TankDrive ( motor_group & left_motors,
motor_group & right_motors,
robot_specs_t & config,
OdometryBase * odom = NULL )

Create the TankDrive object

Parameters
left_motorsleft side drive motors
right_motorsright side drive motors
configthe configuration specification defining physical dimensions about the robot. See robot_specs_t for more info
odoman odometry system to track position and rotation. this is necessary to execute autonomous paths

Member Function Documentation

◆ drive_arcade()

void TankDrive::drive_arcade ( double forward_back,
double left_right,
int power = 1,
BrakeType bt = BrakeType::None )

Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

forward_back and left_right are in "percent": -1.0 -> 1.0

Parameters
forward_backthe percent to move forward or backward
left_rightthe percent to turn left or right
powermodifies the input velocities left^power, right^power
btbreaktype. What to do if the driver lets go of the sticks

Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

left_motors and right_motors are in "percent": -1.0 -> 1.0

◆ drive_forward() [1/2]

bool TankDrive::drive_forward ( double inches,
directionType dir,
double max_speed = 1,
double end_speed = 0 )

Autonomously drive the robot forward a certain distance

Parameters
inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Autonomously drive the robot forward a certain distance

Parameters
inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have finished driving to our point

◆ drive_forward() [2/2]

bool TankDrive::drive_forward ( double inches,
directionType dir,
Feedback & feedback,
double max_speed = 1,
double end_speed = 0 )

Use odometry to drive forward a certain distance using a custom feedback controller

Returns whether or not the robot has reached it's destination.

Parameters
inchesthe distance to drive forward
dirthe direction we want to travel forward and backward
feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true when we have reached our target distance

Use odometry to drive forward a certain distance using a custom feedback controller

Returns whether or not the robot has reached it's destination.

Parameters
inchesthe distance to drive forward
dirthe direction we want to travel forward and backward
feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

◆ drive_tank()

void TankDrive::drive_tank ( double left,
double right,
int power = 1,
BrakeType bt = BrakeType::None )

Drive the robot using differential style controls. left_motors controls the left motors, right_motors controls the right motors.

left_motors and right_motors are in "percent": -1.0 -> 1.0

Parameters
leftthe percent to run the left motors
rightthe percent to run the right motors
powermodifies the input velocities left^power, right^power
btbreaktype. What to do if the driver lets go of the sticks

◆ drive_tank_raw()

void TankDrive::drive_tank_raw ( double left,
double right )

Drive the robot raw-ly

Parameters
leftthe percent to run the left motors (-1, 1)
rightthe percent to run the right motors (-1, 1)

◆ drive_to_point() [1/2]

bool TankDrive::drive_to_point ( double x,
double y,
vex::directionType dir,
double max_speed = 1,
double end_speed = 0 )

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

Returns whether or not the robot has reached it's destination.

Parameters
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

Returns whether or not the robot has reached it's destination.

Parameters
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have reached our target point

◆ drive_to_point() [2/2]

bool TankDrive::drive_to_point ( double x,
double y,
vex::directionType dir,
Feedback & feedback,
double max_speed = 1,
double end_speed = 0 )

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

Returns whether or not the robot has reached it's destination.

Parameters
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

Returns whether or not the robot has reached it's destination.

Parameters
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have reached our target point

◆ modify_inputs()

double TankDrive::modify_inputs ( double input,
int power = 2 )
static

Create a curve for the inputs, so that drivers have more control at lower speeds. Curves are exponential, with the default being squaring the inputs.

Parameters
inputthe input before modification
powerthe power to raise input to
Returns
input ^ power (accounts for negative inputs and odd numbered powers)

Modify the inputs from the controller by squaring / cubing, etc Allows for better control of the robot at slower speeds

Parameters
inputthe input signal -1 -> 1
powerthe power to raise the signal to
Returns
input^power accounting for any sign issues that would arise with this naive solution

◆ pure_pursuit() [1/2]

bool TankDrive::pure_pursuit ( PurePursuit::Path path,
directionType dir,
double max_speed = 1,
double end_speed = 0 )

Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of waypoints - the robot will attempt to follow the points while cutting corners (radius) to save time (compared to stop / turn / start)

Use the default drive feedback

Parameters
pathThe list of coordinates to follow, in order
dirRun the bot forwards or backwards
max_speedLimit the speed of the robot (for pid / pidff feedbacks)
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
True when the path is complete

Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of waypoints - the robot will attempt to follow the points while cutting corners (radius) to save time (compared to stop / turn / start)

Use the default drive feedback

Parameters
pathThe list of coordinates to follow, in order
dirRun the bot forwards or backwards
max_speedLimit the speed of the robot (for pid / pidff feedbacks)
Returns
True when the path is complete

◆ pure_pursuit() [2/2]

bool TankDrive::pure_pursuit ( PurePursuit::Path path,
directionType dir,
Feedback & feedback,
double max_speed = 1,
double end_speed = 0 )

Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of waypoints - the robot will attempt to follow the points while cutting corners (radius) to save time (compared to stop / turn / start)

Parameters
pathThe list of coordinates to follow, in order
dirRun the bot forwards or backwards
feedbackThe feedback controller determining speed
max_speedLimit the speed of the robot (for pid / pidff feedbacks)
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
True when the path is complete

Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of waypoints - the robot will attempt to follow the points while cutting corners (radius) to save time (compared to stop / turn / start)

Parameters
pathThe list of coordinates to follow, in order
dirRun the bot forwards or backwards
feedbackThe feedback controller determining speed
max_speedLimit the speed of the robot (for pid / pidff feedbacks)
Returns
True when the path is complete

◆ reset_auto()

void TankDrive::reset_auto ( )

Reset the initialization for autonomous drive functions

◆ stop()

void TankDrive::stop ( )

Stops rotation of all the motors using their "brake mode"

◆ turn_degrees() [1/2]

bool TankDrive::turn_degrees ( double degrees,
double max_speed = 1,
double end_speed = 0 )

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

Uses the defualt turning feedback of the drive system.

Parameters
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

Uses the defualt turning feedback of the drive system.

Parameters
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we turned te target number of degrees

◆ turn_degrees() [2/2]

bool TankDrive::turn_degrees ( double degrees,
Feedback & feedback,
double max_speed = 1,
double end_speed = 0 )

Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

Uses PID + Feedforward for it's control.

Parameters
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

Uses the specified feedback for it's control.

Parameters
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have turned our target number of degrees

◆ turn_to_heading() [1/2]

bool TankDrive::turn_to_heading ( double heading_deg,
double max_speed = 1,
double end_speed = 0 )

Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

Parameters
heading_degthe heading to which we will turn
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

Parameters
heading_degthe heading to which we will turn
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have reached our target heading

◆ turn_to_heading() [2/2]

bool TankDrive::turn_to_heading ( double heading_deg,
Feedback & feedback,
double max_speed = 1,
double end_speed = 0 )

Turn the robot in place to an exact heading relative to the field. 0 is forward.

Parameters
heading_degthe heading to which we will turn
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion

Turn the robot in place to an exact heading relative to the field. 0 is forward.

Parameters
heading_degthe heading to which we will turn
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
end_speedthe movement profile will attempt to reach this velocity by its completion
Returns
true if we have reached our target heading

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