Write to EEPROM
By: Matt Shellhammer (Electronics & Control Engineer)
Approved by: Lucas Gutierrez (Project Manager)
Table of Contents
Introduction
When in RC mode the robots will be controlled to travel through the maze with the Arxterra App through Bluetooth wireless communications. The robots are then required to memorize the path traveled and then repeat this path in playback mode. To make this possible information about the path must be saved while traveling through the maze. The information that will be saved is direction and turn so we know what direction the robot was facing and what direction it turned at each decision point. This data will be stored in EEPROM and then eventually read to implement playback mode.
Methodology
This software is developed to store data about direction and turn value every time a decision is made (room types 1, 2, and 4). It stores data into the EEPROM starting at address 0x0000. Every time a decision is made it stores the direction, increments the counter, stores the turn value decided on, and then increments the counter again for the next time a decision is made. This storage method decided upon is limited to 512 decisions since the address range of EEPROM is 0x0000 to 0x03FF, 1 KB, and we store two bytes for every decision therefore only 512 decisions can be stored within EEPROM.
Data Stored as follows:
Address | Value |
0x0000 |
Direction (decision 1) |
0x0001 | Turn (decision 1) |
0x0002 | Direction (decision 2) |
0x0003 | Turn (decision 2) |
0x0004 | Direction (decision 3) |
… | … |
Software
EEPROM_Write.ino (MAIN SETUP & LOOP) //////////////////////////////////////////////////////////////// // Name : EEPROM Write maze data // // Author : Matt Shellhammer // // Date : 2 December, 2017 // // Version : 1.0 // //////////////////////////////////////////////////////////////// #define __PROG_TYPES_COMPAT__ // __PROG_TYPES_COMPAT__ #include <avr/pgmspace.h> #include <Robot3DoTBoard.h> #include <EEPROM.h> #include <Wire.h> #include <Servo.h> #include "maze.h" void setup() { Serial.begin(9600); delay(5000); } void loop() { static uint16_t EEPROM_Idx = 0x0000; // first EEPROM index is 0x0000 static uint8_t type = 0; // initially outside of the maze static bool decision; // create a variable called decision static myRobot_t robot_inst; // create an instance of myRobot_t called robot_inst // No decision to be made when in a Hallway or outside of the maze (go straight) if ((type == 0)||(type == 5)){decision = false;robot_inst.turn = 0x00;} // No decision to be made when in a left corner (turn left) if (type == 3){decision = false;robot_inst.turn = 0x10;} // No decision to be made when in a right corner (turn right) if (type == 6){decision = false;robot_inst.turn = 0x01;} // No decision to be made when at a dead end (turn around) if (type == 7){decision = false;robot_inst.turn = 0x11;} else{decision = true;} // Call write data to EEPROM when a decision is made on the Arxterra App at a decision point if ((decision == true)&&(EEPROM_Idx < 0x400)){ // Call Arxterra custom command to request a turn value (update robot_inst.turn) // Store dir facing and turn value EEPROM_write(EEPROM_Idx, robot_inst.dir);EEPROM_Idx++; EEPROM_write(EEPROM_Idx, robot_inst.turn);EEPROM_Idx++; } robot_inst = enterRoom(robot_inst); // Update robot_inst type = roomType(robot_inst); // Determine room type } maze.h (Structure, array, and variable definitions) struct coord_t{ uint8_t row = 0x13; // Robot is initially outside of the maze uint8_t col = 0x00; // Robot is initially outside of the maze }; struct myRobot_t{ uint8_t dir = 0x03; // Robot is initially facing north uint8_t turn = 0x00; // First action is no turn coord_t maze; uint8_t room = 0x00; // Initial room is empty uint8_t bees = 0x00; // No bees present }; const uint8_t hit_table[] PROGMEM = {0x08, // South (dir == 0b00) 0x02, // East (dir == 0b01) 0x04, // West (dir == 0b10) 0x01}; // North (dir == 0b11) //Compass S E W N //dir 00 01 10 11 const uint8_t turn_table[] PROGMEM = {0b00, 0b01, 0b10, 0b11, // 00 no turn 0b10, 0b00, 0b11, 0b01, // 01 turn right 0b01, 0b11, 0b00, 0b10, // 10 turn left 0b11, 0b10, 0b01, 0b00 // 11 turn around }; // row col dir const int8_t map_table[] PROGMEM = {1 , 0, // 00 0 , 1, // 01 0 , -1, // 10 -1 , 0 // 11 }; const int maze_length = 399; const uint8_t theMaze[] PROGMEM = // 00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 {0x05,0x09,0x09,0x09,0x09,0x09,0x01,0x03,0x05,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x29,0x09,0x09,0x09,0x02, // 00 0x0C,0x09,0x09,0x03,0x05,0x09,0x0A,0x06,0x06,0x05,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x03,0x05,0x03,0x06, // 01 0x05,0x09,0x0B,0x06,0x06,0x05,0x09,0x0A,0x06,0x0C,0x09,0x09,0x09,0x09,0x09,0x01,0x0B,0x0C,0x0A,0x06,0x06, // 02 0x06,0x0D,0x09,0x0A,0x06,0x06,0x05,0x03,0x0C,0x09,0x09,0x03,0x05,0x09,0x09,0x0A,0x05,0x09,0x09,0x08,0x02, // 03 0x06,0x05,0x09,0x09,0x0A,0x06,0x06,0x0C,0x09,0x09,0x09,0x0A,0x0C,0x09,0x09,0x03,0x06,0x05,0x09,0x09,0x0A, // 04 0x06,0x0C,0x03,0x05,0x09,0x02,0x06,0x05,0x09,0x09,0x09,0x09,0x09,0x09,0x03,0x06,0x06,0x0C,0x03,0x05,0x03, // 05 0x06,0x05,0x0A,0x0C,0x03,0x06,0x06,0x06,0x05,0x01,0x03,0x07,0x05,0x03,0x06,0x06,0x06,0x05,0x0A,0x06,0x06, // 06 0x06,0x0C,0x09,0x03,0x0E,0x0C,0x08,0x02,0x06,0x06,0x06,0x06,0x06,0x06,0x0C,0x02,0x06,0x0C,0x09,0x02,0x06, // 07 0x06,0x05,0x0B,0x0C,0x09,0x09,0x09,0x08,0x02,0x06,0x06,0x06,0x06,0x0C,0x09,0x0A,0x04,0x09,0x0B,0x06,0x06, // 08 0x0C,0x08,0x09,0x09,0x09,0x09,0x01,0x01,0x02,0x06,0x0C,0x08,0x08,0x09,0x01,0x09,0x08,0x09,0x03,0x06,0x06, // 09 0x05,0x01,0x09,0x09,0x0B,0x07,0x06,0x04,0x02,0x0C,0x09,0x09,0x09,0x03,0x04,0x09,0x03,0x07,0x06,0x06,0x06, // 0A 0x06,0x0C,0x09,0x09,0x09,0x02,0x06,0x04,0x02,0x0D,0x09,0x09,0x09,0x0A,0x0C,0x03,0x06,0x06,0x06,0x06,0x06, // 0B 0x06,0x05,0x09,0x09,0x09,0x0A,0x06,0x0C,0x0A,0x05,0x09,0x09,0x09,0x09,0x03,0x06,0x06,0x06,0x06,0x06,0x06, // 0C 0x06,0x0C,0x09,0x09,0x09,0x03,0x04,0x09,0x09,0x08,0x0B,0x05,0x03,0x05,0x0A,0x06,0x06,0x06,0x06,0x06,0x06, // 0D 0x04,0x09,0x09,0x09,0x09,0x08,0x02,0x05,0x01,0x09,0x03,0x06,0x06,0x06,0x05,0x0A,0x0E,0x06,0x06,0x06,0x06, // 0E 0x06,0x05,0x09,0x09,0x09,0x09,0x0A,0x0E,0x06,0x07,0x06,0x06,0x06,0x06,0x06,0x05,0x09,0x0A,0x06,0x06,0x06, // 0F 0x06,0x0C,0x09,0x09,0x09,0x09,0x09,0x09,0x0A,0x06,0x06,0x06,0x06,0x0E,0x0E,0x06,0x05,0x09,0x0A,0x06,0x06, // 10 0x04,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x0A,0x0C,0x0A,0x06,0x05,0x09,0x0A,0x06,0x0D,0x09,0x0A,0x06, // 11 0x04,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x09,0x08,0x08,0x09,0x09,0x08,0x09,0x09,0x09,0x0A, // 12 };
subroutines.ino
/* * Write data to EEPROM, NOTE: interrupts are disabled while writing * @param uiAddress 16 bit interger pointing to the address of the data to write * @param ucData 8 bit value signifying the data being written */ void EEPROM_write(uint16_t uiAddress, uint8_t ucData) { /*Store SREG value before we disable Interrupts*/ char SREG_save = SREG; noInterrupts(); /* Wait for completion of any Flash Write Note:Only necessary if Flash Memory Manipulation is taking place */ while(SPMCSR &(1<<SPMEN)); /* Wait for completion of previous write */ while(EECR & (1<<EEPE)); /* Set up address and Data Registers */ EEAR = uiAddress; EEDR = ucData; /* Write logical one to EEMPE */ EECR |= (1<<EEMPE); /* Start eeprom write by setting EEPE */ EECR |= (1<<EEPE); /*Restore the SREG value*/ SREG = SREG_save; } /* * Read data from EEPROM, NOTE: interrupts are disabled while writing * @param uiAddress 16 bit interger pointing to the address of the data to read * @return 8 bit value signifying the data that was read */ uint8_t EEPROM_read(uint16_t uiAddress) { /*Store SREG value before we disable Interrupts*/ char SREG_save = SREG; noInterrupts(); /* Wait for completion of any Flash Write Note:Only necessary if Flash Memory Manipulation is taking place */ while(SPMCSR &(1<<SPMEN)); /* Wait for completion of previous write */ while(EECR & (1<<EEPE)); /* Set up address register */ EEAR = uiAddress; /* Start eeprom read by writing EERE */ EECR |= (1<<EERE); /*Restore the SREG value*/ SREG = SREG_save; /* Return data from Data Register */ return EEDR; } myRobot_t enterRoom(myRobot_t robot){ robot = turnInMaze(robot); robot = stepInMaze(robot); robot = roomInMaze(robot); return robot; } // Returns updated direction based on current direction and turn value // values returned in robot structure myRobot_t turnInMaze(myRobot_t robot){ // index = 4*turn_val + dir_val uint8_t index = (robot.turn << 2) + robot.dir; robot.dir = pgm_read_byte_near(turn_table + index); return robot; } // Returns updated row and column values after taking a step in current direction // values returned in robot structure myRobot_t stepInMaze(myRobot_t robot){ // index = 2*robot.dir uint8_t index = (robot.dir << 1); robot.maze.row += pgm_read_byte_near(map_table + index); // Add either -1, 0, or 1 to current row value robot.maze.col += pgm_read_byte_near(map_table + index + 1); // Add either -1, 0, or 1 to current column value return robot; } // Returns updated room and bees values using current row and column values // values returned in robot structure myRobot_t roomInMaze(myRobot_t robot){ // index = 21*robot.maze.row + robot.maze.col uint16_t index = (21*robot.maze.row) + robot.maze.col; uint8_t maze_val = pgm_read_byte_near(theMaze + index); robot.room = maze_val & 0x0F; // clear upper nibble and store as the room value uint8_t temp_bees = (maze_val & 0xF0) >> 4; // clear lower nibble and store as the temp bees value robot.bees += temp_bees; // add temp_bees to curret bees value return robot; } // Room Type subroutine uint8_t roomType(myRobot_t robot){ bool leftWall = leftHit(robot); // Test if hiting left wall bool hit = hitWall(robot); // Test if facing wall bool rightWall = rightHit(robot); // Test if hiting right wall uint8_t room = (uint8_t(leftWall) << 2)|(uint8_t(hit) << 1)|uint8_t(rightWall); // Convert to room type return room; } // Returns true if there is a wall and false if there is no wall bool hitWall(myRobot_t robot){ // index = dir_val robot = roomInMaze(robot); // Determine room value uint8_t wallVal = pgm_read_byte_near(hit_table + robot.dir); // Determine wall bit based on direction uint8_t outVal = bool(wallVal & robot.room); // Clear all bits other than the wall robot is facing if (outVal == 0){return false;} // If the robot is not hiting a wall outVal will equal zero else {return true;} // and the subroutine will return false, else it returns true. } // Returns true if there is a wall and false if there is no wall // on the right side of the robot bool rightHit(myRobot_t robot){ robot.turn = 0x01; // Modify turn value to turn right robot = turnInMaze(robot); // Call turnInMaze to turn the robot (virtually) bool hit = hitWall(robot); // Test hit wall return hit; } // Returns true if there is a wall and false if there is no wall // on the left side of the robot bool leftHit(myRobot_t robot){ robot.turn = 0x02; // Modify turn value to turn left robot = turnInMaze(robot); // Call turnInMaze to turn the robot (virtually) bool hit = hitWall(robot); // Test hit wall return hit; }
References
https://www.techworm.net/wp-content/uploads/2015/05/Untitled27-e1432324102995.png