UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Revision:
2:0537a8007a39
Parent:
1:1ac7d472cfa2
Child:
3:527f0b949839
--- a/initializations.cpp	Tue Feb 06 20:50:55 2018 +0000
+++ b/initializations.cpp	Thu Feb 08 22:23:40 2018 +0000
@@ -8,6 +8,8 @@
 
 #define BNO055_ID        (0xA0)
 
+//Serial pc(USBTX, USBRX);
+
 // Initializations
 
 void setupGimbal(){
@@ -19,14 +21,11 @@
     wait(0.1);
     gimbal.servo(ROLLID, ROLLZERO, 50);
     control.roll = ROLLZERO;
-    dynaInt.attach(&motorInterrupt, 0.0001); // Update Dynamixel at 1kHz.
-    rosInt.attach(&rosInterrupt, 0.1);
 }
 
 void setupLift(){
     
     hallInt.attach(&hallInterrupt, 0.05);
-    liftInt.attach(&liftInterrupt, 0.1);
     liftSpeed.period_us(50);
     
     // Find the bottom position. Go down at lowest speed and set zero point.
@@ -34,12 +33,13 @@
     liftSpeed.write(0.3);   
     
     // Wait until the motor stalls, know the motor is at bottom.
-    while(!stall){}
+    while(!stall){wait(.01);}
     if(stall == true){
        liftSpeed.write(0);
        currentPosition = 0;
        stall = false; 
     } 
+    
 }
 
 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){