DFRduino Arduino Library  0.0.1
Provides an object used to control a DFRduino based robot
 All Classes Files Functions
Public Member Functions | List of all members
DFRduino Class Reference

Public Member Functions

 DFRduino ()
 
void setDirection (char direction)
 
void setMotors (int left, int right)
 
void setHorizontalHeadPosition (int angle)
 
void setVerticalHeadPosition (int angle)
 
int readDistanceInCentimeters ()
 

Constructor & Destructor Documentation

DFRduino::DFRduino ( void  )

Set up the sensors and motors.

15  {
16  initMotors();
17  initSensors();
18 }

Member Function Documentation

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

73  {
78  int distance = 1;
79  for (int i = 0; i < 10; i++) {
80  distance += 4800/(analogRead(DISTANCE_SENSOR_INPUT_PIN) - 20);
81  delayMicroseconds(2);
82  }
83  distance /= 10;
84 
85  if (distance > 150 || distance < 0)
86  return 150;
87  return distance;
88 }
void DFRduino::setDirection ( char  direction)

Sets the direction of the robot at 100% speed:

Parameters
directiontakes ones of the following: 'f': Forward, 'b': Backward, 'r': Right, 'l': Left
31  {
32  switch(direction) {
33  case ('f'):
34  setMotors(100, 100);
35  break;
36  case ('b'):
37  setMotors(-100, -100);
38  break;
39  case ('r'):
40  setMotors(100, -100);
41  break;
42  case ('l'):
43  setMotors(-100, 100);
44  break;
45  }
46 }
void setMotors(int left, int right)
Definition: DFRduino.cpp:52
void DFRduino::setHorizontalHeadPosition ( int  angle)

Sets the horizontal position of the head.

Parameters
angle(0,180) degrees

Positions: (from the robot's perspective) 90: Central 0: Left 180: Right

90  {
91  // Refactoring the attach out doesn't work
92  horizontalServo.attach(HORIZONTAL_SERVO_PIN);
93  horizontalServo.write(angle);
94 }
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
leftPercentage that the left motor is on (-100,100)
rightPercentage that the right motor is on (-100,100)
52  {
53  right = scaleSpeedToRangeOfInt(right);
54  left = scaleSpeedToRangeOfInt(left);
55 
56  if (left < 0) {
57  digitalWrite(LEFT_MOTOR_DIRECTION_CONTROL, HIGH);
58  analogWrite(LEFT_MOTOR_SPEED_CONTROL, -left);
59  } else {
60  digitalWrite(LEFT_MOTOR_DIRECTION_CONTROL, LOW);
61  analogWrite(LEFT_MOTOR_SPEED_CONTROL, left);
62  }
63 
64  if (right < 0) {
65  digitalWrite(RIGHT_MOTOR_DIRECTION_CONTROL, HIGH);
66  analogWrite(RIGHT_MOTOR_SPEED_CONTROL, -right);
67  } else {
68  digitalWrite(RIGHT_MOTOR_DIRECTION_CONTROL, LOW);
69  analogWrite(RIGHT_MOTOR_SPEED_CONTROL, right);
70  }
71 }
void DFRduino::setVerticalHeadPosition ( int  angle)

Sets the vertical position of the head.

Parameters
angle(0,180) degrees

Positions: 160: As downards as it can go 130: Central 0: Pointing upwards and backwards

96  {
97  if (angle >= 165) {
98  error("Too high an angle");
99  return;
100  }
101  // Refactoring the attach out doesn't work
102  verticalServo.attach(VERTICAL_SERVO_PIN);
103  verticalServo.write(angle);
104 }

The documentation for this class was generated from the following files: