-
Notifications
You must be signed in to change notification settings - Fork 15
API documentation
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.
In order to start using the library in your Arduino sketch, you have to include the Autonomous-Car Arduino library, the Servo library and the Wire library. 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.
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 */
}
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);
}
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();
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
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
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 */
}
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
}
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();
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
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
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 */
}
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 */
}
Initiate a measurement by the Odometer. Call this function every time you want to start measuring the traveled distance of the Smartcar. 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 */
}
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 Smartcar platform and is set to 4 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
}
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 */
}
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 */
}
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
Initiate a measurement by the Gyroscope. Call this function every time you want to start measuring the angular displacement (rotation) of the Smartcar. 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 */
}
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();
}
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());
}
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
}