DFRduino::DFRduino |
( |
void |
| ) |
|
Set up the sensors and motors.
int DFRduino::readDistanceInCentimeters |
( |
| ) |
|
Reads the input from the IR sensor and calculates the distance to the object the IR light bounces off
- Returns
- Distance in cm (int).
Max distance detectable is 150cm
Min distance detectable is 20cm
79 for (
int i = 0; i < 10; i++) {
80 distance += 4800/(analogRead(DISTANCE_SENSOR_INPUT_PIN) - 20);
85 if (distance > 150 || distance < 0)
void DFRduino::setDirection |
( |
char |
direction | ) |
|
Sets the direction of the robot at 100% speed:
- Parameters
-
direction | takes ones of the following: 'f': Forward, 'b': Backward, 'r': Right, 'l': Left |
void setMotors(int left, int right)
Definition: DFRduino.cpp:52
void DFRduino::setHorizontalHeadPosition |
( |
int |
angle | ) |
|
Sets the horizontal position of the head.
- Parameters
-
Positions: (from the robot's perspective) 90: Central 0: Left 180: Right
92 horizontalServo.attach(HORIZONTAL_SERVO_PIN);
93 horizontalServo.write(angle);
void DFRduino::setMotors |
( |
int |
left, |
|
|
int |
right |
|
) |
| |
Set the motors as a percentage of their max speed. Anything lower than 30 doesn't do anything.
- Parameters
-
left | Percentage that the left motor is on (-100,100) |
right | Percentage that the right motor is on (-100,100) |
53 right = scaleSpeedToRangeOfInt(right);
54 left = scaleSpeedToRangeOfInt(left);
57 digitalWrite(LEFT_MOTOR_DIRECTION_CONTROL, HIGH);
58 analogWrite(LEFT_MOTOR_SPEED_CONTROL, -left);
60 digitalWrite(LEFT_MOTOR_DIRECTION_CONTROL, LOW);
61 analogWrite(LEFT_MOTOR_SPEED_CONTROL, left);
65 digitalWrite(RIGHT_MOTOR_DIRECTION_CONTROL, HIGH);
66 analogWrite(RIGHT_MOTOR_SPEED_CONTROL, -right);
68 digitalWrite(RIGHT_MOTOR_DIRECTION_CONTROL, LOW);
69 analogWrite(RIGHT_MOTOR_SPEED_CONTROL, right);
void DFRduino::setVerticalHeadPosition |
( |
int |
angle | ) |
|
Sets the vertical position of the head.
- Parameters
-
Positions: 160: As downards as it can go 130: Central 0: Pointing upwards and backwards
98 error(
"Too high an angle");
102 verticalServo.attach(VERTICAL_SERVO_PIN);
103 verticalServo.write(angle);
The documentation for this class was generated from the following files: