Final Project Report: The Clinton Foundation (Team 7)

ME 210: Introduction to Mechatronics Winter 2017



Part 1: The Robot

1.1  Mechanical Design

Below are the mechanical diagrams for the various subsystems used in the robot.

Robot (left):

Robot (back):

Robot (right):

Robot (front):

For the entire diagram file, click here.

1.2  Electronic Design

Below are the electrical schematics for the various subsystems used in the robot.

The high-level Arduino schematic:

Drivetrain:

Hopper:

Launcher:

Line Sensor:

Ultrasonic Sensor:

1.3  Algorithmic Design

The Arduino code we wrote for this project was carefully architected beforehand through the use of state machines (shown below). Then, these designs were translated to code, which was well-decomposed and well-commented.

A key innovation was the use of a function pointer void (*state)(void) to keep track of the state. With this approach, each separate state encapulates its own tests for events and responses, as well as any needed local variables.

For the entire code repository, click here.

Below is the main file, ExecutiveOrder66v1.ino, which has the following functionality:

  • define the global constants
  • set up the state machine
  • run the main loop, which only calls respond_to_global_events() and state()
  • implement all needed families of helper functions, including motors (driving motors using PWM), timer (timing functions), sonar (ultrasonic sensor), lsensor (line sensors), lfollow (line following using PID control), and lalign (line aligning using PID control)
  • set up debugging function / verbose mode


/*  =================================================================================================================
 *  FILE: ExecutiveOrder66v1.ino

 *  VERSION: 1
        Maintains original parameterization for gameplay strategy.

 *  DESCRIPTION:
        Main program for competition gameplay. The execution flow of the program is as follows:
            (1) Run ESCAPE subroutine to escape the Safe Space.
            (2) Follow opponent-specific strategy, determined in |SITE_BLOCK| and |SITE_LAUNCH|.
                (a) Run ADVANCE subroutine to move until oriented over perpendicaular black tape line.
                (b) Run LAUNCH subroutine to launch balls into safe space, specified by |SITE_LAUNCH|.
                (c) Run BLOCK subroutine to block the social media using the pressure buttons, specified by |SITE_BLOCK|
            (3) Run RESET subroutine to go back to the Safe Space to reload.
    ================================================================================================================= */

/*  =================================================================================================================
    SECTION: Global constants & objects.
    ================================================================================================================= */

/* Debugging & Testing */
#define VERBOSE_STATES      0           // whether to log state names
#define VERBOSE_SENSORS     0           // whether to log sensor readings
#define SERIAL_COMM         0           // whether serial communication is required (e.g. for calibration tests)
#define SERIAL_BAUD         115200      // baud rate for serial communication

/* Motors */
// NOTE: Written label right motor is #1, left motor is #2
#define DRIVE_R_PWM         9           // PWM output pin
#define DRIVE_R_DIR         8           // output pin
#define DRIVE_L_PWM         3           // PWM output pin
#define DRIVE_L_DIR         7           // output pin

#define DRIVE_SPEED         57          // drive motor base speed; calibrate this (!!); all time constants are based on this
#define DRIVE_L_COMP_FW     0           // left drive motor forward compensation factor; calibrate this (!!)
#define DRIVE_L_COMP_BK     5           // left drive motor backward compensation factor for left motor; calibrate this (!!)

/* Ultrasonic Sensor */
#define SONAR_PIN_TRIGGER   6           // trigger pin
#define SONAR_PIN_ECHO      4           // echo pin
#define SONAR_MAX_DISTANCE  40          // max sonar reading (cm)
#define SONAR_NUM_SMOOTH    5           // number of values to smooth over
NewPing sonar(SONAR_PIN_TRIGGER, SONAR_PIN_ECHO, SONAR_MAX_DISTANCE);

/* Launcher */
#define LAUNCHER_PWM        10          // PWM output pin
#define LAUNCHER_SPEED      33          // launcher wheel base speed

/* Hopper */
#define HOPPER_PIN_COMM     12          // PWM output pin

/* Line Follower */
#define LINE_NUM_SENSORS    5           // number of sensors used
#define LINE_PINS           ((unsigned char[]){A0, A1, A2, A4, A3})     // analog pins for line sensors
double line_sensor_vals[LINE_NUM_SENSORS];

/* Timer */
#define MAIN_TIMER_ID       9           // which timer channel to use for main program
#define RUN_TIME            130000      // counting 2m10s = 130s

/* Strategy Parameters */
#define SITE_LAUNCH         ((int[]){  -1, 4, 4, 4})    // whether to fire at each site; dummy -1 for index alignment
#define SITE_BLOCK          ((char[]){ -1, 0, 0, 0})    // whether to block ("fact-check") at each site; dummy -1 for index alignment (!!)


/*  =================================================================================================================
    SECTION: Global variables.
    ================================================================================================================= */

void (*state)(void);  // function pointer to current state
int site_id;  // keep track of location on board; 0 = safe space, 1-3 = social media sites


/*  =================================================================================================================
    SECTION: Main methods for main program.
    ================================================================================================================= */

/*
    FUNCTION: |setup|
        Run once to set up Arduino, initialize variables and state machine.
*/
void setup()
{
    #if VERBOSE_STATES || VERBOSE_SENSORS || SERIAL_COMM
    Serial.begin(SERIAL_BAUD);
    Serial.println(F("serial begin"));
    #endif

    // init pin modes
    pinMode(DRIVE_R_PWM, OUTPUT);
    pinMode(DRIVE_L_PWM, OUTPUT);
    pinMode(DRIVE_R_DIR, OUTPUT);
    pinMode(DRIVE_L_DIR, OUTPUT);
    pinMode(SONAR_PIN_TRIGGER, OUTPUT);
    pinMode(SONAR_PIN_ECHO, INPUT);
    pinMode(LAUNCHER_PWM, OUTPUT);
    pinMode(HOPPER_PIN_COMM, OUTPUT);
    for(unsigned char line_pin : LINE_PINS)
        pinMode(line_pin, INPUT);

    site_id = 0;  // initial location
    state = STATE_ESCAPE_INIT;  // initial state

    timer_start(MAIN_TIMER_ID, RUN_TIME);  // start main countdown timer (2m10s)
}

/*
    FUNCTION: |loop|
        Run continuously to handle state machine functionality.

    NOTES:
        Uses state machine by storing a function pointer named |state|, which points to a state function.
        This state function must take no arguments and return void; it handles all the tests and responses
        internally.
*/
void loop()
{
    respond_to_global_events();
    state();
}

/*
    FUNCTION: |respond_to_global_events|
        Test for global events that are common to all states in the state machine.
*/
void respond_to_global_events()
{
    if (timer_expired(MAIN_TIMER_ID) && state != STATE_NULL)
    {
        // cease all motor functions
        motors_set(0, 0);
        digitalWrite(LAUNCHER_PWM, LOW);
        digitalWrite(HOPPER_PIN_COMM, LOW);

        state = STATE_NULL;

        #if VERBOSE_STATES
        Serial.println(F("main timer expired"));
        Serial.println(F("cease all motor functions"));
        #endif
    }
}

/*
    STATE: |STATE_NULL|
        Do nothing. Save battery using delay.
*/
void STATE_NULL()
{
    delay(1000);
}


/*  =================================================================================================================
    SECTION: Helper methods: motors, timer, sonar
    ================================================================================================================= */

/*
    FUNCTION: |motors_set|
        Run the motors at the desired speed/direction. A value of 255 is full throttle forward,
        0 is stopped, -255 is full throttle backward. There is no ched on incoming parameter ranges.

    PARAMETERS:
        |left_speed|, |right_speed| - integer motor speed
            (255 full-throttle forward, 0 stopped, -255 full-throttle backward)
*/
void motors_set(int left_speed, int right_speed)
{
    // set right wheel
    analogWrite(DRIVE_R_PWM, abs(right_speed));
    digitalWrite(DRIVE_R_DIR, right_speed >= 0 ? HIGH : LOW);

    // set left wheel
    analogWrite(DRIVE_L_PWM, abs(left_speed) + (left_speed >= 0 ? DRIVE_L_COMP_FW : DRIVE_L_COMP_BK));  // compensate left
    digitalWrite(DRIVE_L_DIR, left_speed >= 0 ? LOW : HIGH);
}

/*
    FUNCTIONS: |timer_start|, |timer_expired|, |timer_clear|
        Start, test expiration on, and clear expiration any of the 16 independent timer
        channels available.

    PARAMETERS:
        |id| - identifier of timer in range 0-15
*/
void timer_start(unsigned char id, unsigned long num_ms)
{
    TMRArd_InitTimer(id, num_ms);
}
unsigned char timer_expired(unsigned char id)
{
    return (unsigned char)(TMRArd_IsTimerExpired(id));
}
void timer_clear(unsigned char id)
{
    TMRArd_ClearTimerExpired(id);
}
unsigned long timer_clock()
{
    return TMRArd_GetTime();
}

/*
    FUNCTION: |sonar_dist|
        Return the distance value (inches) read by ultrasonic sensor.
*/
unsigned int sonar_vals[SONAR_NUM_SMOOTH];
void sonar_reset()
{
    for (int i = 0; i < SONAR_NUM_SMOOTH; i++)
        sonar_vals[i] = SONAR_MAX_DISTANCE;
}
unsigned int sonar_inst()  // instantaneous
{
    unsigned int val = sonar.ping_cm();
    return (val == 0 ? SONAR_MAX_DISTANCE : val);  // in cm
}
unsigned int sonar_dist()  // smoothed
{
    // shift values
    unsigned int sum = 0;
    for (int i = 1; i < SONAR_NUM_SMOOTH; i++)
    {
        sonar_vals[i - 1] = sonar_vals[i];
        sum += sonar_vals[i - 1];
    }

    unsigned int val = sonar.ping_cm();
    sonar_vals[SONAR_NUM_SMOOTH - 1] = (val == 0 ? SONAR_MAX_DISTANCE : val); // in cm
    sum += sonar_vals[SONAR_NUM_SMOOTH - 1];

    Serial.println(sonar_vals[SONAR_NUM_SMOOTH - 1]);
    return sum / SONAR_NUM_SMOOTH;
}

/*  =================================================================================================================
    SECTION: Helper methods: lsensor
    ================================================================================================================= */

#define LINE_BLACK ((long[]){131, 102, 62, 139, 127})       // values on black; calibrate this (!!)
#define LINE_WHITE ((long[]){988, 989, 975, 993, 992})      // values on white; calibrate this (!!)

/*
    FUNCTION: |lsensor_capture|
        Read in line sentor values to |line_sensor_vals|, mapped and constrained to within [0, 1000].

    NOTES:
        line_sensor_vals[i] --> ideally 0 on white board, 1000 on black tape; mapped & constrained
*/
void lsensor_print_raw()
{
    #if VERBOSE_SENSORS || SERIAL_COMM
    Serial.print(F("lsensor_print_raw\tline_senor_vals={\t"));
    for(int i = 0; i < LINE_NUM_SENSORS; i++)
    {
        int raw = analogRead(LINE_PINS[i]);
        Serial.print(raw);
        Serial.print('\t');
    }
    Serial.println(F("}"));
    #endif
}
void lsensor_capture()
{
    #if VERBOSE_SENSORS
    Serial.print(F("lsensor_capture\tline_sensor_vals={\t"));
    #endif

    for(int i = 0; i < LINE_NUM_SENSORS; i++)
    {
        int raw = analogRead(LINE_PINS[i]);
        line_sensor_vals[i] = constrain(map(raw, LINE_WHITE[i], LINE_BLACK[i], 0, 1000), 0, 1000);

        #if VERBOSE_SENSORS
        Serial.print(line_sensor_vals[i]);
        Serial.print(F("\t"));
        #endif
    }

    #if VERBOSE_SENSORS
    Serial.println(F("}"));
    #endif
}


/*  =================================================================================================================
    SECTION: Helper methods: lfollow
    ================================================================================================================= */

#define LFOLLOW_KP                  12.0    // 10; proportional constant
#define LFOLLOW_KD                  150     // 130; derivative constant
#define LFOLLOW_KN                  0.0     // nonlinear constant
#define LFOLLOW_SETPOINT            2.0       // ideal calibrated position value
#define LFOLLOW_ALL_WHITE_TOL       100     // tolerance for combined all white readings (below is fine); calibrate this (!!)
#define LFOLLOW_ALL_BLACK_TOL       4500    // tolerance for combined all black readings (above is fine); calibrate this (!!)
#define LFOLLOW_BLACK_WHITE_DIFF    500     // min difference between black and white readings
double lfollow_last_error, lfollow_last_pos;


/*
    FUNCTION: |lfollow_pos|
        Return position of line based on sensor readings.

    RETURNS:
        |pos| - position of line based on sensor readings; pos = 2 --> in middle based on ids {0, 1, 2, 3, 4}
                      0*val[0] + 1*val[1] + 2*val[2] + ...
                pos = ------------------------------------
                       val[0]  +  val[1]  +  val[2]  + ...

*/
double lfollow_pos()
{
    lsensor_capture();  // read sensor data

    // calcalutions using values
    double num = 0.0;
    double denom = 0.0;
    double min_sensor_val = line_sensor_vals[0];
    for (int i = 0; i < LINE_NUM_SENSORS; i++)
    {
        num += i * line_sensor_vals[i];
        denom += line_sensor_vals[i];
        if(line_sensor_vals[i] < min_sensor_val)
            min_sensor_val = line_sensor_vals[i];
    }

    unsigned char is_uniform = true;
    for (int i = 0; i < LINE_NUM_SENSORS; i++)
    {
        if(line_sensor_vals[i] - min_sensor_val >= LFOLLOW_BLACK_WHITE_DIFF)
        {
            is_uniform = false;
            break;
        }
    }

    unsigned char is_off_line = denom <= LFOLLOW_ALL_WHITE_TOL;

    double pos = 0.0;
    if(is_off_line || is_uniform)  // off line completely, uniform distribution --> use last position
    {
        pos = (lfollow_last_pos > LFOLLOW_SETPOINT ? LINE_NUM_SENSORS-1 + LFOLLOW_KN : 0 - LFOLLOW_KN);
    }
    else  // line within sensors --> position is weighted average
    {
        pos = num / denom;
    }

    lfollow_last_pos = pos;

    #if VERBOSE_SENSORS
    Serial.print(F("lfollow_pos\tnum="));
    Serial.print(num);
    Serial.print(F("\tdenom="));
    Serial.print(denom);
    Serial.print(F("\tpos="));
    Serial.println(pos);
    #endif

    return pos;
}

/*
    FUNCTION: |lfollow_calc|
        Calculate PID control value |u(t)| for adjusting the motor speed/trajectory to follow a line.
        Calls callback function when detects a T-head/perpendicular.

        u(t) = <-- NEG ------ ZERO ------ POS -->
                 go left     perfect    go right

    RETURNS:
        |u| - control variable; adjust motor speed: (left, right) = (base, base) + (+PID, -PID)
*/
double lfollow_calc()
{
    double pos = lfollow_pos();
    double error = pos - LFOLLOW_SETPOINT;
    double u = LFOLLOW_KP * error + (lfollow_last_error != 0.0 ? LFOLLOW_KD * (error - lfollow_last_error) : 0.0);  // control variable

    lfollow_last_error = error;

    #if VERBOSE_SENSORS
    Serial.print(F("lfollow_calc\tu="));
    Serial.print(u);
    Serial.print(F("\terror="));
    Serial.println(error);
    #endif

    return u;
}
/*
    FUNCTION: |lfollow_run|
        Run line follower until robot crosses a perpendicular, then call callback function.
*/
void lfollow_run(void (*callback)(void), int dir)
{
    #if VERBOSE_SENSORS
    Serial.println(F("lfollow_run"));
    #endif

    double u = lfollow_calc();

    // test if crossing perpendicular; put here so have updated line_sensor_vals (!!)
    if (line_sensor_vals[0] + line_sensor_vals[4] >= 1800)
    {
        #if VERBOSE_SENSORS
        Serial.println(F("lfollow_run detected perp"));
        #endif

        motors_set(0, 0);
        callback();
        return;
    }

    int motor_speed_left = dir * (u <= 0 ? DRIVE_SPEED : DRIVE_SPEED + u);
    int motor_speed_right = dir * (u <= 0 ? DRIVE_SPEED - u : DRIVE_SPEED);

    #if VERBOSE_SENSORS
    Serial.println(F("lfollow_run motors set"));
    #endif

    motors_set(motor_speed_left, motor_speed_right);
}

void lfollow_reset()
{
    #if VERBOSE_SENSORS
    Serial.println(F("lfollow_reset"));
    #endif

    lfollow_last_error = 0.0;
    lfollow_last_pos = LFOLLOW_SETPOINT;
}


/*  =================================================================================================================
    SECTION: Helper methods: lalign
    ================================================================================================================= */
#define LALIGN_SETPOINT     500         // ideal edge sensor values; calibrate this (!!)
#define LALIGN_TOLERANCE    6           // tolerance value for motor deltas to stop alignment attempt
#define LALIGN_KP           0.035       // proportional constant
#define LALIGN_KI           0.00        // integral constant
#define LALIGN_KD           0.00        // derivative constant

#define LALIGN_SPACING_SPEED    20      // speed to move for spacing
#define LALIGN_SPACING_TIME     500     // time to move for spacing

/*
    FUNCTION: |lalign_run|
        Align line sensors exactly over an edge of the T-head/perpendicular tape.

        u(t) = <-- NEG ------ ZERO ------ POS -->
                 go left     perfect    go right

    PARAMETERS:
        |side| = 1 for forward side of tape, -1 for backward side of tape
*/
unsigned char lalign_has_spaced;
double lalign_sum_left_error, lalign_sum_right_error, lalign_last_left_error, lalign_last_right_error;
unsigned long lalign_last_clock;

/*
    FUNCTION: |lalign_run|
        Align line sensors exactly on a perpendicular, then call callback function.
*/
void lalign_run(void (*callback)(void), int side)
{
    if (!lalign_has_spaced)
    {
        motors_set(side * LALIGN_SPACING_SPEED, side * LALIGN_SPACING_SPEED);
        delay(LALIGN_SPACING_TIME);
        lalign_has_spaced = true;
        lalign_last_clock = timer_clock();
    }

    lsensor_capture();  // capture sensor values
    double left_error =  line_sensor_vals[0] - LALIGN_SETPOINT;
    double right_error = line_sensor_vals[LINE_NUM_SENSORS-1] - LALIGN_SETPOINT;

    double dt = timer_clock() - lalign_last_clock;
    int u_left =  LALIGN_KP * left_error  + LALIGN_KI * (lalign_sum_left_error  + left_error  * dt) + \
                  LALIGN_KD * (left_error  - lalign_last_left_error)  / dt;
    int u_right = LALIGN_KP * right_error + LALIGN_KI * (lalign_sum_right_error + right_error * dt) + \
                  LALIGN_KD * (right_error - lalign_last_right_error) / dt;
    lalign_last_left_error = left_error;
    lalign_last_right_error = right_error;
    lalign_last_clock = timer_clock();

    #if VERBOSE_SENSORS
    Serial.print(F("lalign_run\tu_left="));
    Serial.print(u_left);
    Serial.print(F("\tu_right="));
    Serial.println(u_right);
    #endif

    // aligned below tolerance --> stop
    if (abs(u_left) <= LALIGN_TOLERANCE && abs(u_right) <= LALIGN_TOLERANCE)
    {
        motors_set(0, 0);
        callback();
        return;
    }

    motors_set(side * u_left, side * u_right);
}
void lalign_reset()
{
    lalign_has_spaced = false;
    lalign_sum_left_error = lalign_sum_right_error = 0.0;
    lalign_last_left_error = lalign_last_right_error = 0.0;
						

1.4  Bill of Parts

For the entire bill of parts file, click here.

Note that some of the components broke, so were not used in the final robot.


Part 2: The Journey

2.1  Week 1

We met at the beginning of the week for several hours to discuss and start planning our robot. In this session we began by mapping all of the aspects of the problem we needed to address. We agreed that our primary goal was to reach minimum functionality, and only after achieving that would we look into scaling up our robot to be competitive.

Design goal aside, we began to discuss the functionality of our robot, dividing it up into categories of launching mechanisms, mobility, feeding mechanisms, sensors, and strategy.

We came up with three main ideas for a launcher, namely, a tennis ball launcher with either one or two flywheels, a catapult, and a tee/hammer concept, in which the ball would sit on a tee and be launched by a hammer swinging through. We discussed powering these mechanisms with motors, springs, and pneumatics.

Ultimately, we decided motors were the most realistic and settled on a two motor flywheel design.

For feeding mechanisms, we were very keen on designing a passive system, and came up with a few ideas for hoppers. Design concerns included the friction of the balls on one another, and the possibility for jamming. With these in mind, we developed two ideas, one for a vertical hopper that used slotted ramps to feed a chain of balls to our launcher, and other for what we called our “cake tier” model, in which a spiral ramp was implemented to create a relatively short, horizontal feeder. We chose to prototype the “cake tier” model.

With regards to mobility, we had several models, although the primary focus of our discussion was whether to use normal wheels, omniwheels, or mecanum wheels. Although initially we were leaning towards mecanum over omniwheels or regular, we found that both mecanum and omniwheels to be more expensive than we were comfortable with given the spending limit. We settled on two regular wheels spaced across from one another on the central axis of the robot, with two ball bearings axially 90º offset from wheels to provide stability.

Although IR beacons were provided for us to help navigate the playing field, we decided not to make use of them, choosing alternatively to rely on a line sensing phototransistor array, and an ultrasonic sensor situated at the rear of our robot to be used in escaping the safe space, and aligning to shoot.

Very little discussion was dedicated to our overall strategy at this point, as we were under the impression that we could work it out more once we had finalized and developed our robot further.

Over the course of the week, we drew up schematics of the drive train, feeder mechanism, and did some calculations to determine what sorts of motors and configuration we would require for our launching mechanism.

With these considerations in mind, we purchased the materials to assemble our drivetrain, sensors array, and launcher mechanism. We started construction on the drivetrain at the end of this week, and had it mostly finalized before the end of the week.

2.2  Week 2

This week was almost entirely dedicated to building the physical robot. The drivetrain was assembled, and after some further considerations regarding the launcher (and the arrival of the motors), we assembled the launcher. We assembled the launcher (what would be the first of three), from a straight, 2” diameter PVC pipe, mounted on a duron platform with metal brackets. The same duron platform was also used to attach the motors for the flywheels. Also at the same time, we laser cut and assembled our “cake tier” feeder mechanism, but were restricted from testing it, as we needed to use wood glue to set it in a deformed state to provide a constant gradient. We completed all of this before the end of Tuesday, and submitted photos of all of our systems to our coach to be checked off for the subsystems check off. At this time, our launcher fired relatively consistently, and with the requisite range to play the game. Likewise, our drivetrain also functioned well.

Once our feeder mechanism had set, we tested it, but found that the friction between each ball as they tried to roll resulted in jamming throughout the system, and so we were forced to scrap that design. Despite some attempts to make a new passive feeder system, we chose to copy a design we had seen in the presentations for a new motor-driven feeder system. In this system, we had a base plate with one hole near the outside rim, and another plate on top with holes near the edge to accommodate twelve balls. The base plate is fixed, and the top plate is driven by a motor such that as the plate would spin, one ball at a time would fall through the hole in the base plate into the launcher. We laser cut this system out of three plates of duron (two spinning plates to hold the balls better), and then attached them to a DC motor through the base plate.

Towards the end of the week, we assembled all of the parts using four roughly 10” threaded metal rods as structural support (secured with threadlocked nuts), and had mostly completed the mechanical build of the robot. The final touch we added was a rails system to guide the ball from the hopper mechanism into the launcher.

2.3  Week 3

At the beginning of week three, we had a fully completed mechanical robot, and added vertical plate to one side of the robot to attach the electronics to. By tuesday, all of the electronics were fully wired and the mechanical robot was fully complete ready to be coded and tested. Unfortunately, we made no significant progress on the robot until friday evening, apart from some testing on Wednesday night which revealed that the launcher was subject to significant vibrations, which we dampened in the PRL the following day.

Friday afternoon into the evening we began testing with code the various parts of the robot, and by the end of the day, it looked like things were going quite smoothly and that we’d be done with only a few more hours of work, tuning the PID developing the software, so we called it a night after a time and got some rest.

Saturday morning we arrived around 10am, ready to work, with some members showing up later or popping in and out throughout the day. One of our members took the lead in developing the code to run our robot, so the others took on supporting roles, helping to test various features and snippets of code as they came up. Notable was the testing of the drivetrain, which revealed that although equal motor output resulted in a straight forward drive, there was a slight disparity between the motors when put into reverse. This data lead to the development of a compensation factor in the code.

Things seemed to be progressing smoothly, although work continued into the night, longer than expected. Due to the late requirement for a new hopper design, we were unable to procure the correct sized shaft coupler for the DC motor we were using, which resulted in the hopper being delicate and unstable in certain regions of its cycle. Work had been done to stabilize this previously, further work was done at this time to reduce friction in the system and stabilize it more.

Ultimately, two members ended having to pull an all-nighter on saturday night, and all four members pulled an all-nighter on sunday night for reason to explained consequently. Work was undertaken to make the launcher more consistent, the feeder rails had been broken, remade, and needed to be recalibrated, and then one of the motors for the launcher’s gearbox broke. One of the members was able to fix it briefly, but was bumped into resulting in the loss of a tiny washer integral to the motor, and with it the motor became obsolete. Soon thereafter, the sensors array started feeding the arduino with only no-reflectance values. We built an entirely new launcher using the remaining motor and some curved PVC piping that had been (luckily for us) discarded in the lab, and recreated our sensors array pcb on breadboard with materials from lab.

The launcher turned out to be far more consistent and accurate than the previous launcher, but the sensors array, wired identically to the previous array, fed out similar values to its predecessor, leading a several hour long debugging process. In the end, we used different sensors, redesigned the array, and reinstalled the array in the robot. As we were gaining traction again, the second motor broke in the same failure mode as the first. Once more the member who had fixed the previous motor took apart and reassembled the gearbox for the motor, in the process identifying a solution to the issue with this particular motor. Under an axial compression loading, motor and gearbox would function as required, however, despite attempts to create the correct conditions in our launcher design we were unable to get it to work.

At this point we gave up on our motor, and replaced it with an ungeared DC motor from the ME210 store, and using glue and an old rollerblade wheel we found lying around we were able to construct a new launcher with the same curved PVC piping. This launcher was also very consistent, accurate, but also significantly more powerful than previous iterations. The one major downside to this design was that the flywheel speed slowed significantly following each shot, and took a while to get up to speed initially given its low torque.

We also chose around this time to replace the DC motor driving our hopper with a stepper motor, and as such switched out motor drivers to reflect this change. We discovered, though, that we were incapable of running our DC motor for the launcher and the stepper motor for the hopper at the same time off the same arduino, so we quickly grabbed another arduino and used communication between the two arduinos to power both the hopper and the launcher at the same time.

Throughout this time, the code was tuned further, and the PID likewise received significant tuning.

Monday morning, we had a fully functional robot, and spent the morning iterating through various coding choices, tuning the PID values, escape algorithm, fact checking algorithm, and motor control (specifically with regards to the hopper and the launcher).

When we found that we were able to get a roughly 70% check off rate for our robot, the two remaining members of the team at that point decided to attempt a mulligan check off. We failed the mulligan and invested the next few hours into tuning the code again.

At the end of our process around 1pm, we were able to check off 10 times consecutively, and decided that although there was a chance of failure, we were comfortable with the odds. We checked off, marking our 11th consecutive success, and a 100% success rate.

Part 3: The Reflection

3.1  Areas of Improvement

The ME210 final project was an intense period, and ultimately as a team we are proud of what we accomplished and built. However there were a few things that we could have done better. Our time distribution is by far the most glaring, given our final sprint double all-nighter to the finish.

If we were to do it again, it would have served us better to have done all of our construction in parallel. We started our mechanical construction as soon as we had parts, but didn’t make any significant progress on our electrical work or our coding until the third week. Certainly, the mechanical construction required significantly more time, but had we had our electrical elements and code ready to be tested right when the mechanical robot was completed, we wouldn’t have needed to sprint in quite the same manner at the end.

Likewise, we could have done a better job of testing things along the way. Our drivetrain was for the most part completed pretty early on, so at that time we had the ability to begin testing the sensors array and drivetrain in tandem to calibrate the PID. Likewise, although our launcher took some time finalize, we could have started testing it on the field once we had it completed.

3.2  Areas of Strength

One of our best moves was by far to work in the PRL room 36. It wasn’t ever too crowded, we had access to all of the tools we needed to make mechanical adjustments to the robot, and we also had access to a wealth of electronics materials. It also meant that our initial mechanical constructions were very clean and precise.

Likewise, we benefited significantly from our initial planning sessions. We spent a lot of time in the beginning just talking through things, drawing, making calculations, and planning. At times it was a little painful, we really just wanted to get on with the build and have something to show for our work, but it paid off to wait. Because of our initial design considerations, when things went wrong throughout the project, we were easily able to pivot and recover.

With regards to the specifics of our design that were so useful in that regard, using a chain-drive system for our drivetrain worked incredibly well, as it allowed us to offset our motors towards the back of the robot, freeing up space in the middle of the robot for the sensors array and launcher. When both the launcher and the sensors array broke (multiple times) we were grateful for the free space to maneuver. Also, we mounted a duron plate vertically to attach our electronics to, which meant we didn’t have to work around a platform in our design as many other teams’ robots did. We always had access to every part of the robot, without really having to disassemble anything.

Similarly, we were lucky to have such an incredible coder on our team, as our code was designed in a way that was very modular; it allowed for significant customization and reworking without breaking. This was integral in the later stages of the process, when we had to start changing parts of the code rapidly to accommodate changes in strategy and mechanical construction.