Roomba Tank
CSC 460 Project 3
roomba.c
Go to the documentation of this file.
1 #define F_CPU 16000000
2 
3 #include "roomba.h"
4 
5 #include <avr/io.h>
6 #include <avr/interrupt.h>
7 #include <util/delay.h>
8 #include "../uart/uart.h"
9 
13 void Roomba_Init(){
14 
15  // Wake Roomba from sleep
16  // Pin 25
17  DDRA |= (1<<PA3);
18  PORTA |= (1<<PA3);
19 
20  PORTA &= ~(1<<PA3);
21 
22  PORTA |= (1<<PA3);
23 
24  // start the OI
26 
27  _delay_ms(2100);
28 
29  PORTA |= (1<<PA3);
30  PORTA &= ~(1<<PA3);
31  _delay_ms(100);
32 
33  PORTA |= (1<<PA3);
34  PORTA &= ~(1<<PA3);
35  _delay_ms(100);
36 
37  PORTA |= (1<<PA3);
38  PORTA &= ~(1<<PA3);
39  _delay_ms(100);
40 
41  // set Roomba to safe mode
43 
44  Roomba_Song(0); // Initialize song 0
45 }
46 
50 void Roomba_Drive(int16_t velocity, int16_t radius) {
52  Roomba_Send_Byte(velocity>>8);
53  Roomba_Send_Byte(velocity);
54  Roomba_Send_Byte(radius>>8);
55  Roomba_Send_Byte(radius);
56 }
57 
61 void Roomba_Play(uint8_t song) {
63  Roomba_Send_Byte(song);
64 }
65 
69 void Roomba_Sensors(uint8_t packet_id) {
71  Roomba_Send_Byte(packet_id);
72 }
73 
77 void Roomba_QueryList(uint8_t packet1, uint8_t packet2) {
80  Roomba_Send_Byte(packet1);
81  Roomba_Send_Byte(packet2);
82 }
83 
87 void Roomba_Song(uint8_t n) {
89  Roomba_Send_Byte(n); // Song 0
90  Roomba_Send_Byte(6); // 6 Notes
91 
92  Roomba_Send_Byte(72); // C
93  Roomba_Send_Byte(16);
94  Roomba_Send_Byte(69); // A
95  Roomba_Send_Byte(16);
96  Roomba_Send_Byte(67); // G
97  Roomba_Send_Byte(16);
98  Roomba_Send_Byte(64); // E
99  Roomba_Send_Byte(16);
100  Roomba_Send_Byte(62); // D
101  Roomba_Send_Byte(16);
102  Roomba_Send_Byte(60); // C
103  Roomba_Send_Byte(16);
104 }
#define QUERYLIST
Definition: roomba.h:23
#define SAFE_MODE
Definition: roomba.h:16
#define PLAY
Definition: roomba.h:21
void Roomba_Sensors(uint8_t packet_id)
Definition: roomba.c:69
void Roomba_Init()
Definition: roomba.c:13
#define DRIVE
Definition: roomba.h:19
void Roomba_Song(uint8_t n)
Definition: roomba.c:87
#define SONG
Definition: roomba.h:20
#define START
Definition: roomba.h:14
void Roomba_Play(uint8_t song)
Definition: roomba.c:61
#define SENSORS
Definition: roomba.h:22
void Roomba_Drive(int16_t velocity, int16_t radius)
Definition: roomba.c:50
void Roomba_Send_Byte(uint8_t data_out)
Definition: uart.c:27
void Roomba_QueryList(uint8_t packet1, uint8_t packet2)
Definition: roomba.c:77