Go to the documentation of this file.
4 #include "GP2Y0A21_Sensor.h"
6 #include "Romi_Motor_Power.h"
7 #include "Bump_Switch.h"
16 #define LS_NUM_SENSORS 8 // number of sensors used
38 #define MOTOR_DIR_FORWARD 0
42 #define MOTOR_DIR_BACKWARD 1
195 void clearMinMax(uint16_t *sensorMin,uint16_t *sensorMax);
207 void setSensorMinMax(uint16_t *sensor,uint16_t *sensorMin,uint16_t *sensorMax);
void setMotorDirection(uint8_t motorNum, uint8_t direction)
Set direction the motor will turn.
uint16_t readSharpDist(uint8_t num)
Read distance sensor value.
bool isBumpSwitchPressed(uint8_t num)
Return bump switch status.
void readLineSensor(uint16_t *sensor)
Read line sensor values.
void clearMinMax(uint16_t *sensorMin, uint16_t *sensorMax)
Provide default values for the sensor's Min and Max arrays.
uint32_t getLinePosition(uint16_t *calVal, uint8_t mode)
Get line position.
void setupRSLK()
Performs a variety of initialization needed for the RSLK.
void disableMotor(uint8_t motorNum)
Disable motor (puts the motor to sleep)
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 resumeMotor(uint8_t motorNum)
Resume motor (take the motor out of sleep and resumes its prior speed)
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 waitBtnPressed(uint8_t btn)
Busy wait until user pushes and releases button.
void pauseMotor(uint8_t motorNum)
Pause motor (put the motor to sleep while saving its speed)
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.
void enableMotor(uint8_t motorNum)
Enable motor (take it out of sleep)