UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Revision:
9:30901bec3a2d
Parent:
8:478f75c6109c
Child:
10:836e701d00a6
--- a/ros_functions.cpp	Thu Mar 15 19:20:23 2018 +0000
+++ b/ros_functions.cpp	Mon Mar 26 21:32:30 2018 +0000
@@ -55,7 +55,7 @@
                 rosMode_Delay.stop();
             } 
         }
-        if(rosInput.mode == 2){ //Chat Mode - Standing
+        if(rosInput.mode == 2){ //Chat Mode
             if(initialize != rosInput.mode){
                 control.pitch = 2122;
                 control.height = LIFTHEIGHTMAX; 
@@ -72,39 +72,12 @@
                 }
             }
         }
-        if(rosInput.mode == 3){ //Chat Mode - Sitting
+        if(rosInput.mode == 3){ //Do Nothing Mode
             if(initialize != rosInput.mode){
-                control.pitch = PITCHZERO;
-                control.height = 1100; // need to find values
-                control.yaw  = YAWZERO;
-                control.roll  = ROLLZERO;
+                control.height = currentPosition;
                 initializeMode();
             }
-            else{
-                rosTranslator(rosInput.height, rosInput.yaw, rosInput.pitch, rosInput.roll);
-                if(rosMode_Delay.read() > rosModeDelay){
-                    rosFlag = 1;
-                    rosMode_Delay.reset();
-                    rosMode_Delay.stop();
-                } 
-            }
         }
-        if(rosInput.mode == 4){ //Chat Mode - in bed
-             if(initialize != rosInput.mode){
-                control.pitch = 2500; // need to find values
-                control.height = 1700; // need to find values
-                control.yaw  = YAWZERO; // need to find values
-                initializeMode();
-            }
-            else{
-                rosTranslator(rosInput.height, rosInput.yaw, rosInput.pitch, rosInput.roll);
-                if(rosMode_Delay.read() > rosModeDelay){
-                    rosFlag = 1;
-                    rosMode_Delay.reset();
-                    rosMode_Delay.stop();
-                } 
-            }
-        }  
 }
 
 // Converting the ros inputs for the lift and gimbal and determining action