4#include "GP2Y0A21_Sensor.h"
6#include "Romi_Motor_Power.h"
7#include "Bump_Switch.h"
19#define LS_NUM_SENSORS 8
24#define DST_NUM_SENSORS 3
34#define LP_LEFT_BTN PUSH2
39#define LP_RIGHT_BTN PUSH1
64#define LEFT_SHRP_DIST 0
69#define CENTER_SHRP_DIST 1
74#define RIGHT_SHRP_DIST 2
79#define MOTOR_DIR_FORWARD 0
84#define MOTOR_DIR_BACKWARD 1
335#define readLineSensor readRawLineSensor
349void clearMinMax(uint16_t *sensorMin, uint16_t *sensorMax);
364void setSensorMinMax(uint16_t *sensor, uint16_t *sensorMin, uint16_t *sensorMax);
#define DARK_LINE
Used to specify that the robot is running on a floor lighter than the line.
uint32_t getLinePosition()
Get line position.
void enableMotor(uint8_t motorNum)
Enable motor (take it out of sleep)
float readSharpDistIN(uint8_t num)
Read distance sensor value in inches.
void setMotorSpeed(uint8_t motorNum, uint8_t speed)
Set the motor speed.
bool isBumpSwitchPressed(uint8_t num)
Return bump switch status.
void setupRSLK()
Performs a variety of initialization needed for the RSLK.
void clearMinMax(uint16_t *sensorMin, uint16_t *sensorMax)
Provide default values for the sensor's Min and Max arrays.
void disableMotor(uint8_t motorNum)
Disable motor (puts the motor to sleep)
void setMotorDirection(uint8_t motorNum, uint8_t direction)
Set direction the motor will turn.
uint16_t readSharpDist(uint8_t num)
Read distance sensor value.
void readRawLineSensor(uint16_t *sensor)
Read raw line sensor values.
uint8_t getBumpSwitchPressed()
Return mask of bump switch states.
void waitBtnPressed(uint8_t btnPin, int8_t ledPin=0)
Busy wait until user pushes and releases button.
void setupWaitBtn(uint8_t btn)
Configure pin as a wait to release button.
void pauseMotor(uint8_t motorNum)
Pause motor (put the motor to sleep while saving its speed)
void readCalLineSensor(uint16_t *calVal)
Read calibrated line sensor values. Assumes calibration completed.
void setupLed(uint8_t ledPin)
Configure pin that is connected to an led.
void calibrateLineSensor(uint8_t mode=DARK_LINE, uint32_t duration=500)
Calibrates line sensor.
void resumeMotor(uint8_t motorNum)
Resume motor (take the motor out of sleep and resumes its prior speed)
int16_t readSharpDistMM(uint8_t num)
Read distance sensor value in millimeters.
void setSensorMinMax(uint16_t *sensor, uint16_t *sensorMin, uint16_t *sensorMax)
Update line sensor's min and max values array based on current data.