API documentation

Dimitris Platis edited this page Sep 28, 2015 · 62 revisions

Introduction

Here you can find the Autonomous-Car Arduino Library API documentation that will allow you to control the Autonomous Car made by Team Pegasus and read data from various sensors on it. You can find the various accessible API components as well as usage examples. If you want to review how these components are used in a common sketch, please refer to the Example sketches section. Currently, the library supports the following sensors:

  • The the HC-SR04 & SRF05 ultra sound sensors that measures distance.
  • The SHARP GP2D120 infrared sensor that measures distance.
  • The L3G4200D gyroscope, which returns angular displacement from an initial position.
  • A wheel encoder, which returns pulses that can be mapped to centimeters.
  • A 9 DOF IMU (Sparkfun Razor) that returns displacement in degrees from the North, as a compass.

You can use as many infra red and ultra sound sensors your development platform allows. They should all be running independently from each other. Moreover, when using the Arduino IDE, the available API components will be color-coded after being typed, which should help you acclimatize yourself and review code faster.

Contents

Dependencies

In order to start using the library in your Arduino sketch, you have to include the Autonomous-Car Arduino library, the Servo library (for the ESC and the steering wheel Servo) and the Wire library (for the Gyroscope). You can achieve that in the standard C way, by using the #include statements like this:

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

The above lines must be written every time, if you want to use the Autonomous-Car Arduino library.

API components

Car(unsigned short steeringWheelPin, unsigned short escPin)

The constructor of a Car instance. You have to instantiate a Car in order to be able to control it. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements. The constructor can optionally receive two arguments, specifying the (PWM) pins that the steering wheel Servo motor and the ESC will be attached to. If no arguments are supplied, then some default values (DEFAULT_SERVO_PIN and DEFAULT_ESC_PIN in AndroidCar/Car.cpp) will be applied instead. Note: It does not really matter if you use an int instead of unsigned short, as arguments, as long as you remember that pins are almost always a small natural number.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

const int SERVO_PIN = 4;
const int ESC_PIN = 6;

Car car(SERVO_PIN, ESC_PIN);
//Car car(); //could have also be used like this if you want to use the default pins

void setup(){
  // put your setup code here, to run once:
}

void loop(){
  // put your main code here, to run repeatedly:
}

void begin()

Always use this function first in the void setup() in order to initialize the car. This function initializes the ESC and the steering wheel Servo motor, therefore is crucial to the total functionality of the Autonomous-car.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

const int SERVO_PIN = 4;
const int ESC_PIN = 6;

Car car(SERVO_PIN, ESC_PIN);

void setup(){
  car.begin();
}

void loop(){
  // put your main code here, to run repeatedly:
}

void setSpeed(int speed)

Set the speed that the motors will run. The variable int speed, is in reality how much you want to deviate from the "neutral" (immobilized) state, in microseconds. If for example the ESC's neutral state is at 1500 μsec then setSpeed(-500), is interpreted usually as the maximum reverse speed, while setSpeed(500) is full speed forward speed. The maximum and minimum values of int speed are defined in the constants MAX_FRONT_SPEED and MAX_BACK_SPEED, which can be found in AndroidCar/Car.cpp. If an out of range value is supplied, either too large or too small, it will be constrained to the maximum and minimum allowed values respectively.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

const int SERVO_PIN = 4;
const int ESC_PIN = 6;

Car car(SERVO_PIN, ESC_PIN);

void setup(){
  car.begin();
  car.setSpeed(0); //make sure you immobilize the car after you've started it
  delay(1000); //wait for one second
}

void loop(){
 car.setSpeed(200); //writes the value of 1500 μsec to the ESC
 delay(1000);
 car.setSpeed(-200); //writes the value of 1300 μsec to the ESC
 delay(1000);
}

void setAngle(int degrees)

Sets the steering wheel angle, that will allow you to steer the car. The minimum and the maximum degrees that the steering wheel can deviate from the "middle" or "straight" position, are defined in MAX_RIGHT_DEGREES and MAX_LEFT_DEGREES at AndroidCar/Car.cpp. Usually, the Servo motor's shaft is at its "middle" position at 0 degrees and can go from -90 to 90 degrees. Therefore, when int degrees = 0 the steering wheel is at its "middle" position, as defined by the STRAIGHT_WHEELS in AndroidCar/Car.cpp.

Example

car.setAngle(-20); //20 degrees (usually) to the left
car.setAngle(20); //20 degrees (usually) to the right

int getSpeed()

Returns the speed currently supplied to the ESC. If the user has previously supplied an out of range value in setSpeed(int speed) then getSpeed() will return the value that was actually written to the ESC.

Example

car.setSpeed(200);
int currentSpeed = car.getSpeed(); //currentSpeed == 200
car.setSpeed(-5550); //an invalid value
currentSpeed = car.getSpeed(); //currentSpeed == -200 or whatever the minimum allowed speed is

int getAngle()

Returns the speed currently supplied to the steering Servo motor. If the user has previously supplied an out of range value in setAngle(int degrees) then getAngle() will return the value that was actually written to the Servo motor.

Example

car.setAngle(-25);
int currentAngle = car.getAngle(); //currentSpeed == -25
car.setAngle(300); //an invalid value
currentAngle = car.getAngle(); //currentSpeed == 25 or whatever the maximum allowed speed is

Sonar()

The constructor of a Sonar instance, representing programmatically an ultra sound sensor that measures distance. You have to instantiate a Sonar in order to be able to control it. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements. Don't forget that you can instantiate many sensors, as long as they are on different pins.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Sonar rearSonar;
    
void setup(){
/* put your setup code here to run once */
}
void loop(){
/* your main loop code here to run repeatedly */
}

void attach(unsigned short triggerPin, unsigned short echoPin)

Always use this function first in the void setup() in order to initialize the Sonar and define the pins that it will be connected to, namely the echo pin and the trigger pin. Don't forget that you can attach many sensors as long as they are on different pins. Note: It does not really matter if you use an int instead of unsigned short, as arguments, as long as you remember that pins are almost always a small natural number.

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>
Sonar rearSonar;
const int TRIG_PIN = 38; //sensor's trig pin
const int ECHO_PIN = 39; //sensor's echo pin

void setup(){
    rearSonar.attach(TRIG_PIN, ECHO_PIN);
}

unsigned int getDistance()

Get the distance measured by the specific ultra sound sensor in centimeters. The maximum distance that the ultra sound sensor can reliably measure in real life conditions is set around 150 centimeters. The Autonomous-car does not care about distances over 70 centimeters so the maximum distance is set to that value. If a distance is out of range (either too close or too far away) 0 will be returned instead, as an indication of an error.

Example

int rearDistance = rearSonar.getDistance();

unsigned int getMedianDistance()

Get the median distance of the last 5 measurements by the specific ultra sound sensor, in centimeters. The most distance that the ultra sound sensor can reliably measure in real life conditions is around 150 centimeters. The Autonomous-car does not care about distances over 70 centimeters so the maximum distance is set to that value. Expect a delay, between the measurements, of approximately 150 milliseconds when using this method. This is a simple and handy filter for the ultra sound sensor measurements.

Example

int rearDistance = rearSonar.getMedianDistance(); //get the median of the last 5 measurements

unsigned int getMedianDistance(int iterations)

Get the median distance of the last iterations measurements by the specific ultra sound sensor, in centimeters. The most distance that the ultra sound sensor can reliably measure in real life conditions is around 150 centimeters. The Autonomous-car does not care about distances over 70 centimeters so the maximum measurable distance is set to that value. If a distance is out of range (either too close or too far away) 0 will be returned instead, as an indication of an error. Expect a delay, between the measurements, of approximately 29 milliseconds for every iteration when using this method. This is a simple, flexible and handy filter for the ultra sound sensor measurements.

Example

int rearDistance = rearSonar.getMedianDistance(3); //get the median of the last 3 measurements

Sharp_IR()

The constructor of a Sharp_IR instance, representing programmatically an SHARP (GP2D120) infrared sensor that measures distance. You have to instantiate a Sharp_IR in order to be able to control it. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements. Don't forget that you can instantiate many sensors, as long as they are on different analog pins.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Sharp_IR frontIR;

void setup(){
/* put your setup code here to run once */
}
void loop(){
/* your main loop code here to run repeatedly */
}

void attach(unsigned short IR_pin)

Always use this function first in the void setup() in order to initialize the Sharp_IR and define the analog pin that it will be connected to. Don't forget that you can attach many sensors as long as they are on different analog pins. Note: It does not really matter if you use an int instead of unsigned short, as arguments, as long as you remember that pins are almost always a small natural number.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Sharp_IR frontIR;
const int IR_pin = A5; //set analog pin 5 to receive infra red's data

void setup(){
  frontIR.attach(IR_pin); //attach infra red sensor to IR_pin
}

unsigned int getDistance()

Get the distance measured by the specific infra red sensor in centimeters. The maximum distance that the infra sound sensor (GP2D120) can reliably measure in real life conditions is set to 25 centimeters, while minimum at 4 centimeters. If a distance is out of range (either too close or too far away) 0 will be returned instead, as an indication of an error.

Example

int frontDistance = frontIR.getDistance();

unsigned int getMedianDistance()

Get the median distance of the last 5 measurements by the specific infra red sensor, in centimeters. The maximum distance that the infra red sensor (GP2D120) can reliably measure in real life conditions is set to 25 centimeters, while minimum at 4 centimeters. If a distance is out of range (either too close or too far away) 0 will be returned instead, as an indication of an error. Expect a delay, needed between the measurements, of approximately 75 milliseconds when using this method. This is a simple and handy filter for the infra red sensor measurements.

Example

int frontDistance = frontIR.getMedianDistance(); //get the median of the last 5 measurements

unsigned int getMedianDistance(int iterations)

Get the median distance of the last iterations measurements by the specific infra red sensor, in centimeters. The maximum distance that the infra red sensor can reliably measure in real life conditions is set to 80 centimeters, while minimum at 20 centimeters. If a distance is out of range (either too close or too far away) 0 will be returned instead, as an indication of an error. Expect a delay, between the measurements, of approximately 15 milliseconds for every iteration when using this method. This is a simple and handy filter for the infra red sensor measurements.

Example

int frontDistance = frontIR.getMedianDistance(3); //get the median of the last 3 measurements

Odometer()

The constructor of an Odometer instance, representing programmatically an odometer (speed encoder) sensor that measures motor revolutions and thus an approximation of the traveled distance. You have to instantiate an Odometer in order to be able to read its data. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements.

IMPORTANT

  • You can only instantiate the odometer once. With limited modifications, the library can handle two (or more) encoders, if necessary.
  • Connect the odometer data line only to interrupt pins! Find out which those are for your board here.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Odometer encoder; //instantiate the odometer

void setup(){
/* put your setup code here to run once */
}
void loop(){
/* your main loop code here to run repeatedly */
}

int attach(unsigned short odometerPin)

Always use this function in order to initialize the Odometer and define the interrupt pin that it will be connected to. Don't forget that you can attach attach just one odometer and that only on an interrupt pin. If the pin is not a valid, then the function will return 0 to indicate an error, otherwise if everything works as it returns 1. Keep in mind that you do not necessarily have to do this during setup() and that that interrupt pin should not be used for other purposes as long the Odometer is attached. Note: It does not really matter if you use an int instead of unsigned short, as arguments, as long as you remember that interrupt pins are almost always a small natural number.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Odometer encoder;
const int encoderPin = 19; //digital pin 19 (interrupt 4 on arduino mega)

void setup(){
    encoder.attach(encoderPin);
}
void loop(){
/* your main loop code here to run repeatedly */
}

void begin()

Initiate a measurement by the Odometer. Call this function every time you want to start measuring the traveled distance of the Autonomous-car. Remember that you have to first attach(unsigned short odometerPin) the Odometer to a valid interrupt pin before you start measuring. If the Odometer is not attached then this function will have no effect. Moreover, if this function is omitted, then the measurement will begin from the last attach(unsigned short odometerPin), so it is strongly suggested to use this function for clarity.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Odometer encoder;
const int encoderPin = 19; //digital pin 19 (interrupt 4 on arduino mega)

void setup(){
    encoder.attach(encoderPin);
    encoder.begin();
}
void loop(){
/* your main loop code here to run repeatedly */
}

unsigned int getDistance()

Get the current traveled distance, in centimeters, since the beginning of the measurement. In other words since the last begin(). If begin() has been omitted, then you will get the distance since the last attach(int odometerPin), however this is not suggested for clarity reasons. If the Odometer is not attached or has been attached to an invalid (non-interrupt) pin, then this function will keep returning 0. The traveled distance has been empirically determined for the Autonomous-car platform and is set to 0.5 pulses per centimeter. If you are using a different set up, please adjust the PulsesToCentimeters macro in Odometer.cpp

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Odometer encoder;
const int encoderPin = 19; //digital pin 19 (interrupt 4 on arduino mega)

void setup(){
    Serial.begin(9600);
    encoder.attach(encoderPin);
    encoder.begin(); // begin measurement HERE
}
void loop(){
    int traveledDistance = encoder.getDistance(); //get distance traveled since begin() in setup()
    Serial.println(traveledDistance); // print the traveled distance
    delay(200); //run the above every 200 milliseconds
}

void detach()

Use this function in order to detach an Odometer from its assigned (interrupt) pin. Call this method in order to free the odometer pin, so it's no longer used by the Odometer and can be possibly used for different purposes or different sensors. After detaching an Odometer, getDistance() will keep returning 0 and begin() will have no effect. If you want to reattach an odometer, just call the attach(unsigned short odometerPin) method again.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Odometer encoder;
const int encoderPin = 19; //digital pin 19 (interrupt 4 on arduino mega)

void setup(){
    Serial.begin(9600);
    encoder.attach(encoderPin);
    encoder.begin(); // begin measurement HERE
    delay(10000); //wait for 10 seconds (while the car is traveling)
    int traveledDistance = encoder.getDistance(); //get distance traveled since begin()
    Serial.println(traveledDistance); //print the traveled distance
    encoder.detach();
    delay(5000); //wait for 5 seconds (while the car keeps traveling)
    traveledDistance = encoder.getDistance(); // traveledDistance = 0 !
    Serial.println(traveledDistance); //will print 0
}
void loop(){
/* your main loop code here to run repeatedly */
}

Gyroscope()

The constructor of a Gyroscope instance, representing programmatically a gyroscope, a sensor that measures angular velocity in X,Y,Z axis and thus an approximation of angular displacement. To put it simply, you can use a gyroscope to determine how much you have rotated. You have to instantiate an Gyroscope in order to be able to read its data. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements.

IMPORTANT

  • You can only instantiate the gyroscope once.
  • Connect the gyroscope only only to SDA and SCL pins! Find out which those are for your board here.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Gyroscope gyro;

void setup(){
/* put your setup code here to run once */
}
void loop(){
/* your main loop code here to run repeatedly */
}

void attach()

Always use this function in order to initialize the gyroscope and establish the connection to it. Don't forget that you can attach attach just one gyroscope and that only on the appropriate pins. Keep in mind that you do not necessarily have to do this during setup(). Finally, it is advised that you give it some time to set up the connection and get ready, with a delay of around 1.5 seconds.

Example

gyro.attach(); //initializes the gyroscope
delay(1500); //wait for it to get ready

void begin()

Initiate a measurement by the Gyroscope. Call this function every time you want to start measuring the angular displacement (rotation) of the Autonomous-car. Remember that you always have to first attach() the Gyroscope before you start measuring. Generally you should avoid measuring angular displacement over long periods of time, due to errors accumulating in the result, so it is advised to begin() every time you want to initiate a measurement.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Gyroscope gyro;

void setup() {
   gyro.attach(); //initializes the gyroscope
   delay(1500); //wait for it to get ready
   gyro.begin(); //start measuring angular displacement NOW
}

void loop() {
/* your main loop code here to run repeatedly */
}

void update()

Always have this function preferably in your main loop() or happening frequently, in order to get the latest measurements from the gyroscope.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Gyroscope gyro;

void setup() {
   gyro.attach(); //initializes the gyroscope
   delay(1500); //wait for it to get ready
   gyro.begin(); //start measuring angular displacement NOW
}

void loop() {
   gyro.update();
}

int getAngularDisplacement()

Get the current angular displacement, in degrees, since the beginning of the measurement. Negative values indicate counter clockwise rotation while positive clockwise. If you have different set up (orientation of gyroscope or different gyroscope model) you will have to adapt accordingly. This method will measure the angular displacement (rotation) since the last begin(). If begin() has been omitted, you will be receiving 0 as result, regardless of rotation. Keep in mind that the longer time has passed since the last begin() the less the accurate the results will be, due to error accumulation. Use begin() as often as you must in order to minimize the drift caused from errors. Always remember to use update() in your main loop along with this method.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Gyroscope gyro;

void setup() {
   Serial.begin(9600);
   gyro.attach(); //initializes the gyroscope
   delay(1500); //wait for it to get ready
   gyro.begin(); //start measuring angular displacement NOW
}

void loop() {
   gyro.update();
   Serial.println(gyro.getAngularDisplacement());
}

void stop()

Always use this method when you are done with a series of measurements, in order to free system resources. After you have used stop(), you need to use begin() in order to initiate a new measurement.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Gyroscope gyro;

void setup() {
    Serial.begin(9600);
    gyro.attach(); //initializes the gyroscope
    delay(1500); //wait for it to get ready
    gyro.begin(); //start measuring angular displacement NOW
}

void loop() {
    delay(20);
    gyro.update();
    Serial.println(gyro.getAngularDisplacement()); //print angular displacement since begin() after approximately 20 milliseconds
    gyro.stop();
    Serial.println(gyro.getAngularDisplacement()); //will print 0 as will the first print out on the next loop
}

Razorboard()

The constructor of a Razorboard that programmatically represents the Razor 9DOF IMU by Sparkfun. The Razorboard should be running the latest version of Attitude and Heading Reference System, found here. The Razorboard is used to specify the displacement from the North as a compass in order to define how much the car's heading has changed. Due to the placement of the Razorboard on Team Pegasus' vehicle, API components to get the current yaw have been devised, which can be very easily modified to get other axis as well. Additionally, the user can get direct access to the Razorboard's output. You have to instantiate an Razorboard, in order to be able to read its data. You should do this before your void setup() function in order for the instance variable to be globally accessible in your sketch and after the include statements.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Razorboard razor;

void setup(){
/* put your setup code here to run once */
}
void loop(){
/* your main loop code here to run repeatedly */
}

void attach(HardwareSerial *razorSerial)

Attach the Razorboard's output to a Serial port on your Arduino. RX from the Razorboard goes to the TX on the Arduino and vice versa. Note that you have to pass the reference to the Serial port you want to utilize, not its value. This method could be very easily modified to accept SoftwareSerial connections instead. You should always do this in your setup() function, before reading data from the Razorboard.

Example

#include <AndroidCar.h>
#include <Servo.h>
#include <Wire.h>

Razorboard razor;

void setup(){
  razor.attach(&Serial2); //attaching the Razorboard to the Serial2 port of Arduino Mega
}
void loop(){
/* your main loop code here to run repeatedly */
}

boolean available()

Returns a boolean depending on whether there is incoming data from the Razorboard. It is used the same way as the standard Arduino Serial.available(). It can be used in order to determine fast whether there is an incoming String from the Razorboard.

Example

if (razor.available()){
//read razorboard's input
}

String readLine()

Returns a string with the first line that is in the incoming buffer, from the Razorboard. This method keeps reading from the buffer until a new line character (\n) is detected and returns everything until then, without the new line character. Note that it will not return the most recent line supplied by the Razorboard, but the "oldest" one which can be found in the buffer. The readLine() method will return the first (oldest) line found in the buffer, if there is one, otherwise it will return the string error. Therefore it is safe to use without available().

Example

String razorInput = razor.readLine(); //will return the first (oldest) incoming line from the buffer, if there is one

String readLastLine()

Returns a string with the last (most recent) line that is currently in the incoming buffer, disregarding the previous ones. Works similarly to the readLine() with the difference that it will read the most recent incoming line coming from the Razorboard, disregarding the rest, which can be particularly useful in some occasions. This method will return error if nothing is incoming, therefore it is safe to use without available().

Example

String lastRazorInput = razor.readLastLine(); //will return the latest incoming line from the buffer, if there is one

int getHeading()

Parses the first incoming line found in the buffer in order to return the displacement from the North, in the Yaw axis. The output of this method ranges between -180 and 180, with 0 pointing to the North. If there is no incoming line, then -1000 is returned, therefore it is safe to use without available(). Keep in mind that this is not necessarily the most recent heading detected by the Razorboard, but rather the first (oldest) one found in the Serial buffer.

Example

int heading = razor.getHeading();
if (heading == -1000){
//error, no input detected
}

int getLatestHeading()

Parses the last incoming line found in the buffer in order to return the current displacement from the North, in the Yaw axis. The output of this method ranges between -180 and 180, with 0 pointing to the North. If there is no incoming line, then -1000 is returned, therefore it is safe to use without available(). This method will return the most recent heading measured by the Razorboard and disregard any previous readings, which can be useful in many occasions. If there is no incoming line, then -1000 is returned, therefore it is safe to use without available().

Example

int latestHeading = razor.getLatestHeading();
if (latestHeading == -1000){
//error, no input detected
}
Clone this wiki locally
You can’t perform that action at this time.
You signed in with another tab or window. Reload to refresh your session. You signed out in another tab or window. Reload to refresh your session.
Press h to open a hovercard with more details.