ME 210 Mechatronics Final Project

Design Objective

Our prompt is to design an autonomous robot that is able to deliver good and bad press from the STUDIO to the audience and media. The objective is to deliver more good press to your audience than your opponent does to theirs, and/or deliver sufficient bad press to your opponent’s audience to offset their ratings.

Our robot will start in its respective STUDIO and compete head-to-head against another team’s robot. Here, we can manually pre-load 4x PRESS which are represented by balls, 1.6in in diameter. The objective is to transport the PRESS from the STUDIO to your AUDIENCE. However, our opponent will be working against us in two ways, delivering good PRESS to their own AUDIENCE and bad PRESS to our AUDIENCE.

The Game

Rules of the Game

  • The robot must start in its respective STUDIO with random orientation.

  • It must orient itself, and place at least one ball in its own good press bucket and one ball in its opponent’s bad press bucket.

  • Up to 4 balls can be manually loaded in or on the robot only when it is in the Film Studio.

  • When the robot is in the STUDIO it may only be interacted with via a button, switch, or potentiometer.

  • The robot’s control software must only be executed from the flash memory of the Arduino UNO.

  • IR beacons will be placed near each STUDIO, emitting a frequency of either 3333 Hz or 909 Hz.

  • Red tape will be placed from the STUDIO to the press buckets as illustrated. Black tape will be placed between each half of the playing field and the scales.

  • Each good press for your FILM’s scale is scored as 3 points. Each bad press on your FILM’s scale removes 2 points from your score.

Game Field

Our Strategy

Our approach was to favor simplicity and consistency. To do this we chose to have our robot line follow and dump the PRESS directly into the bucket, as opposed to riskier strategies like trying to shoot the PRESS as projectiles into the bucket. Our robot checked off functionality by following a set of repeatable steps:

  1. To orient, we turned in place until an IR phototransistor sensed the IR beacon directly to the right of the robot. Then the robot moved forward until it was out of the studio.

  2. From there, the robot will make use of the “Red Carpet” for line following using IR emitter/sensor pairings mounted to the bottom of the robot. The robot will line follow favoring right turns, until the black tape in front of the good press bucket is sensed.

  3. Then the robot will quickly use a servo motor to drop a single ball out of the chute, allowing gravity to deliver the ball into the bucket.

  4. The robot will then back up and turn 180 degrees before following the line again. After once again favoring right turns during the line following, the robot will sense black tape again, this time in front of the bad press bucket.

  5. Finally, the robot will open the chute with the servo motor once again, allowing the remaining balls to fall into the bad press bucket, and completing the check off.

Mechanical Design

Chassis Design

Our goal was to make the robot as simple as possible, beginning with the chassis design. The chassis consists of two layers, each cut from a sheet of acrylic with a laser cutter. The Main layer is used as a platform to support the arduino, breadboards, and drive train. There are dedicated screw holes for the motor mounts, roller, L298N, and all threaded rods which rigidly connect the bottom layer to the main layer. The bottom layer is a thin rectangle used to fix four IR emitter/detector sensors 3 mm from the ground, since that is the distance they are designed to work best at.

Powertrain

The drivetrain consists of 2 12V 200 RPM motors in line with each other near the front of the chassis. These motors are attached to the chassis via motor mounts on the underside of the chassis. These motors are attached to shaft couplers, which are then attached to 2 inch shafts which connect into the wheel mounts on the wheels. The rear of the chassis is supported by a 1 inch diameter ball bearing roller which rolls freely. The choice to use this design was for simplicity, as we would only need to control two wheels. Additionally, because our strategy involved line following, our movement only needed to consist of moving forward, backward, and turning left and right, and therefore we did not need to use omni wheels.

Delivery System

The delivery system consists of a simple gravity fed chute with an end effector powered by a 9g servo motor. It is cut out of sheets of acrylic from a laser cutter, and pieced together by peg and slot. This entire system is mounted on top of the main layer of the chassis, and is situated such that the exit of the chute sits high off the ground. This added height is to allow for the variable heights of the press buckets which sit on movable scales.

Sensor Location

Our strategy required that we are able to detect the IR beacon directly to the right of the robot, and be able to detect the lines of tape on the floor of the stage. In order to sense the IR beacon, we lifted a phototransistor off the base of the chassis to point it directly at the beacon, which is situated 7 inches from the floor.

In order to sense the tape on the floor of the stage, we attached four IR tape sensors to a rigid acrylic board, and attached this board to the main chassis via two all thread rods. The acrylic board was used to keep all four sensors at the same height off the ground, and the all thread rod connections allowed for this height to be changed fluidly depending on the sensitivity of the sensors.

Electrical Design

Overall Circuit

The overall circuitry of GARBO is pretty simple. It uses 8 digital out pins and 5 analog in pins to perform all its movement and sensing. A pinout table is included.

Featured electronic devices are a single L298N motor driver H-bridge, 4 IR line sensors including both a phototransistor and IR LED, and 2 9g servos for bucket opening and flag movements.

Power

The power for our robot is supplied through a 7.2V NiMH battery. This battery supplies both the motors through the L298N as well as the Arduino. From there, the Arduino supplies power to a 5V rail. This rail powers the IR phototransistor and the IR tape sensors, as well as the 2 9g servo motors.

Motor Driver

To drive our motors we used an L298N. The H-bridge allowed us to spin the wheels in either direction. The ZYTD520 motors have a free running current of 30mA which is is well within the L298N current rating of 2A per channel. While the motors can draw up to 0.65 A at stall, we would never hold any of the motors in stall, and they were always at high speeds. The direction and speed of each motor can be controlled independently. The direction of each motor is controlled by flipping the LOW-HIGH combination of the direction control pins on the L298N. The speed of the motors are controlled by varying the PWM to the enable pin for each motor. This capability allowed for us to control when we wanted to make swing turns and point turns.

Line Sensing

Line sensor resistance values were determined experimentally to find a comfortably high threshold to distinguish between dark and light. We were advised to use a slightly dimmer light and higher sensitivity than we'd used in the past, which led us to resistor choices of 470 ohms on the LEDs with 100k ohms on the phototransistors. With these resistor values combined, much of our line sensing was able to be resolved on the software side.

Beacon Sensing

Much like our line following sensors, resistor values for our beacon phototransistor were determined experimentally. We knew we wanted a high voltage to be difficult to hit, as our sensor would have to ignore the opposing side's beacon, leading us to use a 6.8 kiloohm resistor with our phototransistor to create a simple analog beacon finder. A high voltage threshold ensured the robot's light sensor would be pointed straight at the beacon each time it ran!

Servos

Our final wired components were 2 9g servo motors, each of which was supplied from our arduino's 5V rail and controlled with a simple digital pin. Pins 11 and 12 were available and easily accessible, so we chose to use those pins to control our servos.

Software Design

Summary and Strategy

Much like the rest of the design, our code was designed to simplify the lives of its creators while still achieving great functionality. It features two simple line-following algorithms, reuse of a single timer, and lots of individual states to break down functions of the robot into passive states, such as line following and driving forward, and finite timed actions, like depositing a ball or snapping onto a branched line.

State Diagrams

The two state diagrams describe the bulk of GARBO's processes, with the first describing our total checkoff strategy. By attacking both buckets in a single move, the robot can maximize its chance of success. The second diagram shows a fairly general line following algorithm, which the robot uses to track lines very accurately. By turning towards the line at all times, the robot straddles the line with great consistency.

Complete Code

Our robot features 2 different code trims, one used to check off, and the other used to compete. The check off code attacks both buckets in a single run, whereas the competition code exclusively targets the good press bucket.

  • #include <Servo.h>

    typedef enum {

    STATE_HELLO_WORLD, STATE_ALIGNING, STATE_ESCAPING, STATE_SPACE_BUFFERING, STATE_APPROACHING, STATE_DEPOSITING, STATE_BACKING_UP,

    STATE_ROTATING, STATE_RETURNING, STATE_BRANCHING, STATE_ENDGAME, STATE_DONE

    } States_t; // state structure ripped almost directly from the starter code for the raptor project!

    States_t state;

    Servo armServo;

    Servo flagServo;

    int THRESHOLD = 777; // Line reading threshold is high enough to see the black tape under red tape

    int BEACON_THRESHOLD = 950;

    bool inAction = false;

    bool allDone = false;

    int actionTimer; // action timer allows actions to take place for finite periods of time

    int gameTimer;

    void leftForward(int);

    void rightForward(int);

    void leftBackward(int);

    void rightBackward(int); // simple motor driving controls make coding a lot easier

    void checkGlobalEvents(void);

    void lineFollowRight(void);

    void lineFollowLeft(void);

    void stop(void);

    void closeBucket(void);

    void openBucket(void);

    void lineFollowBackwards(void);

    void swingRight(void);

    void branchConnect(void);

    void flaunt(void);

    void flagUp(void);

    void flagDown(void);

    void align(void);

    void bufferAngle(void);

    void arc(void);

    bool TestForStudio(void);

    void RespToStudio(void);

    void setup() {

    state = STATE_HELLO_WORLD;

    armServo.attach(11);

    flagServo.attach(12);

    flagUp();

    closeBucket();

    gameTimer = millis(); // keeps track of how long we've been in the game, if it's more than 130 seconds, we stop all the robot's functions!

    }

    void loop() {

    checkGlobalEvents(); // look for the the game timer, full black barriers, and studio exits

    switch (state) { // tons of states, makes each action more isolated and controllable with a single timer

    case STATE_HELLO_WORLD:

    flaunt(); // move the flag up and down and prepare to align!

    break;

    case STATE_ALIGNING:

    align(); // spin until our phototransistor sees a beacon!

    break;

    case STATE_ESCAPING:

    lineFollowRight(); // use a line following procedure to escape. makes the robot more perpendicular with the studio walls!

    break;

    case STATE_SPACE_BUFFERING:

    bufferSpace(); // drive forward a bit to avoid studio double detection!

    break;

    case STATE_APPROACHING:

    lineFollowRight(); // line follow favoring right turns, gets GARBO to the good press bucket!

    break;

    case STATE_DEPOSITING: // deposit a single ball into the good press bucket!

    deposit();

    break;

    case STATE_BACKING_UP: // back away from the ledge!

    backAway();

    break;

    case STATE_ROTATING: // spin around to snap onto the line facing the opposite direction!

    oneEightyRight();

    break;

    case STATE_RETURNING: // line follow back favoring left turns, with added functionality to snap to wide right branches!

    lineFollowLeft();

    break;

    case STATE_BRANCHING: // pull an aggressive right turn and snap to the branching line!

    branchConnect();

    break;

    case STATE_ENDGAME: // line follow until we see the border of the game field. once seen, deposit the remaining balls into the bad press bucket!

    lineFollowRight();

    break;

    case STATE_DONE: // stop the robot's motors, and wave the flag one more time!

    stop();

    break;

    default: // Should never get into an unhandled state

    Serial.println("What is this I do not even...");

    }

    }

    void swingRight() { // begin a swing turn to the right

    rightBackward(255);

    }

    void checkGlobalEvents() { // ensure we still have time left in the game, and check if we're over a barrier or the studio

    if (millis() - gameTimer >= 130000) RespToTimer();

    if (TestForBarrier()) RespToBarrier();

    if (TestForStudio()) RespToStudio();

    }

    void RespToTimer() { // when time is up, if we haven't already, wave the flag. then, enter the done state, stopping the robot!

    if (! allDone) {

    flagDown();

    delay(500); // the only blocking code in the whole thing! once the game's over, the timing shouldn't matter much anymore

    flagUp();

    allDone = true;

    }

    state = STATE_DONE;

    }

    void backAway() { // sends the robot straight backwards for 900 milliseconds

    if (!inAction) {

    leftBackward(200);

    rightBackward(200);

    actionTimer = millis(); // this pattern of code: setting the action timer, and toggling the inAction boolean, creates finite timed actions without using a ton of timers

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 900) {

    stop();

    inAction = false;

    state = STATE_ROTATING;

    }

    }

    }

    void oneEightyRight() { // turn 180 degrees to the right. this function will also snap onto the next line it sees

    if (!inAction) {

    leftForward(255);

    rightBackward(255);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 750 && analogRead(A1) <= THRESHOLD) { // turn the robot for at least 750 milliseconds, then wait for the inner left sensor to see a line before linefollowing again

    stop();

    inAction = false;

    state = STATE_RETURNING;

    }

    }

    }

    bool TestForBarrier() { // see if all the line sensors are dark

    return (analogRead(A0) <= THRESHOLD && analogRead(A1) <= THRESHOLD && analogRead(A2) <= THRESHOLD && analogRead(A3) <= THRESHOLD);

    }

    void RespToBarrier() { // if we're approaching the good press, begin depositing

    if (state == STATE_APPROACHING) {

    stop();

    state = STATE_DEPOSITING;

    }

    if (state == STATE_ENDGAME) { // if we're approaching the bad press, open the bucket all the way indefinitely and stop

    stop();

    openBucket();

    state = STATE_DONE;

    }

    }

    bool TestForStudio() { // looks for the inner two line sensors to be dark before recognizing the studio

    return (analogRead(A1) <= THRESHOLD && analogRead(A2) <= THRESHOLD && state == STATE_ESCAPING);

    }

    void RespToStudio() { // if we see a studio when we're escaping, do a flag flourish, and move forward just a bit to avoid double detections

    if (state == STATE_ESCAPING) {

    stop();

    flagDown();

    delay(500);

    flagUp();

    state = STATE_SPACE_BUFFERING;

    }

    }

    void deposit() { // open the bucket servo for only 110 milliseconds, then slam it shut quickly!

    if (! inAction) {

    stop();

    openBucket();

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 110) {

    closeBucket();

    inAction = false;

    state = STATE_BACKING_UP;

    }

    }

    }

    void lineFollowLeft() { // line follow with preferences for left turns. if the far right sensor sees something, address the branch on the right

    if (! inAction) { // the first time through, set a one second timeout on branch detection, should avoid early accidental trips

    actionTimer = millis();

    inAction = true;

    }

    if (analogRead(A1) <= THRESHOLD) { // if the inner left bumper senses a line, make a sharp turn left

    leftBackward(200);

    rightForward(200);

    }

    else if (analogRead(A3) <= THRESHOLD && millis() - actionTimer >= 1000) { // if the far right sensor sees a line and the timeout is passed, begin snapping to the branch on the right

    stop();

    inAction = false;

    state = STATE_BRANCHING;

    }

    else if (analogRead(A2) <= THRESHOLD && analogRead(A3) > THRESHOLD) { // if the inner right bumper sees a line and the outer right doesn't, turn right sharply

    leftForward(200);

    rightBackward(200);

    }

    else { // in any other case, move forward!

    moveForward(200);

    }

    }

    void lineFollowRight() { // line follow favoring right turns! avoids the branch if it's on the left side

    if (analogRead(A2) <= THRESHOLD) { // turn sharply into the inner right bumper if it sees a line

    leftForward(200);

    rightBackward(200);

    }

    else if (analogRead(A1) <= THRESHOLD && analogRead(A0) > THRESHOLD) { // turn left if the inner left sees a line and the outer left doesn't

    leftBackward(200);

    rightForward(200);

    }

    else { // otherwise, move forward!

    moveForward(200);

    }

    }

    void moveForward(int power) { // set each motor to the specified power going forward!

    leftForward(power);

    rightForward(power);

    }

    void stop() { // turn off both motors, allowing the robot to coast to a stop

    digitalWrite(3, LOW);

    digitalWrite(5, LOW);

    }

    void leftForward(int power) { // set the left motor to the specified power going forward

    analogWrite(3, power);

    digitalWrite(10, HIGH);

    digitalWrite(9, LOW);

    }

    void rightForward(int power) { // set the right motor to the specified power going forward

    analogWrite(5, power);

    digitalWrite(8, HIGH);

    digitalWrite(7, LOW);

    }

    void leftBackward(int power) { // set the left motor to the specified power going backward

    analogWrite(3, power);

    digitalWrite(10, LOW);

    digitalWrite(9, HIGH);

    }

    void rightBackward(int power) { // set the right motor to the specified power going backward

    analogWrite(5, power);

    digitalWrite(8, LOW);

    digitalWrite(7, HIGH);

    }

    void closeBucket() { // close the bucket arm on the dispensing chute

    armServo.write(90);

    }

    void openBucket() { // open the bucket arm on the dispensing chute

    armServo.write(0);

    }

    void lineFollowBackwards() { // attempt to line follow going backwards! this function tends not to work too well, so it doesn't get used in our standard operation.

    if (analogRead(A2) <= THRESHOLD) {

    rightBackward(255);

    leftForward(255);

    }

    else if (analogRead(A1) <= THRESHOLD) {

    leftBackward(255);

    rightForward(255);

    }

    else {

    rightBackward(200);

    leftBackward(200);

    }

    }

    void branchConnect() { // connect to the branch on the return trip from the good press bucket!

    if (!inAction) { // point turn to the right for at least 400 milliseconds

    rightBackward(255);

    leftForward(255);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 400 && analogRead(A1) <= THRESHOLD) { // when 400 milliseconds have passed and the inner left sensor sees a line, stop and start line following again

    stop();

    inAction = false;

    state = STATE_ENDGAME;

    }

    }

    }

    void flaunt() { // when the game starts, show off a bit!

    if (! inAction) { // flip the flag down for 500 milliseconds

    inAction = true;

    actionTimer = millis();

    flagDown();

    }

    else {

    if (millis() - actionTimer >= 500) { // after 500 milliseconds, flip the flag up and begin aligning to the beacon

    flagUp();

    state = STATE_ALIGNING;

    inAction = false;

    }

    }

    }

    void flagUp() { // put up the flag!

    flagServo.write(90);

    }

    void flagDown() { // put down the flag!

    flagServo.write(0);

    }

    void align() { // begin turning right until we sense the beacon!

    rightBackward(200);

    leftForward(200);

    if (analogRead(A4) >= BEACON_THRESHOLD) { // once we see the phototransistor cross the threshold, stop turning furiously and begin escape protocols!

    stop();

    state = STATE_ESCAPING;

    }

    }

    void bufferSpace() { // add a little distance buffer to our escape lineup, avoiding double detections

    if (! inAction) { // move forward quickly for 750 milliseconds

    leftForward(200);

    rightForward(200);

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 750) {

    stop();

    inAction = false;

    state = STATE_APPROACHING;

    }

    }

    }

    void arc() { // arc with a gentle bend to the right. our beacon alignment worked well enough that this function became mostly unnecessary

    if (! inAction) {

    leftForward(255);

    rightForward(200);

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 750 && analogRead(A1) >= THRESHOLD) {

    stop();

    inAction = false;

    state = STATE_APPROACHING;

    }

    }

    }

  • #include <Servo.h>

    typedef enum {

    STATE_HELLO_WORLD, STATE_ALIGNING, STATE_ESCAPING, STATE_SPACE_BUFFERING, STATE_APPROACHING, STATE_DEPOSITING, STATE_BACKING_UP,

    STATE_ROTATING, STATE_RETURNING, STATE_BRANCHING, STATE_ENDGAME, STATE_DONE

    } States_t;

    States_t state;

    Servo armServo;

    Servo flagServo;

    int THRESHOLD = 777;

    int BEACON_THRESHOLD = 950;

    bool inAction = false;

    bool allDone = false;

    int actionTimer;

    int boxTimer;

    int gameTimer;

    void leftForward(int);

    void rightForward(int);

    void leftBackward(int);

    void rightBackward(int);

    void checkGlobalEvents(void);

    void lineFollowRight(void);

    void lineFollowLeft(void);

    void stop(void);

    void closeBucket(void);

    void openBucket(void);

    void lineFollowBackwards(void);

    void swingRight(void);

    void branchConnect(void);

    void flaunt(void);

    void flagUp(void);

    void flagDown(void);

    void align(void);

    void bufferAngle(void);

    void arc(void);

    bool TestForStudio(void);

    void RespToStudio(void);

    void bufferSpace(void);

    void deposit(void);

    void lineFollowBack(void);

    void goInStudio(void);

    void setup() {

    state = STATE_HELLO_WORLD;

    armServo.attach(11);

    flagServo.attach(12);

    flagUp();

    closeBucket();

    gameTimer = millis();

    }

    void loop() {

    checkGlobalEvents();

    switch (state) {

    case STATE_HELLO_WORLD:

    flaunt();

    break;

    case STATE_ALIGNING:

    align();

    break;

    case STATE_ESCAPING:

    lineFollowRight();

    break;

    case STATE_SPACE_BUFFERING:

    bufferSpace();

    break;

    case STATE_APPROACHING:

    lineFollowRight();

    break;

    case STATE_DEPOSITING:

    deposit();

    break;

    case STATE_BACKING_UP:

    backAway();

    break;

    case STATE_ROTATING:

    oneEightyRight();

    break;

    case STATE_RETURNING:

    lineFollowBack();

    break;

    //case STATE_BRANCHING:

    //branchConnect();

    //break;-

    case STATE_ENDGAME:

    lineFollowRight();

    break;

    case STATE_DONE:

    stop();

    break;

    default: // Should never get into an unhandled state

    Serial.println("What is this I do not even...");

    }

    }

    void swingRight() {

    rightBackward(255);

    }

    void checkGlobalEvents() {

    if (millis() - gameTimer >= 130000) RespToTimer();

    if (TestForBarrier()) RespToBarrier();

    if (TestForStudio()) RespToStudio();

    }

    void RespToTimer() {

    if (! allDone) {

    flagDown();

    delay(500);

    flagUp();

    allDone = true;

    }

    state = STATE_DONE;

    }

    void backAway() {

    if (!inAction) {

    leftBackward(200);

    rightBackward(200);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 900) {

    stop();

    inAction = false;

    state = STATE_ROTATING;

    }

    }

    }

    void oneEightyRight() {

    if (!inAction) {

    leftForward(255);

    rightBackward(255);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 750 && analogRead(A1) <= THRESHOLD) {

    stop();

    inAction = false;

    state = STATE_RETURNING;

    }

    }

    }

    bool TestForBarrier() {

    return (analogRead(A0) <= THRESHOLD && analogRead(A1) <= THRESHOLD && analogRead(A2) <= THRESHOLD && analogRead(A3) <= THRESHOLD);

    }

    void RespToBarrier() {

    if (state == STATE_APPROACHING) {

    stop();

    state = STATE_DEPOSITING;

    }

    if (state == STATE_ENDGAME) {

    stop();

    openBucket();

    state = STATE_DONE;

    }

    if (state == STATE_RETURNING) {

    boxTimer = millis();

    leftForward(200);

    rightForward(200);

    if (millis() - boxTimer > 100) {

    stop();

    delay(2000);

    state = STATE_ALIGNING;

    }

    }

    }

    bool TestForStudio() {

    return (analogRead(A1) <= THRESHOLD && analogRead(A2) <= THRESHOLD && (state == STATE_ESCAPING || state == STATE_RETURNING));

    }

    void RespToStudio() {

    if (state == STATE_ESCAPING) {

    stop();

    flagDown();

    delay(500);

    flagUp();

    state = STATE_SPACE_BUFFERING;

    }

    if (state == STATE_RETURNING) {

    goInStudio();

    }

    }

    void deposit() { //update with real procedures

    if (! inAction) {

    stop();

    openBucket();

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 400) {

    closeBucket();

    inAction = false;

    state = STATE_BACKING_UP;

    }

    }

    }

    void lineFollowBack() {

    if (analogRead(A2) <= THRESHOLD && analogRead(A3) > THRESHOLD) {

    leftForward(200);

    rightBackward(200);

    }

    else if (analogRead(A1) <= THRESHOLD && analogRead(A0) > THRESHOLD) {

    leftBackward(200);

    rightForward(200);

    }

    else {

    moveForward(200);

    }

    }

    void lineFollowLeft() {

    if (! inAction) {

    actionTimer = millis();

    inAction = true;

    }

    if (analogRead(A1) <= THRESHOLD) {

    leftBackward(200);

    rightForward(200);

    }

    else if (analogRead(A3) <= THRESHOLD && millis() - actionTimer >= 1000) {

    stop();

    inAction = false;

    state = STATE_BRANCHING;

    }

    else if (analogRead(A2) <= THRESHOLD && analogRead(A3) > THRESHOLD) {

    leftForward(200);

    rightBackward(200);

    }

    else {

    moveForward(200);

    }

    }

    void lineFollowRight() {

    if (analogRead(A2) <= THRESHOLD) {

    leftForward(200);

    rightBackward(200);

    }

    else if (analogRead(A1) <= THRESHOLD && analogRead(A0) > THRESHOLD) {

    leftBackward(200);

    rightForward(200);

    }

    else {

    moveForward(200);

    }

    }

    void moveForward(int power) {

    leftForward(200);

    rightForward(200);

    }

    void stop() {

    digitalWrite(3, LOW);

    digitalWrite(5, LOW);

    }

    void leftForward(int power) {

    analogWrite(3, power);

    digitalWrite(10, HIGH);

    digitalWrite(9, LOW);

    }

    void rightForward(int power) {

    analogWrite(5, power);

    digitalWrite(8, HIGH);

    digitalWrite(7, LOW);

    }

    void leftBackward(int power) {

    analogWrite(3, power);

    digitalWrite(10, LOW);

    digitalWrite(9, HIGH);

    }

    void rightBackward(int power) {

    analogWrite(5, power);

    digitalWrite(8, LOW);

    digitalWrite(7, HIGH);

    }

    void closeBucket() {

    armServo.write(90);

    }

    void openBucket() {

    armServo.write(0);

    }

    void lineFollowBackwards() {

    if (analogRead(A2) <= THRESHOLD) {

    rightBackward(255);

    leftForward(255);

    }

    else if (analogRead(A1) <= THRESHOLD) {

    leftBackward(255);

    rightForward(255);

    }

    else {

    rightBackward(200);

    leftBackward(200);

    }

    }

    void goInStudio() {

    if (!inAction) {

    rightForward(255);

    leftForward(255);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 100) {

    stop();

    delay(2000);

    inAction = false;

    state = STATE_ALIGNING;

    }

    }

    }

    void branchConnect() {

    if (!inAction) {

    rightBackward(255);

    leftForward(255);

    actionTimer = millis();

    inAction = true;

    }

    else {

    if (millis() - actionTimer >= 400 && analogRead(A1) <= THRESHOLD) {

    stop();

    inAction = false;

    state = STATE_ENDGAME;

    }

    }

    }

    void flaunt() {

    if (! inAction) {

    inAction = true;

    actionTimer = millis();

    flagDown();

    }

    else {

    if (millis() - actionTimer >= 500) {

    flagUp();

    state = STATE_ALIGNING;

    inAction = false;

    }

    }

    }

    void flagUp() {

    flagServo.write(90);

    }

    void flagDown() {

    flagServo.write(0);

    }

    void align() {

    rightBackward(200);

    leftForward(200);

    if (analogRead(A4) >= BEACON_THRESHOLD) {

    stop();

    state = STATE_ESCAPING;

    }

    }

    void bufferSpace() {

    if (! inAction) {

    leftForward(200);

    rightForward(200);

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 750) {

    stop();

    inAction = false;

    state = STATE_APPROACHING;

    }

    }

    }

    void arc() {

    if (! inAction) {

    leftForward(255);

    rightForward(200);

    inAction = true;

    actionTimer = millis();

    }

    else {

    if (millis() - actionTimer >= 750 && analogRead(A1) >= THRESHOLD) {

    stop();

    inAction = false;

    state = STATE_APPROACHING;

    }

    }

    }

Functionality Video

We were successfully able to complete the challenge! Our robot was able to deliver to both press bucket stations in a single run, and do so very quickly! Here is our checkoff run through, where we opted to deliver three press to our “GOOD” bucket, and one to the opponents “BAD” bucket:

Skills Learned

  • Our group had the mentality of successfully passing all requirements ASAP. We were able to do this significantly under budget and with days to spare by being scrappy and using simple mechatronics methods. We found that getting our bot moving and attempting the challenge early helped inform us about unforeseen challenges and exploits that simplified and streamlined our design.

  • This project taught me how to write code for microcontrollers to process sensor data and control the robot’s actions. I learned how to create and incorporate a robust state machine into the program to direct the robot accordingly.

  • This project taught me about electronics, such as calibrating sensors to ensure accurate data readings and responses. I also learned how to Incorporate actuators, such as motors and servos to control the robot's movements.

Previous
Previous

Volkswagen Senior Capstone: Wheelchair Access to Autonomous Vehicles

Next
Next

Track Actuator Analysis Rig