TI RSLK Library  0.2.0
All Classes Files Functions Variables Enumerations Enumerator Macros
SimpleRSLK.h
Go to the documentation of this file.
1 
2 #include "RSLK_Pins.h"
3 #include "QTRSensors.h"
4 #include "GP2Y0A21_Sensor.h"
5 #include "Encoder.h"
6 #include "Romi_Motor_Power.h"
7 #include "Bump_Switch.h"
8 
9 #ifndef SimpleRSLK_h
10 #define SimpleRSLK_h
11 
12 
16 #define LS_NUM_SENSORS 8 // number of sensors used
17 
18 /*
19  * @brief Total number of bump switches.
20  */
21 #define TOTAL_BP_SW 6
22 
25 #define LEFT_MOTOR 0
26 
29 #define RIGHT_MOTOR 1
30 
33 #define BOTH_MOTORS 2
34 
38 #define MOTOR_DIR_FORWARD 0
39 
42 #define MOTOR_DIR_BACKWARD 1
43 
47 #define DARK_LINE 0
48 
52 #define LIGHT_LINE 1
53 
58 void setupRSLK();
59 
72 uint16_t readSharpDist(uint8_t num);
73 
85 bool isBumpSwitchPressed(uint8_t num);
86 
95 void enableMotor(uint8_t motorNum);
96 
105 void disableMotor(uint8_t motorNum);
106 
115 void pauseMotor(uint8_t motorNum);
116 
125 void resumeMotor(uint8_t motorNum);
126 
133 
139 void setMotorDirection(uint8_t motorNum,uint8_t direction);
140 
155 void setMotorSpeed(uint8_t motorNum, uint8_t speed);
156 
168 void readLineSensor(uint16_t *sensor);
169 
176 void setupWaitBtn(uint8_t btn);
177 
184 void waitBtnPressed(uint8_t btn);
185 
195 void clearMinMax(uint16_t *sensorMin,uint16_t *sensorMax);
196 
207 void setSensorMinMax(uint16_t *sensor,uint16_t *sensorMin,uint16_t *sensorMax);
208 
209 
236 void readCalLineSensor(uint16_t* sensor,
237  uint16_t* calVal,
238  uint16_t *sensorMin,
239  uint16_t *sensorMax,
240  uint8_t mode);
241 
260 uint32_t getLinePosition(uint16_t* calVal, uint8_t mode);
261 
262 #endif
setMotorDirection
void setMotorDirection(uint8_t motorNum, uint8_t direction)
Set direction the motor will turn.
Definition: SimpleRSLK.cpp:108
RSLK_Pins.h
readSharpDist
uint16_t readSharpDist(uint8_t num)
Read distance sensor value.
Definition: SimpleRSLK.cpp:40
isBumpSwitchPressed
bool isBumpSwitchPressed(uint8_t num)
Return bump switch status.
Definition: SimpleRSLK.cpp:47
readLineSensor
void readLineSensor(uint16_t *sensor)
Read line sensor values.
Definition: SimpleRSLK.cpp:153
clearMinMax
void clearMinMax(uint16_t *sensorMin, uint16_t *sensorMax)
Provide default values for the sensor's Min and Max arrays.
Definition: SimpleRSLK.cpp:157
getLinePosition
uint32_t getLinePosition(uint16_t *calVal, uint8_t mode)
Get line position.
Definition: SimpleRSLK.cpp:187
setupRSLK
void setupRSLK()
Performs a variety of initialization needed for the RSLK.
Definition: SimpleRSLK.cpp:10
disableMotor
void disableMotor(uint8_t motorNum)
Disable motor (puts the motor to sleep)
Definition: SimpleRSLK.cpp:71
setMotorSpeed
void setMotorSpeed(uint8_t motorNum, uint8_t speed)
Set the motor speed.
Definition: SimpleRSLK.cpp:129
setupWaitBtn
void setupWaitBtn(uint8_t btn)
Configure pin as a wait to release button.
Definition: SimpleRSLK.cpp:224
resumeMotor
void resumeMotor(uint8_t motorNum)
Resume motor (take the motor out of sleep and resumes its prior speed)
Definition: SimpleRSLK.cpp:96
setSensorMinMax
void setSensorMinMax(uint16_t *sensor, uint16_t *sensorMin, uint16_t *sensorMax)
Update line sensor's min and max values array based on current data.
Definition: SimpleRSLK.cpp:210
QTRSensors.h
waitBtnPressed
void waitBtnPressed(uint8_t btn)
Busy wait until user pushes and releases button.
Definition: SimpleRSLK.cpp:228
pauseMotor
void pauseMotor(uint8_t motorNum)
Pause motor (put the motor to sleep while saving its speed)
Definition: SimpleRSLK.cpp:84
readCalLineSensor
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.
Definition: SimpleRSLK.cpp:166
enableMotor
void enableMotor(uint8_t motorNum)
Enable motor (take it out of sleep)
Definition: SimpleRSLK.cpp:57
Encoder.h