Eurobot2012_Primary

Dependencies:   mbed Eurobot_2012_Primary

Files at this revision

API Documentation at this revision

Comitter:
narshu
Date:
Fri Apr 27 16:37:26 2012 +0000
Parent:
6:324946320c6d
Child:
8:ffc7d8af2d5a
Commit message:
Serial problem fixed, working on UI

Changed in this revision

Kalman/IR/IR.cpp Show annotated file Show diff for this revision Revisions of this file
Kalman/Kalman.cpp Show annotated file Show diff for this revision Revisions of this file
front_arms.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
ui/ui.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/Kalman/IR/IR.cpp	Fri Apr 27 14:29:56 2012 +0000
+++ b/Kalman/IR/IR.cpp	Fri Apr 27 16:37:26 2012 +0000
@@ -32,24 +32,17 @@
 
 void IR::vIRValueISR (void) {
 
-
-
-
     // A workaround for mbed UART ISR bug
     // Clear the RBR flag to make sure the interrupt doesn't loop
     // UART3 for the port on pins 9/10, UART2 for pins 28/27, and UART1 for pins 13/14.
     // UART0 for USB UART
+
 #ifdef ROBOT_PRIMARY
     unsigned char RBR = LPC_UART3->RBR;
 #else
     unsigned char RBR = LPC_UART1->RBR;
 #endif
 
-    //printf("%#x/n", RBR);
-
-    OLED3 = !OLED3;
-    return;
-
     // bytes packing/unpacking for IR turret serial comm
     static union IRValue_t {
         float IR_floats[3];
@@ -76,10 +69,7 @@
         if (buff_pointer >= 12) {
             buff_pointer = 0;
             data_flag = false; // dessert the dataflag
-
-
-
-            /*
+        
             if (angleInit) {
                 kalman.runupdate(Kalman::measurement_t(IRValues.IR_ints[0]+3),rectifyAng(IRValues.IR_floats[1] - angleOffset),IRValues.IR_floats[2]);
             } else {
@@ -89,8 +79,6 @@
                 //only update the IRMeasures used by kalman init
                 kalman.IRMeasures[IRValues.IR_ints[0]] = IRValues.IR_floats[1];
             }
-            */
-
 
         }
 
--- a/Kalman/Kalman.cpp	Fri Apr 27 14:29:56 2012 +0000
+++ b/Kalman/Kalman.cpp	Fri Apr 27 16:37:26 2012 +0000
@@ -93,11 +93,13 @@
         IRMeasures[k] = 0;
     }
 
+/*
 #ifdef ROBOT_PRIMARY
     LPC_UART3->FCR = LPC_UART3->FCR | 0x06;       // Flush the serial FIFO buffer / OR with FCR
 #else
     LPC_UART1->FCR = LPC_UART1->FCR | 0x06;       // Flush the serial FIFO buffer / OR with FCR
 #endif
+*/
 
     ir.attachisr();
     //wating untill the IR has reved up and picked up some data
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/front_arms.h	Fri Apr 27 16:37:26 2012 +0000
@@ -0,0 +1,15 @@
+#ifndef _FRONT_ARMS_H
+#define _FRONT_ARMS_H
+
+#include"mbed.h"
+
+#define LEFT_ARM_PIN p21
+#define RIGHT_ARM_PIN p24
+
+Ser
+
+void frontArmsInit() {
+    
+}
+
+#endif // _FRONT_ARMS_H
\ No newline at end of file
--- a/main.cpp	Fri Apr 27 14:29:56 2012 +0000
+++ b/main.cpp	Fri Apr 27 16:37:26 2012 +0000
@@ -41,7 +41,7 @@
     kalman.KalmanInit();
 
     Thread tMotorThread(vMotorThread,NULL,osPriorityNormal,256);
-    Thread tUpdateState(vPrintState,NULL,osPriorityNormal,1024);
+    //Thread tUpdateState(vPrintState,NULL,osPriorityNormal,1024);
     
     //Thread thr_motion(motion_thread,NULL,osPriorityNormal,1024);
     //Motion_Thread_Ptr = &thr_motion;
--- a/ui/ui.cpp	Fri Apr 27 14:29:56 2012 +0000
+++ b/ui/ui.cpp	Fri Apr 27 16:37:26 2012 +0000
@@ -1,6 +1,7 @@
 
 #include "ui.h"
 #include <iostream>
+#include "system.h"
 
 UI::UI() :
         tUI(printtw,this,osPriorityNormal,1024) {
@@ -10,8 +11,6 @@
         buffarr[i] = 0;
     }
 
-    //char* sync = "ABCD";
-    //std::cout.write(sync, 4);
 }
 
 bool UI::regid(char id, unsigned int length) {
@@ -61,8 +60,16 @@
 
 void UI::printloop() {
 
+    OLED4 = !OLED4;
+    Thread::wait(1500);
+
     char* sync = "ABCD";
     std::cout.write(sync, 4);
+    std::cout.flush();
+    //std::cout << std::endl;
+    //printf("\r\n");
+    
+    OLED4 = !OLED4;
 
     while (1) {
 
@@ -75,7 +82,7 @@
             }
         }
 
-        std::cout.flush();
+        //std::cout.flush();
         Thread::wait(200);
     }