|
#define | LS_NUM_SENSORS 8 |
| Total number of sensors on QTR line sensor.
|
|
#define | DST_NUM_SENSORS 3 |
| Total number of distance sensors.
|
|
#define | NUM_MOTORS 2 |
| Total number of motors.
|
|
#define | LP_LEFT_BTN PUSH2 |
| Represent the left push button on the launchpad.
|
|
#define | LP_RIGHT_BTN PUSH1 |
| Represent the right push button on the launchpad.
|
|
#define | TOTAL_BP_SW 6 |
| Total number of bump switches.
|
|
#define | LEFT_MOTOR 0 |
| Can be used to reference the left motor in the below functions.
|
|
#define | RIGHT_MOTOR 1 |
| Can be used to reference the right motor in the below functions.
|
|
#define | BOTH_MOTORS 2 |
| Can be used to reference both motors in the below functions.
|
|
#define | LEFT_SHRP_DIST 0 |
| Can be used to reference the left Sharp distance sensor.
|
|
#define | CENTER_SHRP_DIST 1 |
| Can be used to reference the center Sharp distance sensor.
|
|
#define | RIGHT_SHRP_DIST 2 |
| Can be used to reference the right Sharp distance sensor.
|
|
#define | MOTOR_DIR_FORWARD 0 |
| Can be used to reference setting the motor function to forward.
|
|
#define | MOTOR_DIR_BACKWARD 1 |
| Can be used to reference setting the motor function to backward.
|
|
#define | DARK_LINE 0 |
| Used to specify that the robot is running on a floor lighter than the line.
|
|
#define | LIGHT_LINE 1 |
| Used to specify that the robot is running on a floor darker than the line.
|
|
#define | readLineSensor readRawLineSensor |
| Read line sensor values.
|
|
|
void | setupRSLK () |
| Performs a variety of initialization needed for the RSLK.
|
|
uint16_t | readSharpDist (uint8_t num) |
| Read distance sensor value.
|
|
int16_t | readSharpDistMM (uint8_t num) |
| Read distance sensor value in millimeters.
|
|
float | readSharpDistIN (uint8_t num) |
| Read distance sensor value in inches.
|
|
bool | isBumpSwitchPressed (uint8_t num) |
| Return bump switch status.
|
|
uint8_t | getBumpSwitchPressed () |
| Return mask of bump switch states.
|
|
void | enableMotor (uint8_t motorNum) |
| Enable motor (take it out of sleep)
|
|
void | disableMotor (uint8_t motorNum) |
| Disable motor (puts the motor to sleep)
|
|
void | pauseMotor (uint8_t motorNum) |
| Pause motor (put the motor to sleep while saving its speed)
|
|
void | resumeMotor (uint8_t motorNum) |
| Resume motor (take the motor out of sleep and resumes its prior speed)
|
|
void | setMotorDirection (uint8_t motorNum, uint8_t direction) |
| Set direction the motor will turn.
|
|
void | setMotorSpeed (uint8_t motorNum, uint8_t speed) |
| Set the motor speed.
|
|
void | setupWaitBtn (uint8_t btn) |
| Configure pin as a wait to release button.
|
|
void | setupLed (uint8_t ledPin) |
| Configure pin that is connected to an led.
|
|
void | waitBtnPressed (uint8_t btnPin, int8_t ledPin=0) |
| Busy wait until user pushes and releases button.
|
|
void | calibrateLineSensor (uint8_t mode=DARK_LINE, uint32_t duration=500) |
| Calibrates line sensor.
|
|
void | readCalLineSensor (uint16_t *calVal) |
| Read calibrated line sensor values. Assumes calibration completed.
|
|
uint32_t | getLinePosition () |
| Get line position.
|
|
void | readRawLineSensor (uint16_t *sensor) |
| Read raw line sensor values.
|
|
void | clearMinMax (uint16_t *sensorMin, uint16_t *sensorMax) |
| Provide default values for the sensor's Min and Max arrays.
|
|
void | setSensorMinMax (uint16_t *sensor, uint16_t *sensorMin, uint16_t *sensorMax) |
| Update line sensor's min and max values array based on current data.
|
|
void | readCalLineSensor (uint16_t *sensor, uint16_t *calVal, uint16_t *sensorMin, uint16_t *sensorMax, uint8_t mode) |
| Update sensor's min and max values array based on current data.
|
|
uint32_t | getLinePosition (uint16_t *calVal, uint8_t mode) |
| Get line position.
|
|