TI RSLK Library  0.2.0
Macros | Functions
SimpleRSLK.h File Reference
#include "RSLK_Pins.h"
#include "QTRSensors.h"
#include "GP2Y0A21_Sensor.h"
#include "Encoder.h"
#include "Romi_Motor_Power.h"
#include "Bump_Switch.h"

Go to the source code of this file.

Macros

#define LS_NUM_SENSORS   8
 Total number of sensors on QTR line sensor.
 
#define TOTAL_BP_SW   6
 
#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 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
 Can be used to reference setting the motor function to backward.
 
#define LIGHT_LINE   1
 Can be used to reference setting the motor function to backward.
 

Functions

void setupRSLK ()
 Performs a variety of initialization needed for the RSLK. More...
 
uint16_t readSharpDist (uint8_t num)
 Read distance sensor value. More...
 
bool isBumpSwitchPressed (uint8_t num)
 Return bump switch status. More...
 
void enableMotor (uint8_t motorNum)
 Enable motor (take it out of sleep) More...
 
void disableMotor (uint8_t motorNum)
 Disable motor (puts the motor to sleep) More...
 
void pauseMotor (uint8_t motorNum)
 Pause motor (put the motor to sleep while saving its speed) More...
 
void resumeMotor (uint8_t motorNum)
 Resume motor (take the motor out of sleep and resumes its prior speed) More...
 
void setMotorDirection (uint8_t motorNum, uint8_t direction)
 Set direction the motor will turn. More...
 
void setMotorSpeed (uint8_t motorNum, uint8_t speed)
 Set the motor speed. More...
 
void readLineSensor (uint16_t *sensor)
 Read line sensor values. More...
 
void setupWaitBtn (uint8_t btn)
 Configure pin as a wait to release button. More...
 
void waitBtnPressed (uint8_t btn)
 Busy wait until user pushes and releases button. More...
 
void clearMinMax (uint16_t *sensorMin, uint16_t *sensorMax)
 Provide default values for the sensor's Min and Max arrays. More...
 
void setSensorMinMax (uint16_t *sensor, uint16_t *sensorMin, uint16_t *sensorMax)
 Update line sensor's min and max values array based on current data. More...
 
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. More...
 
uint32_t getLinePosition (uint16_t *calVal, uint8_t mode)
 Get line position. More...
 

Function Documentation

◆ clearMinMax()

void clearMinMax ( uint16_t *  sensorMin,
uint16_t *  sensorMax 
)

Provide default values for the sensor's Min and Max arrays.

Parameters
[out]sensorMinstores sensor's min values. Must pass an array with 8 elements. All elements will by default be given a large value.
[out]sensorMaxstores sensor's max values. Must pass an array with 8 elements. All elements will by default be given a value of 0.

Initializes arrays to be used to store line sensor's min and max values.

Definition at line 157 of file SimpleRSLK.cpp.

◆ disableMotor()

void disableMotor ( uint8_t  motorNum)

Disable motor (puts the motor to sleep)

Parameters
[in]motorNumthat designates the the motor. Valid values are 0 - 2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors

Disabling the motor sets its speed to 0 and puts it to sleep.

Definition at line 71 of file SimpleRSLK.cpp.

◆ enableMotor()

void enableMotor ( uint8_t  motorNum)

Enable motor (take it out of sleep)

Parameters
[in]motorNumthat designates the the motor. Valid values are 0 - 2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors

Takes the motor out of sleep. The motor will not move unless you also call setMotorSpeed.

Definition at line 57 of file SimpleRSLK.cpp.

◆ getLinePosition()

uint32_t getLinePosition ( uint16_t *  calVal,
uint8_t  mode 
)

Get line position.

Parameters
[in]calValis an array that is filled with the line sensor calibrated values.
[in]modedetermines if the line is dark or light.
  • 0 is used when the line is darker than the floor
  • 1 is used when the line is lighter than the floor.
Returns
value between 0 - 7000.
  • 0 no line detected
  • ...
  • 1000 line is directly on the left most sensor
  • ...
  • 3500 line directly over two middle sensors.
  • ...
  • 7000 is under right most line sensor

Using calibrated line sensor value this function provides a numerical value indicating where the robot is detecting the line. This function can be overridden.

Definition at line 187 of file SimpleRSLK.cpp.

◆ isBumpSwitchPressed()

bool isBumpSwitchPressed ( uint8_t  num)

Return bump switch status.

Parameters
[in]numbump switch number. Valid values are 0 - 5 representing the RSLK's 6 bump switches.
  • 0 for left most switch.
  • ...
  • 5 for right most switch.
Returns
  • true if switch is pressed
  • false if switch isn't pressed.

Definition at line 47 of file SimpleRSLK.cpp.

◆ pauseMotor()

void pauseMotor ( uint8_t  motorNum)

Pause motor (put the motor to sleep while saving its speed)

Parameters
[in]motorNumthat designates the the motor. Valid values are 0-2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors

Puts the motor to sleep while also preserving the previously set motor speed.

Definition at line 84 of file SimpleRSLK.cpp.

◆ 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.

Parameters
[out]sensoris an array to be filled with line sensor values.
[out]calValis an array that will be filled with the calibrated values based on the sensor, sensorMin and sensorMax array.
Elements will be filled with values of 0 - 1000
  • 0 means no line detected
  • ...
  • 1000 means line is detected right under sensor.
[in]sensorMinstores sensor's min values.
[in]sensorMaxstores sensor's max values.
[in]modedetermines if the line is dark or light.
  • 0 is used when the line is darker than the floor
  • 1 is used when the line is lighter than the floor.

Takes the current line sensor values and sets calVal to the calibrated values. Uses sensorMin and sensorMax array along with mode to calibrate value.

Calibration:

  • When the line is dark then calibration subtracts sensorMax values from the sensor value read.
  • When the line is light then calibration subtracts sensorMin values from the sensor value read. Then the value is subtracted from 1000 to provide a consistent scale.

Definition at line 166 of file SimpleRSLK.cpp.

◆ readLineSensor()

void readLineSensor ( uint16_t *  sensor)

Read line sensor values.

Parameters
[out]sensorarray that stores values read from line sensor. Must pass an array with 8 elements. Array index 0 represents the left most sensor. Array index 7 represents the right most sensor.
Each index will contain a value from 0 - 2500.
  • 0 max reflection (light line)
  • ....
  • 2500 no reflection (dark line)

Read and store sensor values in the passed in array.

Definition at line 153 of file SimpleRSLK.cpp.

◆ readSharpDist()

uint16_t readSharpDist ( uint8_t  num)

Read distance sensor value.

Parameters
[in]numof the distance sensor to read. Valid values are 0 - 2. Representing the 3 RSLK's sensors that can be mounted on the RSLK (on top of the bump switch assembly).
  • 0 for the left sensor.
  • 1 for the center sensor.
  • 5 for the right sensor.
Returns
A value from 0 - 4065.
  • 0 represents object right infront of sensor
  • ....
  • 4065 represents no object detected

Definition at line 40 of file SimpleRSLK.cpp.

◆ resumeMotor()

void resumeMotor ( uint8_t  motorNum)

Resume motor (take the motor out of sleep and resumes its prior speed)

Parameters
[in]motorNumthat designates the the motor. Valid values are 0-2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors

Take the motor out of sleep and sets its speed to its prior value.

Definition at line 96 of file SimpleRSLK.cpp.

◆ setMotorDirection()

void setMotorDirection ( uint8_t  motorNum,
uint8_t  direction 
)

Set direction the motor will turn.

Parameters
[in]motorNumthat designates the the motor. Valid values are 0-2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors
[in]directionthat specifies the motor's direction
  • 0 for forward
  • 1 for for backward

Specifies the motor's direction. Can control an indivdual motor or both motors.

Definition at line 108 of file SimpleRSLK.cpp.

◆ setMotorSpeed()

void setMotorSpeed ( uint8_t  motorNum,
uint8_t  speed 
)

Set the motor speed.

Parameters
[in]motorNumthat designates the the motor. Valid values are 0-2.
  • 0 for left motor
  • 1 for right motor
  • 2 for both motors
[in]speedthat specifies the motor speed. Valid values are 0 - 100.
  • 0 for 0% of motor speed.
  • ...
  • 100 for 100% of motor speed.

Sets the speed of the motor. A value of 0 means no movement. 100 will set the motor to its fastest speed.

Definition at line 129 of file SimpleRSLK.cpp.

◆ 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.

Parameters
[in]sensoris an array filled with line sensor values previously filled by readLineSensor.
[out]sensorMinstores sensor's min values.
[out]sensorMaxstores sensor's max values.

Take the current line sensor values and update min and max values. This function along with the min and max arrays are useful when performing calibration.

Definition at line 210 of file SimpleRSLK.cpp.

◆ setupRSLK()

void setupRSLK ( )

Performs a variety of initialization needed for the RSLK.

This function must be called before calling any other functions listed on this page.

Definition at line 10 of file SimpleRSLK.cpp.

◆ setupWaitBtn()

void setupWaitBtn ( uint8_t  btn)

Configure pin as a wait to release button.

Parameters
[in]btnthe Launchpad pin number you want to use.

Configure pin to be used as a wait until pushed and released button. Useful if you want to halt the robot's operation until the uses pushes and then releases the button.

Definition at line 224 of file SimpleRSLK.cpp.

◆ waitBtnPressed()

void waitBtnPressed ( uint8_t  btn)

Busy wait until user pushes and releases button.

Parameters
[in]btnthe Launchpad pin number you want to use.

Prevent additional code from executing until use has pushed and released specified button.

Definition at line 228 of file SimpleRSLK.cpp.