Robert Keen
LinkedIn GitHub robert@robertkeen.ca

Me Welcome to my website! On this site, I have a more in-depth and casual overview of my projects and work experience than what is provided by my resume.

Contents

About Me

Another Me

I am an undergraduate of Electrical Engineering who is completing my final semester at the University of Victoria and will be beginning work as an EIT in January 2023.

Beyond school and engineering, I enjoy hanging out with friends, lifting weights, cooking, and working on computer projects such as making this website or working on my media server. Other than that, people have joked by saying that my hobby is finding new hobbies and that is actually somewhat true. I have tried many different things with varying success as to what sticks. Some examples of hobbies that stuck are



Some examples of things I tried that didn't stick (but hope to try again one day) are

Overall, my philosophy is that whether or not things stick, it is important to try new things because no matter what, you will learn something new and sometimes little things like these can turn into a passion.

Autonomous Underwater Vehicles Interdisciplinary Club (AUVIC) Projects

Polaris, AUVIC's 2018-2019 AUV

AUVIC is a University of Victoria robotics team that builds Autonomous Underwater Vehicles (AUVs) to compete in the international RoboSub competition. I joined AUVIC in September 2017–the first semester of my first year of university. Since then, I have been the team President, Project Manager, and Electrical Lead for three, two, and two semesters respectively. Currently, I am serving as the Project Manager and Electrical team lead. On top of this, I am working on designing a new motor controller PCB, IMU breakout board, and motor controller firmware.

The Motor Controller Project (Soldering PCB)

In this project, I am designing a motor controller board that controls the speed of eight brushless DC (BLDC) motors. The end goal is a board that receives commands from a Nvidia Jetson (embedded Linux system that serves as the AUV's main computer) through CANbus and controls motors accordingly. Currently, schematics and routing are complete and the board is being fabricated.

Motor Controller Overview:

Motor Controller Overview

Motor Controller Microcontroller Schematic:

Motor Controller Micro

Motor Controller Power Schematic:

Motor Controller Power

Motor Controller CAN Schematic:

Motor Controller CAN

Motor Controller UART Schematic (for debugging):

Motor Controller UART

Motor Controller ESC Schematic (repeated 8 times):

Motor Controller ESC

Motor Controller Sensors Schematic (temperature and current):

Motor Controller Sensors

IMU Breakout Board

MTI-620 VRU

The IMU Breakout Board is a PCB I designed to communicate with the club's new Xsens MTi-620 VRU. The goal of this board was to breakout the MTi-620's phoenix connector to a more accessible 16*2 male header and AUVIC's standard power and CAN connectors. The MTi-620 will mount to the board using surface mount standoffs.

IMU Breakout Board Schematic:

IMU Breakout Board Schematic

IMU Breakout Board PCB:

IMU Breakout Board PCB

IMU Breakout Board Completed:

IMU Breakout Board Photo

Motor Controller Firmware

Writing C firmware for the motor controller was the first task I did when I joined AUVIC and it is likely how I will spend my last year with AUVIC after the motor controller is complete. All the code I wrote can be found on the AUVIC Github. However, this is a shared repository with multiple contributors so, in the following sections, I will display code that was written solely by myself.

Multiplexing Firmware

The multiplexing firmware was the first project I completed with AUVIC. Since the microcontroller had limited pins and we had to read data from 16 sensors, my task was to write a program to control a 16x1 multiplexer to read from all 16 sensors using only one analog input and four control outputs.


extern void set_motor_current_temp_MUX(ADC_sensors_t ADC_sensor_x) {
    switch (ADC_sensor_x) {
        case Curr_ADC1:
            GPIOC->ODR |= GPIO_Pin_9; //turn on PC9
            GPIOC->ODR &= ~(GPIO_Pin_7 | GPIO_Pin_8);
            break;
        case Curr_ADC2:
            GPIOC->ODR |= GPIO_Pin_9 | GPIO_Pin_8; //turn on PC9 and PC8
            GPIOC->ODR &= ~(GPIO_Pin_7);
            break;
        case Curr_ADC3:
            GPIOC->ODR |= GPIO_Pin_9 | GPIO_Pin_8 | GPIO_Pin_7; //turn on PC9, PC8, and PC7
            break;
        case Curr_ADC4:
            GPIOC->ODR |= GPIO_Pin_9 | GPIO_Pin_7; //turn on PC9 and PC7
            GPIOC->ODR &= ~(GPIO_Pin_8);
            break;
        case Curr_ADC5:
            GPIOD->ODR |= GPIO_Pin_9; //turn on PD9
            GPIOD->ODR &= ~(GPIO_Pin_8);
            GPIOB->ODR &= ~(GPIO_Pin_15);
            break;
        case Curr_ADC6:
            GPIOD->ODR |= GPIO_Pin_9 | GPIO_Pin_8; //turn on PD9 and PD8
            GPIOB->ODR &= ~(GPIO_Pin_15);
            break;
        case Curr_ADC7:
            GPIOD->ODR |= GPIO_Pin_9 | GPIO_Pin_8; //turn on PD9 and PD8
            GPIOB->ODR |= GPIO_Pin_15; //turn on PB15
            break;
        case Curr_ADC8:
            GPIOD->ODR |= GPIO_Pin_9; //turn on PD9
            GPIOB->ODR |= GPIO_Pin_15; //turn on PB15
            GPIOD->ODR &= ~(GPIO_Pin_8);
            break;
        case Temp_ADC1:
            GPIOC->ODR |= GPIO_Pin_8; //turn on PC8
            GPIOC->ODR &= ~(GPIO_Pin_9 | GPIO_Pin_7);
            break;
        case Temp_ADC2:
            GPIOC->ODR |= GPIO_Pin_7; //turn on PC7
            GPIOC->ODR &= ~(GPIO_Pin_8 | GPIO_Pin_9);
            break;
        case Temp_ADC3:
            GPIOC->ODR &= ~(GPIO_Pin_9 | GPIO_Pin_8 | GPIO_Pin_7); //turn off PC7-PC9
            break;
        case Temp_ADC4:
            GPIOC->ODR |= GPIO_Pin_8 | GPIO_Pin_7; //turn on PC7-PC8
            GPIOC->ODR &= ~(GPIO_Pin_9);
            break;
        case Temp_ADC5:
            GPIOD->ODR |= GPIO_Pin_8; //turn on PD8
            GPIOD->ODR &= ~(GPIO_Pin_9);
            GPIOB->ODR &= ~(GPIO_Pin_15);
            break;
        case Temp_ADC6:
            GPIOB->ODR |= GPIO_Pin_15; //turn on PB15
            GPIOD->ODR &= ~(GPIO_Pin_8 | GPIO_Pin_9);
            break;
        case Temp_ADC7:
            GPIOD->ODR &= ~(GPIO_Pin_8 | GPIO_Pin_9); //turn off PD8-PD9
            GPIOB->ODR &= ~(GPIO_Pin_15); //turn off PB15
            break;
        case Temp_ADC8:
            GPIOD->ODR |= GPIO_Pin_8; //turn on PD8
            GPIOB->ODR |= GPIO_Pin_15; //turn on PB15
            GPIOD->ODR &= ~(GPIO_Pin_9);
            break;
        case Water_ADC:
            break;
        default:
            break;
    }
}

Motor Speed Control Firmware

The motor speed control firmware controls motor speed by outputting a PWM signal to electronic speed controllers (ESC).


static void init_motor_pwm_out()
{
    //Enable clock
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);

    //init timers
    RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
    RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
    RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
    RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);

    //GPIOA Configuration for motors 1-4 and 7
    GPIO_InitTypeDef GPIOA_InitStruct;
    GPIOA_InitStruct.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_3 | GPIO_Pin_10 | GPIO_Pin_8 | GPIO_Pin_6;
    GPIOA_InitStruct.GPIO_Mode = GPIO_Mode_AF;
    GPIOA_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOA_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOA_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOA, &GPIOA_InitStruct);

    //GPIOD configuration for motors 5-6
    GPIO_InitTypeDef GPIOD_InitStruct;
    GPIOD_InitStruct.GPIO_Pin = GPIO_Pin_15 | GPIO_Pin_12;
    GPIOD_InitStruct.GPIO_Mode = GPIO_Mode_AF;
    GPIOD_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOD_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOD_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOD, &GPIOD_InitStruct);

    //GPIOB configuration for motor 8
    GPIO_InitTypeDef GPIOB_InitStruct;
    GPIOB_InitStruct.GPIO_Pin = GPIO_Pin_0;
    GPIOB_InitStruct.GPIO_Mode = GPIO_Mode_AF;
    GPIOB_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOB_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOB_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOB, &GPIOB_InitStruct);

    //pin alternate function timer configuration
    GPIO_PinAFConfig(GPIOA, GPIO_PinSource0, GPIO_AF_TIM2);
    GPIO_PinAFConfig(GPIOA, GPIO_PinSource3, GPIO_AF_TIM2);
    GPIO_PinAFConfig(GPIOA, GPIO_PinSource10, GPIO_AF_TIM1);
    GPIO_PinAFConfig(GPIOA, GPIO_PinSource8, GPIO_AF_TIM1);
    GPIO_PinAFConfig(GPIOD, GPIO_PinSource15, GPIO_AF_TIM4);
    GPIO_PinAFConfig(GPIOD, GPIO_PinSource12, GPIO_AF_TIM4);
    GPIO_PinAFConfig(GPIOA, GPIO_PinSource6, GPIO_AF_TIM3);
    GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_TIM3);

    //timer set up
    TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
    TIM_TimeBaseStructure.TIM_Period = PWM_OUT_PERIOD;
    TIM_TimeBaseStructure.TIM_Prescaler = PWM_OUT_PRESCALER;
    TIM_TimeBaseStructure.TIM_ClockDivision = 0;
    TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
    TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
    TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
    TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
    TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
    TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);

    //pwm init
    TIM_OCInitTypeDef TIM_OCInitStructure;
    TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
    TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
    TIM_OCInitStructure.TIM_Pulse = 0;
    TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
    //pwm config for channel 1 PA0 motor 1
    TIM_OC1Init(TIM2, &TIM_OCInitStructure);
    TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Enable);
    //pwm config for channel 4 PA3 motor 2
    TIM_OC4Init(TIM2, &TIM_OCInitStructure);
    TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Enable);

    //pwm config for channel 4 PD15 motor 5
    TIM_OC4Init(TIM4, &TIM_OCInitStructure);
    TIM_OC4PreloadConfig(TIM4, TIM_OCPreload_Enable);
    //pwm config for channel 1 PD12 motor 6
    TIM_OC1Init(TIM4, &TIM_OCInitStructure);
    TIM_OC1PreloadConfig(TIM4, TIM_OCPreload_Enable);
    //pwm config for channel 1 PA6 motor 7
    TIM_OC1Init(TIM3, &TIM_OCInitStructure);
    TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
    //pwm config for channel 3 PB0 motor 8
    TIM_OC3Init(TIM3, &TIM_OCInitStructure);
    TIM_OC3PreloadConfig(TIM3, TIM_OCPreload_Enable);

    TIM_CtrlPWMOutputs(TIM1, ENABLE);

    TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
    TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
    TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
    TIM_OCInitStructure.TIM_Pulse = NEUTRAL;
    TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
    TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCPolarity_High;
    TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
    TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;

    //pwm config for channel 3 PA10 motor 3
    TIM_OC3Init(TIM1, &TIM_OCInitStructure);
    TIM_OC3PreloadConfig(TIM1, TIM_OCPreload_Enable);
    //pwm config for channel 1 PA8 motor 4
    TIM_OC1Init(TIM1, &TIM_OCInitStructure);
    TIM_OC1PreloadConfig(TIM1, TIM_OCPreload_Enable);


    TIM_Cmd(TIM2, ENABLE);
    TIM_Cmd(TIM1, ENABLE);
    TIM_Cmd(TIM4, ENABLE);
    TIM_Cmd(TIM3, ENABLE);
}

Motor Speed Control Function:

Input: Motor to control (motor 1-8), speed (0-100%), direction (forwards/backwards)


extern void motor_set_speed_percent(motors_t motor_x, uint16_t speed, direction_t dir)
{
    uint16_t cc_value = (speed * 12)/10;
    if(dir == Forward){
        cc_value = NEUTRAL + cc_value;
    }else{
        cc_value = NEUTRAL - cc_value;
    }

    switch(motor_x){
        case Motor1:
            TIM_SetCompare1(TIM2, cc_value);
            break;
        case Motor2:
            TIM_SetCompare4(TIM2, cc_value);
            break;
        case Motor3:
            TIM_SetCompare3(TIM1, cc_value);
            break;
        case Motor4:
            TIM_SetCompare1(TIM1, cc_value);
            break;
        case Motor5:
            TIM_SetCompare4(TIM4, cc_value);
            break;
        case Motor6:
            TIM_SetCompare1(TIM4, cc_value);
            break;
        case Motor7:
            TIM_SetCompare1(TIM3, cc_value);
            break;
        case Motor8:
            TIM_SetCompare3(TIM3, cc_value);
            break;
    }

}

ADC Firmware

The ADC firmware was the first code I wrote during my co-op with AUVIC in summer 2018. Its purpose was to read analog data from a power sensor.


#include "stm32f4xx.h"
#include "FreeRTOSConfig.h"
#include "FreeRTOS.h"
#include "task.h"
#include "ADC.h"
#include "stdlib.h"

uint16_t ADC_Values[SENSOR_QUANTITY][AMMOUNT_OF_RECORDED_VALUES];
uint8_t Read_Position;
uint8_t ADC_count;
ADC_sensors_t ADC_sensor = Curr_ADC1;

static void init_motor_current_temp_MUX() {
    //Enable clock
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);

    //GPIOC Configuration
    GPIO_InitTypeDef GPIOC_InitStruct;
    GPIOC_InitStruct.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
    GPIOC_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
    GPIOC_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOC_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOC_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOC, &GPIOC_InitStruct);

    //GPIOD Configuration
    GPIO_InitTypeDef GPIOD_InitStruct;
    GPIOD_InitStruct.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9;
    GPIOD_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
    GPIOD_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOD_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOD_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOD, &GPIOD_InitStruct);

    //GPIOB Configuration
    GPIO_InitTypeDef GPIOB_InitStruct;
    GPIOB_InitStruct.GPIO_Pin = GPIO_Pin_15;
    GPIOB_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
    GPIOB_InitStruct.GPIO_Speed = GPIO_Speed_100MHz;
    GPIOB_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOB_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOB, &GPIOB_InitStruct);
}

static void init_ADC_read(){
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
    RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);

    //GPIOC Setup
    GPIO_InitTypeDef GPIOC_InitStruct;
    GPIOC_InitStruct.GPIO_Mode = GPIO_Mode_AN;
    GPIOC_InitStruct.GPIO_OType = GPIO_OType_PP;
    GPIOC_InitStruct.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3;
    GPIOC_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIO_Init(GPIOC, &GPIOC_InitStruct);

    //ADC1 Setup
    ADC_InitTypeDef ADC_InitStruct;
    ADC_InitStruct.ADC_ContinuousConvMode = DISABLE;
    ADC_InitStruct.ADC_DataAlign = ADC_DataAlign_Right;
    ADC_InitStruct.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
    ADC_InitStruct.ADC_NbrOfConversion = 2;
    ADC_InitStruct.ADC_Resolution = ADC_Resolution_12b;
    ADC_InitStruct.ADC_ScanConvMode = DISABLE;
    ADC_Init(ADC1, &ADC_InitStruct);

    //NVIC Setup
    NVIC_InitTypeDef NVIC_InitStruct;
    NVIC_InitStruct.NVIC_IRQChannel = ADC_IRQn;
    NVIC_InitStruct.NVIC_IRQChannelCmd = ENABLE;
    NVIC_InitStruct.NVIC_IRQChannelPreemptionPriority = 0x0F;
    NVIC_InitStruct.NVIC_IRQChannelSubPriority = 0x0F;
    NVIC_Init(&NVIC_InitStruct);

    //Enable ADC end of conversion flag at the end of each channel conversion
    ADC_EOCOnEachRegularChannelCmd(ADC1, ENABLE);

    //Triggers an interrupt at each EOC flag
    ADC_ITConfig(ADC1, ADC_IT_EOC, ENABLE);
}


extern void set_ADC_channel(ADC_sensors_t ADC_sensor_x){
    //Select ADC channels
    if(((ADC_sensor_x <= Curr_ADC4) && (ADC_sensor_x >= Curr_ADC1)) || ((ADC_sensor_x <= Temp_ADC4) && (ADC_sensor_x >= Temp_ADC1))){
        ADC_RegularChannelConfig(ADC1, ADC_Channel_13, 1, ADC_SampleTime_56Cycles); //PC3
    }
    else if(((ADC_sensor_x <= Curr_ADC8) && (ADC_sensor_x >= Curr_ADC5)) || ((ADC_sensor_x <= Temp_ADC8) && (ADC_sensor_x >= Temp_ADC5))){
        ADC_RegularChannelConfig(ADC1, ADC_Channel_12, 1, ADC_SampleTime_56Cycles); //PC2
    }
    else if(ADC_sensor_x == Water_ADC){
        ADC_RegularChannelConfig(ADC1, ADC_Channel_11, 1, ADC_SampleTime_56Cycles); //PC1
    }
    //Enable ADC
    ADC1->CR2 |= ADC_CR2_ADON;
}

static uint16_t double_to_int(double double_x){
    uint16_t double_int = (uint16_t)double_x;
    if((double_x - (double)double_int) >= 0.5) double_int++;
    return double_int;
}

static double calculate_average(uint8_t Read_Position_x){
    average = 0;
    for(ADC_count = 0; ADC_count < AMMOUNT_OF_RECORDED_VALUES; ADC_count++){
        average += (double)ADC_Values[Read_Position_x][ADC_count];
     }
    average /= AMMOUNT_OF_RECORDED_VALUES;
    return average;
}


static void ADCTask(void *dummy){
    while(1){
        set_motor_current_temp_MUX(ADC_sensor);
        set_ADC_channel(ADC_sensor);
        vTaskDelay(1);
        read_ADC(ADC_sensor);
        ADC_sensor++;
        if(ADC_sensor > Water_ADC) ADC_sensor = Curr_ADC1;
        vTaskDelay(100);
    }
}

I2C Firmware

The I2C code was written while completing a co-op with AUVIC in 2018. This code read data from I2C temperature sensors.


#include "stm32f4xx.h"
#include "I2C.h"
#include "string.h"
#include "I2C_Sensors.h"
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"
#include "simple_UART.h"
#include "stdlib.h"
#include "string.h"
#include "debug.h"

#define I2C_SADD_BIT	1

#define I2C_READ_BIT 0x01

//I2C Output buffer
#define I2C_OUTPUT_BUFFER_SIZE	8
uint8_t I2C_OutputBuffer[I2C_OUTPUT_BUFFER_SIZE];

typedef enum{
    read,
    write
} I2C_state_t;

//I2C Input Buffer
uint8_t *I2C_inputBuffer;

//bytes count
volatile uint8_t bytes_count = 0;

//bytes total
volatile uint8_t bytes_total;

//slave address
uint8_t slave_address;

//I2C state
I2C_state_t I2C_state;

//FreeRTOS current task handle
TaskHandle_t TaskToNotify = NULL;



extern uint16_t switch_endiness_uint16(uint16_t input) {
    uint8_t temp = (input & 0xFF00) >> 8;
    input = (input & 0x00FF) << 8;
    input |= temp;
    return input;
}

extern uint32_t switch_endiness_uint32(uint32_t input, uint8_t numBytes) {

    uint32_t output = 0;

    for(uint8_t i = 0; i < numBytes; i++) {
        output = output << 8;
        output |= (input & 0xFF);
        input = input >> 8;
    }

    return output;
}

extern void I2C_setup(){

    //Enable clock for GPIOB
    RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);

    //GPIOB setup for SCL and SDA
    GPIO_InitTypeDef GPIOB_Init;
    GPIOB_Init.GPIO_Mode = GPIO_Mode_AF;
    GPIOB_Init.GPIO_OType = GPIO_OType_OD;
    GPIOB_Init.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9;
    GPIOB_Init.GPIO_PuPd = GPIO_PuPd_NOPULL;
    GPIOB_Init.GPIO_Speed = GPIO_Speed_100MHz;
    GPIO_Init(GPIOB, &GPIOB_Init);

    //sets alternate function register to AF4 for PB7 and PB6
    GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_I2C1);
    GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_I2C1);

    //NVIC Setup
    NVIC_InitTypeDef NVIC_InitStruct;
    NVIC_InitStruct.NVIC_IRQChannel = I2C1_EV_IRQn;
    NVIC_InitStruct.NVIC_IRQChannelCmd = ENABLE;
    NVIC_InitStruct.NVIC_IRQChannelPreemptionPriority = 7;
    NVIC_InitStruct.NVIC_IRQChannelSubPriority = 0;
    NVIC_Init(&NVIC_InitStruct);

    /* Configure IT */
    /* (3) Set priority for USART1_IRQn */
    /* (4) Enable USART1_IRQn */
    NVIC_SetPriority(I2C1_EV_IRQn, 7); /* (3) */
    NVIC_EnableIRQ(I2C1_EV_IRQn); /* (4) */

}

static void I2C_init(){
    //Enable clock for I2C1
    RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);

    //I2C setup
    I2C_InitTypeDef I2C_Init_Struct;
    I2C_Init_Struct.I2C_Ack = I2C_Ack_Enable;
    I2C_Init_Struct.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
    I2C_Init_Struct.I2C_Mode = I2C_Mode_I2C;
    I2C_Init_Struct.I2C_OwnAddress1 = 0x0;
    I2C_Init_Struct.I2C_ClockSpeed = 50000;
    I2C_Init_Struct.I2C_DutyCycle = I2C_DutyCycle_2;
    I2C_Init(I2C1, &I2C_Init_Struct);

    //Enable I2C
    I2C1->CR1 |= I2C_CR1_PE;

    //Enable interrupts
    I2C1->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN;
}

extern void I2C_read(uint8_t address, uint8_t numBytes, uint8_t *message){
    TaskToNotify = xTaskGetCurrentTaskHandle();
    I2C_init();
    slave_address = address;
    I2C_state = read;
    bytes_total = numBytes;
    I2C_inputBuffer = message;
    I2C1->CR1 |= I2C_CR1_START;
}

extern void I2C_write(uint8_t address, uint8_t numBytes, uint8_t message[]){
    TaskToNotify = xTaskGetCurrentTaskHandle();
    I2C_init();
    I2C_state = write;
    slave_address = address;
    bytes_total = numBytes;
    memcpy(I2C_OutputBuffer, message, numBytes);
    I2C1->CR1 |= I2C_CR1_START;
}

void I2C1_EV_IRQHandler(void) {
    //Waits for start bit
    if((I2C1->SR1 & I2C_SR1_SB) == I2C_SR1_SB){

        I2C1->SR2; //Clear interrupt

        if(I2C_state == write){
            uint8_t output = (slave_address << I2C_SADD_BIT);
            output &= ~(I2C_READ_BIT);
            I2C1->DR = output;
        } else if(I2C_state == read){
            I2C1->DR = (slave_address << I2C_SADD_BIT) | I2C_READ_BIT;

            if( bytes_total == 1 ){
                I2C1->CR1 &= ~(I2C_CR1_ACK);
            }

        }
    //Waits for address sent bit
    }else if((I2C1->SR1 & I2C_SR1_ADDR) == I2C_SR1_ADDR){

        I2C1->SR2;//needs to read SR2 to clear ADDR bit and continue

        if(I2C_state == write){

            I2C1->DR = I2C_OutputBuffer[bytes_count];

            bytes_count++;
            bytes_total--;
        } else if(I2C_state == read){
            //the following is the read process specified by the F4 reference
            //manual page 482-483
            if( bytes_total == 1 ){
                I2C1->CR1 |= I2C_CR1_STOP;
            }
        }

    //Writes data to I2C
    }else if((I2C1->SR1 & I2C_SR1_TXE) == I2C_SR1_TXE){
        if(bytes_total >= 1){
            I2C1->DR = I2C_OutputBuffer[bytes_count];
            bytes_total--;
            bytes_count++;
        }else if(bytes_total == 0){
            bytes_count = 0;
            I2C1->CR1 |= I2C_CR1_STOP;
            I2C1->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN);
            vTaskNotifyGiveFromISR(TaskToNotify, pdFALSE);
        }
    //Reads I2C data
    }else if((I2C1->SR1 & I2C_SR1_RXNE) == I2C_SR1_RXNE){

        *I2C_inputBuffer = I2C1->DR;
        I2C_inputBuffer++;
        bytes_total--;

        if(bytes_total == 1){
            I2C1->CR1 &= ~(I2C_CR1_ACK);
            I2C1->CR1 |= I2C_CR1_STOP;
        }

        if(bytes_total == 0){
            I2C1->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN);
            vTaskNotifyGiveFromISR(TaskToNotify, pdFALSE);
        }
    //Runs in the case of failure
    } else if((I2C1->SR1 & I2C_SR1_AF) == I2C_SR1_AF){
        bytes_count = 0;
        I2C1->CR1 |= I2C_CR1_STOP;
        I2C1->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN);
        I2C_Cmd(I2C1, DISABLE);
        I2C_DeInit(I2C1);
        vTaskNotifyGiveFromISR(TaskToNotify, pdFALSE);
    }
    uint32_t temp = I2C1->SR1;
    temp = I2C1->SR2;

}

My 12 Month Co-op at AXYS Technologies

AXYS Wind Sentinel Autonomous Mooring

I completed my first four-month co-op with AXYS Technologies in January 2019 and got rehired for an eight-month co-op in September 2020. AXYS Technologies is a marine engineering company headquartered in Sidney, BC, and builds autonomous moorings such as the one shown on the right. These moorings collect data for environmental research or renewable energy applications. I was a member of the product development team during these 12 months.

First Co-op at AXYS (January-May 2019)

My first co-op with AXYS was a large collection of small tasks with two medium-sized projects thrown in. Some highlight small tasks would be:

The first of the two medium-sized projects was to create a dashboard for the AXYS test system using Python. The test system is a collection of equipment that aims to simulate a mooring in the field. This dashboard was a web GUI that displayed mooring data in the form of interactive plots and tables. I found this challenging at the time because I had minimal experience with Python programming. However, as a result of this project, I became confident with using Python along with the pandas, matplotlib, and plotly libraries.

The second medium-sized project was to automate the system setup for the industrial PCs (IPCs) onboard AXYS Technologies' flagship floating LiDAR (FLiDAR) buoys. The IPCs were Linux systems that served as the central point of data collection and communication. Before automation, the setup of these systems would take a technician several hours. Through this process, I got proficient in shell scripting and learned a great amount about Linux systems. This project sparked an interest in Linux that I still have to this day.

Second Co-op at AXYS (September-December 2020)

My second co-op with AXYS started with me teaming up with another AXYS Engineer to troubleshoot a thermal bird tracker for one of AXYS's clients. The images taken by the thermal camera were heavily corrupted and our job was to figure out why. We eventually figured out that the corruption was caused by noise in the pulses that were sent to the camera to initiate image capture. This was a fun project where I got to debug a real-world system using an oscilloscope, function generator, and logic analyzer while also regularly reporting progress to the clients.

After the bird tracker project, my tasks were mostly C firmware programming. The remainder of my second co-op with AXYS was spent doing many small bug fixes while I got familiar with the AXYS firmware code. The AXYS firmware is a huge codebase and learning my way around it was easily the greatest challenge I faced in my 12 months as AXYS.

Third Co-op at AXYS: the Buoy-Buoy Link Project (January-April 2021)

During my third Co-op with AXYS, I was assigned my first large project: the Buoy-Buoy Link. The goal of this project was to make several buoys/moorings in a system act as one using master-slave based radio communication network. The overall function of this system is shown in the flow chart below:

Buoy-Buoy Link Flow Chart

This was a project I did for AXYS on my own from spec sheet to testing. Although this was a challenging project with many parts where I felt completely lost, it was also a rewarding endeavour, and am happy about the knowledge and experience I gained from its completion.

Key Takeaways from Working at AXYS

Through the 12 months I spent at AXYS, my most valuable takeaway was that I lost my fear of asking for help. There were many times where I was completely lost while working on an assignment that was out of my comfort zone and in those situations, I have never regretted asking for help. At AXYS, I learned the limits of personal perseverance and that the most valuable resource in an engineering team is the knowledge of those around you.

My Co-op With Cellula Robotics

AXYS Wind Sentinel Autonomous Mooring My four month work term with Cellula Robotics was my fifth and final co-op. I feel this co-op is where all the skills I've developed through school, work with AXYS, and work with AUVIC come together. This was a fast paced co-op with the major focus being preparing Solus-LR for the July 2022 AUV Demo. This involved the testing and troubleshooting of subsystems within the Solus-LR AUV to ensure system and crew readiness in addition to updating cabling and wiring diagrams to keep documentation up to date as changes are made. Another task of mine was to manage the microsub launch. This involved performing writing missions for the microsubs, working with the software team to integrate the launch mechanism, and performing the daily microsub predive prior to AUV launch.

Other Projects

In this section, I have projects that I worked on that weren't with a particular organization. These would be things such as school or personal projects.

ECE 299 Design Project: Alarm Clock Design With Arduino, KiCAD, and TinkerCAD

The ECE 299 alarm clock design project was a fun school project and the first time I've done a PCB design. In this project, I designed a functional alarm clock Arduino shield that could display time, set time, set alarms, and snooze. In the end, this alarm clock design got 100%.

Alarm Clock PCB:

Alarm Clock PCB 3D Alarm Clock PCB 2D

Alarm Clock PCB Enclosure (designed to look like a cartoon bomb):

Alarm Clock Enclosure

Alarm Clock Arduino Code:


int displays[] = {3, 5, 6, 9, NULL};  //contains all pins connected to the MOSFET
int segments[] = {1, 4, 7, 8, NULL}; //
// segments to be set to display a number
int numbers[][4] = {{NULL}, // 0
                  {segments[0], NULL}, // 1
                  {segments[1], NULL}, // 2
                  {segments[0], segments[1], NULL}, // 3
                  {segments[2], NULL}, // 4
                  {segments[2], segments[0], NULL}, // 5
                  {segments[2], segments[1], NULL}, // 6
                  {segments[2], segments[1], segments[0], NULL}, // 7
                  {segments[3], NULL}, // 8
                  {segments[3], segments[0], NULL}, // 9
                  NULL};
// segments which must not be set to display a number
int not_numbers[][5] ={{segments[0], segments[1], segments[2], segments[3], NULL}, // 0
                  {segments[1], segments[2], segments[3], NULL}, // 1
                  {segments[0], segments[2], segments[3], NULL}, // 2
                  {segments[2], segments[3], NULL}, // 3
                  {segments[0], segments[1], segments[3], NULL}, // 4
                  {segments[1], segments[3], NULL}, // 5
                  {segments[0], segments[3], NULL}, // 6
                  {segments[3], NULL}, // 7
                  {segments[0], segments[1], segments[2], NULL}, // 8
                  {segments[1], segments[2], NULL}, // 9
                  NULL};


int time[4] = {2, 3, 5, 9}; //array used for displaying the actual time
int alarmTime[4] = {0, 0, 0, 0};
int brightness = 255; //default brightness
int leds = 10; //the pin the LEDS in between the 7-segment display for signifing a colon are connected to.
int buzzer = 11; //pin the buzzer is connected to
int photo = A0; //pin the phototransistor is connected to.
int currentDisplay = 0;
int stopAlarmButton = 0;
int increaseButton = 0;
int decreaseButton = 0;
int snoozeButton = 2;
int setAlarmButton = 3;
int buttonDelay = 50;
int snoozeInterval = 1;
  
bool alarmState = false; // boolean for dertermining whether the alarm is active or not.

//id

void setup()
{
  pinMode(photo, INPUT); //for the  button
  pinMode(buzzer, OUTPUT); //output for buzzer activation
  int count;
  for(count = 0; count < 4; count++){ //statement for declaring the pins the segment array is connected to as outputs
    pinMode(segments[count], OUTPUT);
  }
  for(count = 0; displays[count] != NULL; count++) pinMode(displays[count], OUTPUT);
  pinMode(leds, OUTPUT);
  
  // timer based interrupt setup for the display
  cli();//stop interrupts
  TCCR1A = 0;// set entire TCCR1A register to 0
  TCCR1B = 0;// set entire TCCR1B register to 0
  TCNT1  = 0;//initialize counter value to 0
  // sets display switching to 100Hz
  // lower = faster display switching
  // prescalar value
  // timer runs at 16MHz
  // OCR1A = 3910; // 3910 ~= (16*10^6)/(1023*4Hz)
  OCR1A = 16; // 16 ~= (16*10^6)/(1023*1000Hz)
  // turn on CTC mode (capture compare mode)
  TCCR1B |= (1 << WGM12);
  TCCR1B |= (1 << CS12) | (1 << CS10);  
  // enable timer compare interrupt
  TIMSK1 |= (1 << OCIE1A);
  sei();//allow interrupts
}

// interrupt runs at ~100Hz 
ISR(TIMER1_COMPA_vect){ 
  digitalWrite(displays[currentDisplay], LOW);
  currentDisplay = (currentDisplay+1)%5;
  displayNumber(time[currentDisplay]);
  analogWrite(displays[currentDisplay], brightness);
}

void displayNumber(int num)
{
  int count;
  // iteratively turns off all segments not involded in displaying num
  for(count = 0; not_numbers[num][count] !=NULL; count++){
    digitalWrite(not_numbers[num][count], LOW);
  }
  // iteratively turns on all segments that coresponds to num being displayed
  for(count = 0; numbers[num][count] != NULL; count++){
    digitalWrite(numbers[num][count], HIGH);
  }
}

int button(){ //this function determines which button has been pressed and returns a value related the the button
 if(digitalRead(A1) && !digitalRead(A2) && !digitalRead(A3) && !digitalRead(A4)&& !digitalRead(A5)) return 1;  //if button 1 (set alarm) is pressed
  else if(!digitalRead(A1) && digitalRead(A2) && !digitalRead(A3) && !digitalRead(A4)&& !digitalRead(A5)) return 2;  //if button 2 (set time) is pressed
  else if(!digitalRead(A1) && !digitalRead(A2) && digitalRead(A3) && !digitalRead(A4)&& !digitalRead(A5)) return 3;  //if button 3 (snooze) is pressed
  else if(!digitalRead(A1) && !digitalRead(A2) && !digitalRead(A3) && digitalRead(A4)&& !digitalRead(A5)) return 4;  //if button 4 (increase) is pressed
  else if(!digitalRead(A1) && !digitalRead(A2) && !digitalRead(A3) && !digitalRead(A4)&& digitalRead(A5)) return 5;  //if button 5 (decrease) is pressed.
  else return 0;
}

void setTime(){
  bool set_hours = true;
  int display = 1;
  int hour = 10*time[0] + time[1];
  int minute = 10*time[2] +time[3]; 
  cli(); // stop interrupts
  for(int i = 0; displays[i] != NULL; i++) digitalWrite(displays[i], LOW);
  while(1){
    digitalWrite(displays[display-1], LOW);
    if(set_hours){
        display = (display%2) + 1; // alternates between 1 and 2
    } else{
        if(display == 3) display = 4; //alternates between 3 and 4
        else display = 3;
    }
    displayNumber(time[display-1]);
    analogWrite(displays[display-1], brightness);
    delay(1);
    
    if(button() == 5){
      if(set_hours){
        hour++;
        if(hour >23) hour = 0;
        time[0] = hour/10;
        time[1] = hour%10;
      } else {
            minute++;
            if(minute >59) minute = 0;
            time[2] = minute/10;
            time[3] = minute%10;
      }
     
      delay(buttonDelay);
    } else if(button() == 4){
      if(set_hours){
          hour--;
          if(hour < 0) hour = 23;
          time[0] = hour/10;
          time[1] = hour%10;
      } else{
            minute--;
            if(minute < 0) minute = 59;
            time[2] = minute/10;
            time[3] = minute%10;
      }
        delay(buttonDelay);
    } else if (button() == 2) {
        for(int i = 0; displays[i] != NULL; i++) digitalWrite(displays[i], LOW);	
        while(button() == 2);	
        if(set_hours) set_hours = false;	
        else break;
        delay(buttonDelay);
    }
     time[0] = hour/10;
     time[1] = hour%10;
  }
    
  sei(); // start interrupts
}

void setAlarm(){  //function for setting the alarm
  bool set_hours = true;
  int display = 1;
  int hour = 10*alarmTime[0] + alarmTime[1];
  int minute = 10*alarmTime[2] +alarmTime[3]; 
  alarmState = true;
  cli(); // stop interrupts
  for(int i = 0; displays[i] != NULL; i++) digitalWrite(displays[i], LOW);
  while(1){
    digitalWrite(displays[display-1], LOW);
    if(set_hours){
        display = (display%2) + 1; // alternates between 1 and 2
    } else{
        if(display == 3) display = 4; //alternates between 3 and 4
        else display = 3;
    }
    displayNumber(alarmTime[display-1]);
    analogWrite(displays[display-1], brightness);
    delay(1);
    
    if(button() == 5){ //if button for increasing the digit on the LED is pressed
      if(set_hours){
        hour++;
        if(hour >23) hour = 0;
        alarmTime[0] = hour/10;
        alarmTime[1] = hour%10;
      } else {
            minute++;
            if(minute >59) minute = 0;
            alarmTime[2] = minute/10;
            alarmTime[3] = minute%10;
      }
     
      delay(buttonDelay);
    } else if(button() == 4){ //if button for decreasing digit on LED is pressed.
      if(set_hours){
          hour--;
          if(hour < 0) hour = 23;
          alarmTime[0] = hour/10;
          alarmTime[1] = hour%10;
      } else{
            minute--;
            if(minute < 0) minute = 59;
            alarmTime[2] = minute/10;
            alarmTime[3] = minute%10;
      }
        delay(buttonDelay);
    } else if (button() == 1) {
        for(int i = 0; displays[i] != NULL; i++) digitalWrite(displays[i], LOW);	
        while(button() == 1);	
        if(set_hours) set_hours = false;	
        else break;
        delay(buttonDelay);
    }
     alarmTime[0] = hour/10;
     alarmTime[1] = hour%10;
  }
    
  sei(); // start interrupts
}
  unsigned long previousMillis = 0;
void timeFunction() //this function controls the time 
{ 
  unsigned long currentMillis = millis(); //these three lines constantly check whether a second has gone by.
  
  
  if(currentMillis - previousMillis >= 1000)
     {
        previousMillis = currentMillis; //restart the minute counter
        time[3]++; //increase LED 1 by 1 minute
    
        if(time[3] > 9)
        {
          time[3] = 0; //set LED 1 back to zero
          time[2]++; //increase LED 2 by one.
          
          if( time[2] > 5) //if LED 2 is greater than 59 minutes.
          {
            time[2] = 0;  //reset LED 2 back to 0.
            time[1]++; //increase LED 3 by 1.
            
            if (time[1] > 9)  //if LED 3 is greater than 9
            {
              time[1] = 0; //set LED 3 back to 0
              time[0]++;  //increase LED 4 to 1.
            }
          }
          
        }
     }

  if(time[0] == 2 && time[1] == 4) //if the clock goes over 23:59, reset all LED's to 0
  {
    time[3] = 0;
    time[2]= 0;
    time[1] = 0;
    time[0] = 0;
  }
   
}


void buttonCheck(){
  switch(button()){
    case 1:  //case if the set alarm button was pressed.
      while(button() == 1); 
      setAlarm();  //go to set alarm function
      delay(buttonDelay);
      break;
    case 2: //case if the set time button was pressed.
      while(button() == 2);
      setTime(); //go to set time function
      delay(buttonDelay);
      break;
    case 3: //case if the snooze button was pressed while the alarm is not sounding.
    // toggles the alarm
      while(button() == 3);
      alarmState = !alarmState;
      if(alarmState == true){
        unsigned long prev = millis();
        // plays a tone to indicate the alarm is active
        while(millis()-prev < 5)
          tone(buzzer, 1000);
        noTone(buzzer);
      }
      break;
    case 4:
        break;
    case 5:
        break;
    default:
        break;
  }
}

void alarm(){  //function for activating the alarm
  if(time[0] == alarmTime[0] &&  //if the time array is equal to the set alarmTime array, activate the buzzer
     time[1] == alarmTime[1] &&
     time[2] == alarmTime[2] &&
     time[3]== alarmTime[3] && alarmState) {
      while(button() == 0){
          tone(buzzer, 300);

      }
      noTone(buzzer);
      if(button() == 3){ // if snooze is pressed
        int minutes = 10*alarmTime[2] + alarmTime[3];
        int hours = 10*alarmTime[0] + alarmTime[1];
        minutes += snoozeInterval;
        if(minutes > 59){
          minutes = minutes -59;
          hours++;
          if(hours > 23) hours = 0;
        } 
        alarmTime[0] = hours/10;
        alarmTime[1] = hours%10;
        alarmTime[2] = minutes/10;
        alarmTime[3] = minutes%10;
        alarmState = true;
        while(button() == 3);
    } else alarmState = false;
  }
}
    
void updateBrightness(){
  // update brightness variable with the value read at analog input 0
  // if V >= 4.83V (4.83/5)*1023 = ~988
  if(analogRead(photo) > 800){
    brightness = 255 - (analogRead(photo)/5);
  } else if((analogRead(photo) < 800) && (analogRead(photo) > 700)){
    brightness = 255 - (analogRead(photo)/8);
  } else {
    brightness = 255;
  }
  // if  4.7V 
}

void loop(){
    analogWrite(leds, brightness);
    buttonCheck();
    updateBrightness();
    alarm();
  
    timeFunction();
}

Personal Soldering Fume Extractor Design Using Solidworks and 3D Printing

The soldering fume extractor was a personal project I did mostly to learn Solidworks and 3D printing. To make use of a 120V AC PC fan that was given to me by a friend, I got a metal tool mount from the dollar store for $5. The next step was to find a way to securely mount the fan and this is where the Solidworks design came in. This project provided me with a good introduction to basic Solidworks modelling and 3D printing. The results are shown in the images below:

Fan Mount CAD Model Fan Mount Pieces Fan Mount Assembled