for ros integration

Dependencies:   wheelchaircontrolRos

Fork of wheelchaircontrolrealtime by ryan lin

Revision:
9:90bc440405b6
Parent:
8:347b10e6bdf8
Child:
11:2cb176f5b345
--- a/main.cpp	Mon Aug 27 23:12:06 2018 +0000
+++ b/main.cpp	Wed Aug 29 21:02:03 2018 +0000
@@ -3,11 +3,11 @@
 AnalogIn x(A0);
 AnalogIn y(A1);
 
+/*
 DigitalOut on(D12);
 DigitalOut off(D11);
 DigitalOut up(D2);
-DigitalOut down(D3);
-DigitalOut horn(D10);
+DigitalOut down(D3);*/
 
 Serial pc(USBTX, USBRX, 57600);
 Timer t;
@@ -21,10 +21,9 @@
 ros::NodeHandle nh;
 //geometry_msgs::Twist commandRead;
 std_msgs::String commandRead;
-std_msgs::String out;
 
 ros::Publisher chatter("chatter", &commandRead);
-bool received = false;
+volatile bool received = false;
 
 void handlerFunction(const std_msgs::String& commandIn)
 {
@@ -99,15 +98,20 @@
 
             } else if(c == 'o') {
                 pc.printf("turning on\n");
-                on = 1;
+                char* temp = "turning on";
+                commandRead.data = temp;
+                chatter.publish(&commandRead);
+                /*on = 1;
                 wait(1);
-                on = 0;
+                on = 0;*/
+                smart.turn_on();
                 c = 'z';
             } else if(c == 'f') {
                 pc.printf("turning off\n");
-                off = 1;
+                /*off = 1;
                 wait(1);
-                off = 0;
+                off = 0;*/
+                smart.turn_off();
                 c = 'z';
             }
 
@@ -115,14 +119,17 @@
                 pc.printf("turning on joystick\n");
                 manual = true;
                 t.reset();
+                received = false;
+                
                 while(manual) {
                     smart.move(x,y);
-                    if( pc.readable()) {
-                        char d = pc.getc();
-                        if( d == 'm') {
+                    if(received) {
+                        char d = commandRead.data[0];
+                        if( d == 'u') {
                             pc.printf("turning off joystick\n");
                             manual = false;
                         }
+                    received = false;
                     }
                 }
             }
@@ -144,11 +151,6 @@
 
 }
 
-void beep() {
-    horn = 1;
-    wait(1);
-    horn =0;
-    }