Pete-Bot – Troubleshooting the GM6 Motors

Written by Zachary de Bruyn

Troubleshooting Results

During the integration of the peripheral devices it was discovered that the GM6 Motors did not operate accordingly. When the motors were inserted into the JP2 and JP3 ports of the 3DoT board, the motors would not operate with the provided code designed to test the GM6 Motors.

/*
Sample Code to run the Sparkfun TB6612FNG 1A Dual Motor Driver using Arduino UNO R3

This code conducts a few simple manoeuvres to illustrate the functions:
  - motorDrive(motorNumber, motorDirection, motorSpeed)
  - motorBrake(motorNumber)
  - motorStop(motorNumber)
  - motorsStandby

Connections:
- Pin 3 ---> PWMA
- Pin 8 ---> AIN2
- Pin 9 ---> AIN1
- Pin 10 ---> STBY
- Pin 11 ---> BIN1
- Pin 12 ---> BIN2
- Pin 5 ---> PWMB

- Motor 1: A01 and A02
- Motor 2: B01 and B02

*/
// FOR V5.03
//Define the Pins

//Motor 1
int pinAIN1 = 12; //Direction
int pinAIN2 = 4; //Direction
int pinPWMA = 6; //Speed

//Motor 2
int pinBIN1 = 9; //Direction
int pinBIN2 = 5; //Direction
int pinPWMB = 10; //Speed

//Standby
int pinSTBY = 8;

//Constants to help remember the parameters
static boolean turnCW = 0;  //for motorDrive function
static boolean turnCCW = 1; //for motorDrive function
static boolean motor1 = 0;  //for motorDrive, motorStop, motorBrake functions
static boolean motor2 = 1;  //for motorDrive, motorStop, motorBrake functions

void setup()
{
  Serial.begin(9600);
  //Set the PIN Modes
  pinMode(pinPWMA, OUTPUT);
  pinMode(pinAIN1, OUTPUT);
  pinMode(pinAIN2, OUTPUT);

  pinMode(pinPWMB, OUTPUT);
  pinMode(pinBIN1, OUTPUT);
  pinMode(pinBIN2, OUTPUT);

  pinMode(pinSTBY, OUTPUT);
  asm("in r24, 0x35");
  asm("ori r24, 0x80");
  asm("out 0x35, r24");
  asm("out 0x35, r24");
}

void loop()
{
  //Assuming that the input command from the arxterra app can be read as an integer
 
 motorDrive(motor1, turnCW, 255);

//  delay(500);
//  motorBrake(motor1);
//
//  delay(500);
  //Command to make spider walk backward

  motorDrive(motor2, turnCCW, 255);
//  delay(500);
//  motorBrake(motor2);
//  delay(500);
}

void motorDrive(boolean motorNumber, boolean motorDirection, int motorSpeed)
{
  /*
  This Drives a specified motor, in a specific direction, at a specified speed:
    - motorNumber: motor1 or motor2 ---> Motor 1 or Motor 2
    - motorDirection: turnCW or turnCCW ---> clockwise or counter-clockwise
    - motorSpeed: 0 to 255 ---> 0 = stop / 255 = fast
  */

  boolean pinIn1;  //Relates to AIN1 or BIN1 (depending on the motor number specified)


  //Specify the Direction to turn the motor
  //Clockwise: AIN1/BIN1 = HIGH and AIN2/BIN2 = LOW
  //Counter-Clockwise: AIN1/BIN1 = LOW and AIN2/BIN2 = HIGH
  if (motorDirection == turnCW)
    pinIn1 = HIGH;
  else
    pinIn1 = LOW;

  //Select the motor to turn, and set the direction and the speed
  if (motorNumber == motor1)
  {
    digitalWrite(pinAIN1, pinIn1);
    digitalWrite(pinAIN2, !pinIn1);  //This is the opposite of the AIN1
    analogWrite(pinPWMA, motorSpeed);
  }
  else
  {
    digitalWrite(pinBIN1, pinIn1);
    digitalWrite(pinBIN2, !pinIn1);  //This is the opposite of the BIN1
    analogWrite(pinPWMB, motorSpeed);
  }

  //Finally , make sure STBY is disabled - pull it HIGH
  digitalWrite(pinSTBY, HIGH);

}

void motorBrake(boolean motorNumber)
{
  /*
  This "Short Brake"s the specified motor, by setting speed to zero
  */

  if (motorNumber == motor1)
    analogWrite(pinPWMA, 0);
  else
    analogWrite(pinPWMB, 0);
}

void motorStop(boolean motorNumber)
{
  /*
  This stops the specified motor by setting both IN pins to LOW
  */

  if (motorNumber == motor1) {
    digitalWrite(pinAIN1, LOW);
    digitalWrite(pinAIN2, LOW);
  }
  else
  {
    digitalWrite(pinBIN1, LOW);
    digitalWrite(pinBIN2, LOW);
  }
}

void motorsStandby()
{
  /*
  This puts the motors into Standby Mode
  */
  digitalWrite(pinSTBY, LOW);
}

With no consideration for the other peripheral devices, and just the GM6 motors attached to the board, the motors are programmed to operate at the HIGH setting as depicted in the code (255). Instead the motors would only “tick”. The following configurations were utilized to try and troubleshoot the issue with the GM6 Motors.

Figure One – Test Results

The above test results above suggest that the board is not providing the necessary voltages to the motors while both are plugged into the board. I referred to the schematic and started by investigating the voltages being read to the motor driver pins A01 and A02

Figure Two – From 3DoT v5.03 schematic

While operating at nominal conditions, I find that the voltages read from these pins are similar to what I was measuring on the motors. I had similar results when performing the measurements for JP3 under identical conditions. Once both motors were connected, however, those voltages dropped down to 4.2 to 7.2 mV.

Testing the TPS61200

The traces of the motor driver were followed back to the TPS61200 buck/boost converter, suspecting that it might be the culprit. However in order to get to the TPS61200, as well as the other IC’s, the CR123 battery holder needed to be replaced and rigged in such a manner that it would still operate the 3DoT board.

Figure Three – Removed Battery Holder

As shown in the figure, the battery holder was removed by removing the solder from the holder leads on the back side of the 3DoT board. Once the battery holder was removed stripped wire was soldered to the battery holder and then soldered onto the 3DoT board. This setup, while ugly, is only temporary; and what has been done can be undone and the battery holder can be reapplied in the correct way once the troubleshooting of the board has completed.

Once the battery holder jumper wires were soldered onto the board, the 3DoT was operationally checked first by simply powering on the board, and then by verifying the board was still programmable.

Figure Four – Temporary Battery Setup

By reviewing both the data sheet of the TPS61200 and the schematic of the v5.03 board, the power pins of the TPS61200 were measured as well as their corresponding input pins to the dual motor driver.

The first pin measured was the EN pin of the TPS61200 which is directly linked to the power switch of the battery. Measuring the EN pin resulted in 4.18 V. By verifying the fact that the EN pin was reading the same voltage as the battery we could safely assume that the network from the battery holder to the input of the TPS61200 was operating correctly, including the 1.5A fuse which lies between the battery holder and the switch. The output pin VOUT was then measured to assure that it was providing the 5 V necessary to power the dual motor driver. Upon inspection, we find that the VOUT pin indeed does measure 5 V (5.06 V to be exact). This node was then traced back to the motor driver.

While operating under no load (ie no motors connected to the motor driver) the voltages were measured at pins VM1, VM2, and VM3 of the dual motor driver. The voltages measured at the motor driver were approximately 5 V for all three of the inputs to the driver. The SAME voltages were read at the three inputs when both motors loads were attached to the board.

By referring to the previous test of the dual motor driver, it is recalled that while a  motor  was operating at optimal conditions the output nodes of the motor drivers (AO1, AO2, BO1, BO2) were 5 V, however once another motor load was placed onto the motor driver, the voltages across the nodes would read 4 to 7 mV.

Reviewing the datasheet of the motor driver we see the following block diagram, and the blocks H-SWA and H-SWB.

Figure Five – Blocks for H-SWA and H-SWB

These H-SW blocks correspond with the MOSFET current mirror images shown below.

Figure Six – MOSFET current mirror images

By analyzing the diagram, it is my belief that the cause of the motor stall issue is that there is a blown MOSFET somewhere in the H-SW block that causes perhaps a short which causes the motors both to be pulled to ground while simultaneously plugged in to the 3DoT board. The voltage parameters are nominal leading up to the motor driver.

Pete-Bot Integration and Testing

Written by Zachary de Bruyn

Table of Contents

Setup

Upon receiving the 3DoT v5.03, the planned peripheral devices were installed and initiated onto the board. The below table displays the ports associated with the 3DoT board, and which pins were connected to the respective peripheral device. Example, the VCC and GND of JP2 are associated with one of the GM6 Motors.

Table One – Ports Associated with 3DoT

As indicated in the below block diagram, there have been a couple peripheral changes in the Pete Bot Chassis from the Preliminary Design Review until now. Reasons for these changes occurred due to several factors. One factor is to consider I2C implementation when designing your system. For our initial design, we were going to utilize a TCS34725 color sensor, however, conflicts arose due to the fact that that sensor utilized I2C address 0x29, which is a common address to use for peripheral devices such as this. Therefore, in order to utilize more than one sensor on the 3DoT, and shield would be needed that would utilize an I2C multiplexer. At the time of the PDR, no viable solution had been discovered which would allow the Pete Bot to implement the ability to sense objects. Many studies were performed, and a VL6180 proximity sensor was chosen to be the best option to be implemented for the 3DoT. The VL6180 operated at a different I2C address and could be easily implemented with the 3DoT peripheral headers, J5 and J6.

Figure One – Final Block Diagram

Measurements

Before physically associating the peripheral devices for their respective ports on the 3DoT board, measurements were performed to check the operating capabilities of the 3DoT board to assure proper functioning. The table below depicts measured values associated with each port, and the required values required to operate the devices.

  1. VL6180 Proximity Sensor
    1. The required voltage to operate the sensor is rated at 2.8 to 5.0 V. Measuring the 3V3.
    2. The measured voltage is 3.28 V
    3. The operating current of the sensor is dependent on the state of the sensor.
      1. Ranging 1.7 mA
      2. Standby is less than 1 uA
    4. The measured current in standby is .10 mA
  2. IR Sensor
    1. The nominal voltage of the sensor is 3.3 V
    2. The measured voltage of the IR shield is 3.28 V.
    3. The measured current draw of the IR shield is 0.1 mA.
  3. GM6 Motors

During testing of the GM6 Motors implemented on the 3DoT board, it was discovered that no readable current or voltages were identified. Various script uploads were performed by different computers, however, it appeared to be a physical limitation with the board.

  1. Measured voltage at a PWM of 255
    1. Motor A
    2. Motor B
  2. Measured current at a PWM of 255
    1. Motor A
    2. Motor B

***** SEE BELOW FOR TROUBLESHOOTING *******

Test/Operational Functioning

The 3DoT board and the above listed peripheral devices were associated with their respective ports in order to perform a baseline operational test on the devices to ensure the devices were operating accordingly. This was performed by writing test script in Arduino and displaying their results in the serial monitor. The following code was used to test the functionality of the devices.

Figure Two – Code for testing functionality of devices

VL6180 Proximity Sensor

The proximity sensor used for the 3DoT board was tested utilizing the following Arduino script.

#define __PROG_TYPES_COMPAT__
#include <avr/pgmspace.h>
#include <Robot3DoTBoard.h>     // instantiated as Robot3DoT at end of class header
#include <Configure.h>
#include <EEPROM.h>
#include <Wire.h>               // I2C support
#include "SparkFun_VL6180X.h"
#include "maze.h"
#include "motor.h"

Robot3DoTBoard Robot3DoT;       // instantiated as Robot3DoT at end of class header

/*Declarations for Proximity Sensor*/
#define VL6180X_ADDRESS 0x29
VL6180xIdentification identification;
VL6180x sensor(VL6180X_ADDRESS);

/* PUT THIS CODE IN THE SETUP SECTION OF THE ARDUINO CODE */

  /* Proximity Setup*/
  Wire.begin(); //Start I2C library
  delay(100); // delay .1s
  sensor.getIdentification(&identification); // Retrieve manufacture info from device memory
//  printIdentification(&identification); // Helper function to print all the Module information

  if(sensor.VL6180xInit() != 0)
  {
    Serial.println("FAILED TO INITALIZE"); //Initialize device and check for errors
  };

  sensor.VL6180xDefautSettings(); //Load default settings to get started.
  delay(1000); // delay 1s

/* PUT THIS CODE IN THE LOOP SECTION OF THE ARDUINO CODE AFTER Robot3Dot.loop() */

/* TEST CODE FOR PROXIMITY SENSOR*/
  //Get Distance and report in cm
  Serial.print("Distance measured (mm) = ");
  Serial.println( sensor.getDistance() );
  int distance = sensor.getDistance();
  delay(500);

The above code was able to utilize the I2C functionality of the 3DoT board, and was able to accurately measure integer distances in units of millimeters. At the end of the above code, an int variable declaration was made which saved the measured distance into a new variable which would be passed to another subroutine in our 3DoT file which would be used to trigger an interrupt and let the robot know of an obstruction in it’s path. A pseudo code for this obstruction was provided by a member of the Goliath project (John Ocampo) HERE.

IR Sensor

The below code was tested and implemented into the 3DoT board to measure the IR of the material/surface under the four implemented QRE1113GR sensors.

/*Declarations for IR Sensor*/
int farRight_IR;
int innerRight_IR;
int innerLeft_IR;
int farLeft_IR;

/* PUT THIS SECTION IN SETUP()*/

/* IR Setup */
  pinMode(A3,INPUT);      //Top view, pins up, far right IR sensor
  pinMode(SDA,INPUT);     //Top view, pins up, second right IR sensor
  pinMode(SCL,INPUT);      //Top view, pins up, second left IR sensor
  pinMode(A2,INPUT);      //Top view, pins up, far left IR sensor

/* PUT THIS SECTION IN LOOP() AFTER 3DoTRobot.loop()*/

/* TEST CODE FOR FOR IR SENSOR */ 
 farRight_IR = analogRead(A3);
 innerRight_IR = analogRead(SDA);
 innerLeft_IR = analogRead(SCL);
 farLeft_IR = analogRead(A2);

 Serial.print("farRight_IR =  ");
 Serial.print(farRight_IR);
 Serial.print("  ");
 Serial.print("innerRight_IR = ");
 Serial.print(innerRight_IR);
 Serial.print("  ");
 Serial.print("innerLeft_IR = ");
 Serial.print(innerLeft_IR);
 Serial.print("  ");
 Serial.print("farLeft_IR = ");
 Serial.println(farLeft_IR);

As demonstrated by the test code above, the 3DoT collected the analog values and I2C values of the QRE1113 sensors and were used to display upon the serial monitor. The IR sensor can detect white or black light, and it is the IR (heat) retention in these surfaces which the sensor reads.

The 3.3 V Pro Micro back-up I&T

Due to the operational conditions of the 3DoT board, a backup system needed to be created that would simulate the software that could complete the mission requirements of the Pete Bot.

Figure Three – Pinout Diagram of Pro Micro

Using the above pinout diagram provided through the SparkFun website, the new pinout diagram is shown in the table below.

Table Two – Pinout Diagram Associated with Drivers, Sensors, and Encoder

The pins not shown are the VCC and GND implementations which are assumed to be known by the reader. As we can see from the above diagram there is no conflict of I2C interfaces with this implementation. SCL and SDA are exclusively used through the proximity sensor. The encoders: Right Motor Encoder (RME) and Left Motor Encoder (LME) are also shown above. Not shown above is the pinout diagram associated with the dual motor driver, which is equivalent to that of the pinout associated with the v5.03 3DoT schematic.

These pins are associated with the ports and registers of the 32U4 through the following code provided by Matt Shellhammer from EE 444.

#define __PROG_TYPES_COMPAT__
#include <avr/pgmspace.h>
#include "maze.h"

// Define motor driver pins                      I USED THE FOLLOWING PINS INSTEAD
#define AIN1 7  // Pro-micro pin 2  (PD1)               PE6 pin 7
#define BIN1 9  // Pro-micro pin 7  (PE6)               PB5 pin 9
#define AIN2 4  // Pro-micro pin 4  (PD4)               PD4 p4
#define BIN2 5  // Pro-micro pin 8  (PB4)               PC6 p5
#define PWMA 6  // Pro-micro pin 5  (PC6)               PD7 p6
#define PWMB 10  // Pro-micro pin 6  (PD7)              PB6 p10
#define STBY 8  // Pro-micro pin 9  (PB5)               PB4 p8

// Define encoder pins
#define LME 14  // Pro-micro pin 10 (PB6)               PB3 p14
#define RME 16  // Pro-micro pin 16 (PB2)              Good as is

void setup() {
  Serial.begin(9600);
  // DDRx & PORTx for IR sensors, 4th PORT ADDED FOR EXTRA IR SENSOR
  DDRF &= ~((1<<PF7)|(1<<PF6)|(1<<PF5)|(1<<PF4));
  PORTF &= ~((1<<PF7)|(1<<PF6)|(1<<PF5)|(1<<PF4));

  // DDRx & PORTx for motor drivers
  DDRD |= (1<<PD4)|(1<<PD7);
  DDRE |= (1<<PE6);
  DDRB |= (1<<PB4)|(1<<PB5)|(1<<PB6);
  DDRC |= (1<<PC6);
  // DDRx & PORTx for Encoders
  DDRB &= ~(1<<PB2);
  PORTB |= (1<<PB2);
  DDRB &= ~(1<<PB3);
  PORTB |= (1<<PB3);
  delay(5000);
}

Test/Operational Functioning

VL6180X

The script to run the proximity sensor is similar to that of the 3DoT program used above. The declarations and functions were placed in a similar manner as well. It is important to remember when using this sensor to also implement the header file so that the software can recognize the specialized functions associated with the sensor. Using the I2C protocol, the sensor is again able to accurately read objects in units of millimeters.

IR Sensor

The utilization of the IR sensor is executed in a different way compared to that of the previous script for the 3DoT board. In the case of this execution of script for the IR sensor the associated ports corresponding to that of the Pro Micro are declared and bit shifted to their respective bit number. Below is a excerpt which highlights the declaration of the registers within the 32U4.

void setup() {
  Serial.begin(9600);
  // DDRx & PORTx for IR sensors, 4th PORT ADDED FOR EXTRA IR SENSOR
  DDRF &= ~((1<<PF7)|(1<<PF6)|(1<<PF5)|(1<<PF4));
  PORTF &= ~((1<<PF7)|(1<<PF6)|(1<<PF5)|(1<<PF4));

As we can see from the above, the IR sensor is associated with the F register within the 32U4, and the values are bit shifted so that the DDRF register will have the following bit sequence: 1 1 1 1 0 0 0 0. The same sequence corresponds with the F Port. A subroutine was created which allowed the program to interpret the information being relayed to the sensors.

     sensors_t readSensors(sensors_t sensors) {
        // readSensors: 0 to 0.4 is white; 0.6 to 1 is black
        // 0.4 to 0.6 determined by previous values (coming from black/white)
        int n = 10;     // number of ADC samples
        float x_i;      // ADC input for sample i
        float A_1;      // current i running average
        float A_0;      // previous i-1 running average

       // read outter left IR sensor           OLD LEFT
       A_0 = 0.0;
       for (int16_t i = 1; i <= n; i++) {
          x_i = analogRead(A0)/1024.0;
          A_1 = A_0 + (x_i - A_0)/i;
          A_0 = A_1;
       }
       sensors.IR0 = A_0;
     Serial.println(sensors.IR0);
       delay(1000);

       // read inner left IR sensor          OLD MIDDLE
       A_0 = 0.0;
       for (int16_t i = 1; i <= n; i++) {
          x_i = analogRead(A1)*(-1.0/1024.0);
          A_1 = A_0 + (x_i - A_0)/i;
          A_0 = A_1;
       }
       sensors.IR1 = A_0;
       Serial.println(sensors.IR1);
       delay(1000);

       // read inner right IR sensor       OLD RIGHT
       A_0 = 0.0;
       for (int16_t i = 1; i <= n; i++) {
          x_i = analogRead(A2)*(-1.0/1024.0);
          A_1 = A_0 + (x_i - A_0)/i;
          A_0 = A_1;
       }
       sensors.IR2 = A_0;
       Serial.println(sensors.IR2);
       delay(1000);

       // read outer right IR sensor
       A_0 = 0.0;
       for (int16_t i = 1; i <= n; i++) {
          x_i = analogRead(A3)/1024.0;
          A_1 = A_0 + (x_i - A_0)/i;
          A_0 = A_1;
       }
       sensors.IR3 = A_0;
       Serial.println(sensors.IR3);
       delay(1000);
       return sensors;
}

The subroutine takes the calculated values from the IR sensor and returns the value to a PID calculator, and then an “If” statement is used to interpret the room that the robot is to be in. The values picked up for the outer IR sensors are usually above 0.98 for black surfaces and below 0.89 for white surfaces. The inner sensors result in a similar response albeit being negative. The IR sensor was tested laying flat on the ground, with the QRE1113 sensors facing down.

GM6 Motors

The motor drivers for the board were associated in a similar way. The driver pins connected to the Pro micro were saved into the various registers of the Pro micro and are shown in the below setup for the drivers.

// DDRx & PORTx for motor drivers
  DDRD |= (1<<PD4)|(1<<PD7);
  DDRE |= (1<<PE6);
  DDRB |= (1<<PB4)|(1<<PB5)|(1<<PB6);
  DDRC |= (1<<PC6);
  // DDRx & PORTx for Encoders
  DDRB &= ~(1<<PB2);
  PORTB |= (1<<PB2);
  DDRB &= ~(1<<PB3);
  PORTB |= (1<<PB3);

As we can see from the above set up the respected ports are bit shifted to specific bit numbers within the  various registers and can be calculated in a binary form similar to how they were calculated in the example for IR sensors. When the script is executed however with the given program, the motors do not respond through the motor driver breakout board.

These values for the motors, and sensors have instances created for them to where when the script is executed.

void loop() {
  Wire.begin(); //Start I2C library
  delay(100); // delay .1s

  static uint8_t type;
  static myRobot_t robot_inst;            // create an instance of myRobot_t called robot_inst
//  static proxSensor_t proxSensor_inst;    // create an instance of proxSensor_t called proxSensor_inst
  static sensors_t sensors_inst;          // create an instance of sensors_t called sensors_inst
  static motors_t motors_inst;            // create an instance of motors_t called motors_inst
  static PID_t PID_inst;                  // create an instance of PID_t called PID_inst

//  proxSensor_inst = readProx(proxSensor_inst);
 int distance = proxSensor.getDistance();
 Serial.println(distance);
 detection(distance);
 /* IF distance is XXXXX
     DO THIS
    Else
     DO THAT
 */

  sensors_inst = readSensors(sensors_inst);             // Read sensor values
  PID_inst = PIDcalc(sensors_inst, PID_inst);           // Calculate PID value
  motors_inst = errorCorrection(PID_inst, motors_inst); // Correct for error with motors
  forward(motors_inst);                                 // send new speed to motors to move forward
  Serial.println("OUT2 Forward");
  // Check if in forest
  inForest(robot_inst);

  // Check if at an intersection
  if ((sensors_inst.IR0 >= 0.89)&&(sensors_inst.IR3 >= 0.89)) // was a negative in front of sensors_inst.IR3, not sure why
  {
    robot_inst = enterRoom(robot_inst);
    Serial.println("After enterRoom");
    type = roomType(robot_inst);
    Serial.println("After roomtype");
    robot_inst = whichWay(type, robot_inst);
    Serial.println("After WhichWay");
  }
  Serial.println("IF statement ended");
}

boolean detection(int distance)
{
  double square_size=66;//mm
  double num_square=ceil(distance/square_size); //length of a square is about 66mm

//Serial.print("Squares Away ");
//Serial.println(num_square);
//delay(100);

  if (num_square<=1)
    {
      boolean inrange= true;
      return(inrange);
    }
  else
    {
      boolean inrange= false;
      return(inrange);
    }
}

Adapt C++ 3DoT Mission Code to SAMB11

Written by Zachary de Bruyn

Table of Contents

Purpose

The purpose of this post is to instruct how to implement the 3DoT code for the SAMB11 MCU. Unfortunately, the SAMB11 is not supported by such a large community like that of the ATMega32U4. There is also not built in functions like there are for Arduino which simplify matters for those interested in the SAMB11.

Set-Up

The first step in utilizing the SAMB11 to be implemented for use is to first download Atmel Studios, which can be found HERE. The good thing about Atmel Studios is that there is a plethora of MCU’s one can program through the software, including the SAMB11.

In order to prep Atmel Studios to use the SAMB11 the following steps need to be performed:

First, click on the “New Project” link at the left hand side of the program. A window will pop-up prompting you to choose one of the various options, either a C or C++ executable program. Once you have chosen which to use, be sure to name the file. After which a folder is created in the “Location” directory where you can find your project. It is suggested if you are wanting to use a majority of Arduino syntax, C++ is the best option, considering C does not support some functionality that Arduino does, such as Classes.

Figure One – Opening a New Project

Once you have saved the executable project a “Device Selection” window will appear. This is where you can select a wide variety of microprocessors, including the SAMB11.

Figure Two – Selecting a Device

As we can see from the figure, the device we have opted to use was the ATSAMB11G18A. Once the correct MCU has been selected, Atmel brings you to the editor, and the “main.cpp” file is automatically generated. Within this main.cpp program, you can see a header file “sam.h” is automatically generated.

Adding .h and .cpp files

Once you have gotten to the main editor window, you can begin creating header files and other subordinate files to the main.cpp(). Note, that it is important that when you are creating new files, you do so under the “Project Name” file. By not doing this you will have many issues when it comes to compiling and debugging your code.

If you do not see the Solution Explorer window click CTRL + ALT + L.

Figure Three – Adding .h and .cpp files

To add other files to your project file, right click on your project name, go to Add and select New Item. Here you can implement another .cpp file or a .h file

Figure Four – Adding other files

Implementing the new program in Atmel Studios

Unfortunately, as I’m sure you are aware, implementing the Arduino software in any other IDE is not a simply copy and paste solution. Because there are MANY built in functions in Arduino, a lot of what we incorporate into the .cpp file will not be supported. Functions like pinMode(), analogWrite(), analogRead(), will all have to be created within the project file. The same is true for Arduino libraries, such as: EEPROM, Wire, and Robot. These libraries do not exist in Atmel Studios, therefore a lot of work will be needed to generate these replacement files.

A solution to this is create a new .h file, and implement the various Arduino function in the file so that you can utilize them for your program. Lets say for example we want to create the ability to use pinMode() in our .cpp file. To do so, in your created header file (.h file) you could start by declaring the function like you would for a function in Arduino. Below is an example:

#ifndef FileName_h
#define FileName_h

// LIST DEFINITIONS YOU MAY COMMONLY USE IN ARDUINO, EXAMPLE PI

void pinMode(uint8_t, unit8_t);

#endif

In the above code we created the function pinMode to accept two unsigned 8 bit integers, which is what would normally be implemented in the Arduino built in function. Creating all these files is a tedious process, and requires research into how Arduino implements there custom libraries to utilize various built in functions. There are various resources online that can help with implementing Arduino code to the new program you are writing however, be ready to debug because what you find online may not be applicable.

Atmel Studios Built-in Examples

If you find yourself lost and confused, don’t worry you’re not alone. Atmel Studios actually provides a lot of examples on how to implement various aspects of which ever microprocessor you choose. One suggestion is to invest in a development board which utilizes the SAMB11. This link HERE provides one suggestion to where you can begin testing. In order to access the built-in examples for which ever board you choose (The suggested one is recommended because it’s known for a fact that there are examples associated for that board.) click on the “New Example Project” shown in the first figure right under “New Project”. If you have the Xplained Pro plugged into your computer, Atmel Studio will automatically detect it. If not, click on “Kit” and select the “SAM B11 Xplained Pro”. From the drop-down menu, you can see the plethora of examples you can use. For example, there are a few example projects which discuss BLE implementation and allow you to send and receive texts from your mobile device. Note, in order to use these BLE examples, you must download the mobile app “Atmel SmartConnect”, which will allow you to discover your board to send and receive messages from your computer.

Figure Five – Example Projects

Pete-Bot Paper Shell

Written by Elizabeth Nguyen (Project Manager)

Objective

Pete-Bot requires an outer paper shell that covers the chassis. Its image should have a likeness of CSULB’s mascot Prospector Pete.

Template

Provided by Professor Hill was a template to create a concept art for the Pete-Bot paper shell. The original image is of Optimus Prime.

Templates of Antenna, Base, and Arms

Templates of Head and Body

Challenges

There are not a lot of pictures of Prospector Pete in the first place. This proved to be a challenge to create a concept art that can fit within the template. Also, no one in the Pete-Bot team has artistic experience, so a friend of the project manager was commissioned.

Time was another issue. In reality, this paper shell should have been worked on from the beginning. It required a concept art that would fit within the template and then worked on from there.

Current Image

My friend was able to draw a 360-view of Prospector Pete. Although it cannot be currently used for the template, it could be used for future reference.

Concept Art

Project and Planning Schedule

Written by Elizabeth Nguyen (Project Manager)

Objective

The objective of the planning and schedule task is to compile a project schedule for EE 400D from start to finish. The schedule was made on Microsoft Project and can be used as future reference for EE 400D project planning. What I’ve described is the process I’ve taken to create this project schedule (currently incomplete) and what details I’ve kept in mind.

Initial Planning

A discussion took place with Professor Hill concerning this project schedule. It needed to encompass a more detailed breakdown of the tasks a toy robot project would require along with links to tasks (to determine a critical path) and a timeline.

For reference, the EE 400D Task Matrix was used as a template for the assembly, software development, and verification phases. A more general project schedule was used to define the details of the design and planning phase.

Top Level Schedule

There are six general phases:

  • Hiring – Week One to Week Three
  • Planning – Week Four to Week Seven
  • Design – Week Four to Week Seven
  • Assembly – Week Eight to Week Thirteen
  • Software Development – Week Three to Week Fourteen
  • Verification and Validation – Week Thirteen to Week Fifteen

I broke down these six phases by the amount of weeks allocated towards them and further broke them down by tasks that should start or begin within them.

Divisions and Management

There are three divisions within EE 400D that students could be assigned to. A member of each division is then assigned to a project manager (PM). Each division is overseen by a division manager (DM) who is responsible for providing training for their respective division members. Their training schedule is accounted for in this project schedule.

Outlined below is a breakdown of the divisions and what they are tasked to do:

  • Manufacturing (MFG)
    • Responsible for learning SolidWorks in order to make 3D-print models for their project
  • Electronics & Control (E&C)
    • Responsible for learning Eagle to design and fabricate a custom PCB for their project
    • Responsible for various electrical components for their team such as encoders, servos, motors, etc.
    • Responsible for firmware
  • Missions, Systems, Test, and Software (MSTS)*
    • Responsible for determining resource allocation (current draw, power budget, etc.)
    • Responsible for development of software (which will follow the EE 444 lab sequence)
    • Responsible for verification and validation
    • Responsible for defining Level 2 Requirements

*Missions, Systems, Test, and Software may be divided into two divisions where MST is as it was before and Software is its own division. This is due to the fact that software tends to be ignored and left until the end of the semester to be done. Also, based on how I’ve currently structured the project schedule, MSTS may be too much of a responsibility for a single student.

Outlined below are some of the responsibilities of the PMs and DMs that were taken into account for the project schedule:

  • Project Managers
    • Responsible for outlining the requirements definition
      • Mission Objective
      • Level 1 Requirements
    • Responsible for the Preliminary Design Plan and Preliminary Project Plan
      • Monetary Budget
      • Project Schedule
    • Division Managers
      • Responsible for creating a training schedule for their respective divisions

Linkages

One important aspect of the project schedule is that the tasks are linked together. Links are created because one task cannot begin without another finishing. For example, PCB fabrication cannot begin without a PCB design and layout.

What also has caused schedules to not perform as intended is because linkages are not determined early enough. The purpose of this project schedule is for these linkages.

Pete-Bot Power Budget

Written by Melwin Pakpahan (Missions, Systems, and Test)

Description

The 3DoT Board contains key components that each draw current from the battery.  The boost draws current directly from the battery and provides power to the LDO. The MST Division Manager created the power budget template which is modified for the Pete-Bot.

Table One

Table Two

The Pete-Bot will use two motors and two color sensors. Values in blue cells are measured values. The motors consume most of the current from our system with about 100mA per motor, but this is acceptable. This value was obtained from my previous blog post, “Measuring Power Consumption of 3DoT Board.”

Table Three

Table Four

The margins for the LDO, Boost, and battery allow for a large margin for additional components.  The estimated mission duration is 20 minutes. The Pete-Bot is expected to run the mission within this time allotted.

Ultrasonic Custom 100mil Male Connector

Written by Zachary de Bruyn

Purpose

The 100-mil male connector was necessary in order to incorporate an accessory item, such as a sensor, to one of the 3DoT boards headers. The ideal connector would allow all projects within 400D to utilize a “universal” connector to implement for their respective projects.

Connector Elements

The utilization of a 100-mil male connector was only applicable to the 3DoT board which utilized female header pins as shown below.

Figure One – JP5 Header used for 3DoT board

The 3DoTX, which utilizes the SAMB11 MCU was designed using male header pins, seen here:

Figure Two – 3DoTX male header pins

Due to the two different header stles used for both boards, a “universal” connector pin could not be implemented to be utilized with a sensor, such as the VL6180X proximity sensor shown below. The pins utilized for the breakout board are male header pins, similar to what is shown in Figure Two.

Figure Three – VL6180 breakout board

Therefore, in order to implement a system that would allow the proximity sensor to be used for both the 3DoT and the 3DoTX, a set of female-to-female (f2f) jumpers will be implemented and attached to the proximity sensors male header pins. This will then be used to connect to the initial 3DoTX board, which again, utilizes male header pins in lieu of the female header pins.

Alternative Plan

The best case scenario is that the 3DoTX board performs its mission objectives without incident. However, if an occasion were to arise such as the new 3DoTX board being replaced by the heritage 3DoT board, then the replacement would be a simple “plug and play.” This would be done first by removing the 3DoTX board from the Pete-Bot chassis. Second, a spare set of male header pins will be inserted into the JP5 female header pins of the 3DoT board. Finally, the f2f jumper cable will then be inserted into the respective port. The heritage 3DoT board can then be easily inserted back into the bottom of the chassis, and the robot can then attempt to perform the objectives it was designed for.

Rapid Prototyping, Motor Assembly, and Print Optimization

Written by Railan Oviedo (Manufacturing)

Table of Contents

Introduction

For this semester’s version of Pete-Bot, the rapid prototyping process involved the verification of being able to fit the motors and the 3DoT board inside a single 3D-printed chassis piece. Furthermore, after confirming that the base design was suitable for fitting the motors and the 3DoT board, the model itself would be altered in order to reduce print time. For information on the print time for each version, see the Print Time post.

Printed Version 1

Shown are side-by-side views of the first version (Model vs. Printed Model). The chassis was printed through the use of Northrop Grumman’s 3D-printer thanks to the connections of a fellow student.

Figure One – Front View Side-by-Side

Figure Two – Back View Side-by-Side

Figure Three – Side View Side-by-Side

Testing 3DoT Board Placement

The mechanism for placing the board in this version is the flap in the back side, which can be pulled to allow for the board to be pushed into the chassis. This was tested and confirmed to work; however, the flimsy nature of the flap caused it to break off of the model, which is why it cannot be seen in the pictures. As such, it was decided that a new mechanism will have to implemented for follow-up versions.

Testing Motor Placement

After attempting to fit the motors inside the chassis, it was found that they could not directly be placed inside with the current design. The 3D-model pictures were altered after printing the chassis, so they show the possible solution to allowing the motors to be placed inside.

Printed Version 2

The second version’s design is as follows. This was printed at the same Northrop Grumman source, but the printer experienced a malfunction mid-print so the chassis came out in a much less stable state than originally anticipated. All versions after this were printed through Ridwan.

Figure Four – Front View Side-by-Side

Figure Five – Back View Side-by-Side

Figure Six – Side View Side-by-Side

Updates from Version 1

  • Pathway on the side has been made to allow the motors to be inserted into the chassis
  • Flap design has been altered so that there are now two small flaps that bend in the same direction of the printed layers
  • Holes were added to the bottom part of the front in order to allow the push-pins to have a place to be inserted. These push-pins will secure the paper shell to the chassis
  • Removed the two tiny holes in the front, as they were deemed to serve no purpose

Testing 3DoT Board Placement

This version still incorporates flaps of a sort, but the orientation has been switched. Instead, they bend towards the same direction of the printed layers, thus allowing for a stronger resistance to breaking. The board was once again confirmed to fit inside, but the flimsiness of the flaps were still notable, so further changes were made for future versions.

Testing Motor Placement

Despite the deformation of the design during the printing process, it was confirmed that adding the pathway between the holes allowed for both motors to be successfully inserted at the same time. From this version onwards, this part of the design remains the same since it properly performs its purpose and simultaneously leads to a lower print time.

Printed Version 3

As follows is the third design.

Figure Seven – Front View Side-by-Side

Figure Eight – Back View Side-by-Side

Figure Nine – Side View Side-by-Side

Updates from Version 2

  • Flaps were completely removed, in favor of making one section of the bottom somewhat separated from the rest of the chassis

Testing 3DoT Board Placement

After replacing the flaps with a small section of the chassis that can be pulled outward, it was found that this design is also sufficient in getting the 3Dot board placed inside. Furthermore, since no part of the chassis acts as a flap, the overall structure and security of the board in the chassis has increased. From all versions after this, the design for the 3DoT Board Placement will remain relatively the same.

Printed Version 4

The fourth design is as follows:

Figure Ten – Front View Side-by-Side

Figure Eleven – Back View Side-by-Side

Figure Twelve – Side View Side-by-Side

Updates from Version 3

  • Structures have been put in place on the inside of the chassis to allow for stable screw placement for the gear system
  • Holes on the side of the chassis have been repositioned for gear testing

Testing 3DoT Board Placement

During this iteration of the chassis, it was discovered that the micro-USB port and the power switch attached to a fully aseembled 3DoT board were unable to fit within the previous design. As such, larger holes were placed in the front to allow these parts of the board to fit inside. However, after testing, it was found that these changes were not enough, so revisions to the front will be made for future versions.

Printed Version 5

This version was the most recent upon the creation of this post, so it is photographed with the motors and unassembled 3DoT board in place.

Figure Thirteen – Front View Side-by-Side

Figure Fourteen – Back View Side-by-Side

Figure Fifteen – Side View Side-by-Side

Figure Sixteen – Bottom View showing the unassembled 3DoT in place

Updates from Version 4

  • Because push-pins will only be inserted on the bak of the chassis, the front circular holes have been replaced with rectangular ones in order to accomodate a wooden platform that the castor wheel and color shield will attach to
  • The holes on the front have been expanded to allow for both the micro-USB port and the power switch to be inserted without hindrance

Testing 3DoT Board Placement

Despite the changes made to the front, it was found that the holes need to be even wider so that the fully assembled 3DoT can be placed inside. Besides this, no other design changes seem to be necessary.

Printed Version 6

This version is the latest as of December 12. It is pictured here with the planetary gear system, the wooden platform, and the castor wheel in place.

Figure Seventeen – Front View Side-by-Side

Figure Eighteen – Back View Side-by-Side

Figure Nineteen – Side View Side-by-Side

Updates from Version 5

  • After discovering that push pins are actually placed on the front, holes were put back in place to match their positioning with the paper shell’s holes for the push pins
  • The positioning for the micro-USB and power switch has been moved to the back of the chassis. Furthermore, the back has been opened up to allow for access to both without having to remove the board from the chassis
  • Rectangular openings have been made on the side of the chassis to make space for the SAMB11 board’s power switch
  • The round holes on the side of the chassis have been adjusted in such a way that the planetary gear system now functions perfectly
  • The front of the chassis has had holes put into it to accommodate a possible motion sensor. However, implementation of this sensor would result in having to cut out part of the paper shell
  • The front of the chassis has had its bottom partially removed to account for the front IR shield that will connect to the 3DoT. Slots have also been placed on the front of the chassis to allow the shield to snap into place

Testing 3DoT Board Placement

With this design, the fully assembled 3DoT was finally confirmed to fit inside. Attaching the IR shield to the board further increases its stability within the chassis due to the slots added to the front.

Wooden Platform

The design for the wooden platform began after it was confirmed that the fully assembled 3DoT with the shield could be placed in the chassis. The Solid Works image of the model is as follows:

Figure Twenty – SolidWorks Model of Platform

After laser cutting the model out of wood, the assembled piece appears as:

Figure Twenty-One – Bottom View of Wood Platform

Figure Twenty-Two – Top View of Wood Platform

As shown in the pictures, both the castor wheel and wooden platform were confirmed to fit on the chassis. The platform is secured into its place with nuts and screws, and has the ability to slightly wiggle vertically in order to allow for better shock absorption for the castor wheel.

Summary Table

Table One – Table Showcasing Current Status

Pete-Bot (P-Bot) Print Time

Written by Railan Oviedo (Manufacturing)

Table of Contents

Introduction

For this semester’s version of the Paper-Bot (now dubbed “P-Bot”), one of the design requirements is to have the chassis 3D-printed as a single piece. After creating the 3D models, the approximate print time for the chassis are approximated through the use of Cura software. All print time estimations are made under the assumption that a Prusa i3 is used with the Coarse Quality (0.4 mm) and 20% infill. For information on the differences between the version, see the Rapid Prototype, Motor Assembly, Print Optimization post.

Cura Printing Setup

Figure One – Cura Printing Setup Screenshot

Printed Version 1

Figure Two – Front Isometric View

Figure Three – Back Isometric View

Figure Four – Side View

The Cura print time is shown as:

Figure Five – Version 1 Print Time

Printed Version 2

Figure Six – Front Isometric View

Figure Seven – Back Isometric View

Figure Eight – Side View

The Cura print time is shown as:

Figure Nine – Version 2 Print Time

Printed Version 3

Figure Ten – Front Isometric View

Figure Eleven – Back Isometric View

Figure Twelve – Side View

The Cura print time is shown as:

Figure Thirteen – Version 3 Print Time

Printed Version 4

Figure Fourteen – Front Isometric View

Figure Fifteen – Back Isometric View

Figure Sixteen – Side View

The Cura print time is shown as:

Figure Seventeen – Version 4 Print Time

Printed Version 5

Figure Eighteen – Front Isometric View

Figure Nineteen – Back Isometric View

Figure Twenty – Side View

The Cura print time is shown as:

Figure Twenty-One – Version 5 Print Time

Summary Table

Table One – Summary of Versions and Print Times

HM-11 Bluetooth Module Soldering

Written by Melwin Pakpahan (Missions, Systems, & Test)

Description

This post will cover the assembly of the HM-11 Bluetooth module onto the 3DoT board. This module allows Bluetooth communication between the Arxterra app on an Android phone and the 3DoT board.

Pinout

According to the 3DoT v5.03 schematic, the functional pins of the HM-11 module used for the 3DoT Board are:

  • Pin 2: UART_TX
  • Pin 4: UART_RX
  • Pin 9: VCC
  • Pin 12: GND

Figure One shows the schematic of the HM-11 module taken from the 3DoT v5.03 schematic.

 

Figure One – Schematic of HM-11 module

Assembly

Assembly of the component is as follows:

  • Component is placed onto the board.
  • Flux is liberally applied to the pins, pads, and it surrounding areas.
  • A technique called drag-soldering is applied to solder the module on.
    • The tip of the soldering iron is tinned with an amount needed to cover all pins in a row.
    • Then, the tip of the iron is dragged across that row of pins.
  • Drag-soldering is repeated on the rest of the row of pins.

Finished assembly is shown in Figure Two.

Figure Two – Finished Assembly

Discussion

Pins 2, 4, 9, and 12 are the functional pins that must be soldered on to the board. In our case, all the pins are soldered onto the board to better hold the module in its place. However, this is not recommended because it makes the board more difficult to remove should there be any discrepancies. Therefore, only power (pin 9), ground (pin 12), transmit (pin 2), and  receive (pin 4) should be soldered.

References

[1] HM-11 – Reference One

[2] 3DoT v5.03 Schematic – Reference Two

[3] Drag-soldering – Reference Three