Jonas Forsslund / Mbed 2 deprecated WoodenHapticsHID

Dependencies:   mbed FastPWM USBDevice

Fork of USBHID_TestCase by Samuel Mokrani

Revision:
7:bb6454b72c57
Parent:
6:3d15e8b4d035
Child:
8:ed6b607462de
--- a/main.cpp	Fri Sep 04 08:03:30 2015 +0000
+++ b/main.cpp	Fri Oct 28 12:34:49 2016 +0000
@@ -1,6 +1,8 @@
 #include "mbed.h"
 #include "USBHID.h"
 #include "WoodenDevice.h"
+#include "FastPWM.h"
+
 
 //We declare a USBHID device. Input out output reports have a length of 8 bytes
 USBHID hid(8, 8);
@@ -37,7 +39,7 @@
 bool encoder_raw[3][2] = {{false,false},{false,false},{false,false}};
 
 PwmOut pwm[3]={p21,p22,p23};
-DigitalOut direction[3]={p24,p25,p26};
+PwmOut direction[3]={p24,p25,p26};
 
 int counter[3] = {0,0,0};
 
@@ -127,7 +129,7 @@
         
     for(int i=0;i<3;i++){
         pwm[i].write(0);  
-        direction[i]=0;
+        direction[i].write(0);
     }        
 }
  
@@ -164,9 +166,10 @@
     configuration config = default_woody();  
     
     for(int i=0;i<3;i++){
-        pwm[i].period_us(1000);
+        pwm[i].period_us(500);
         pwm[i].write(0);  
-        direction[i]=0;
+        direction[i].period_us(500);
+        direction[i].write(0);
         }      
     
     
@@ -235,40 +238,22 @@
 //                    if(i==1)
 //                        pc.printf("Direction: %d (direction %d) \n\r", dir, direction[1].read());
                     float abs_val = std::abs(f[i]);
-                    if(f[i] > 3.0)
+                    if(abs_val > 3.0)
                         pwm[i].write(0.9);
                     else
                         pwm[i].write(0.8*abs_val/3.0+0.1);
                 }
-                
-
-                
-                /*
-                pwm[0].write(0.5);
-                pwm[1].write(0.5);
-                pwm[2].write(0.5);
-                */
             }
                 
             myled1 = 1;
         }
-        
-        
-            
-        // "move the haptic device to the right"        
-        //vec p = getPosition(config, counter);
-        //msg.position_x = p.x;
-        //msg.position_y = p.y;//0.05*sin(t.read());
-        //msg.position_z = p.z;
-        
-        //msg.temperature_0 = counter[0]; // TODO: temperature is used temprarily as a carrier for counter values
-        //msg.temperature_1 = counter[1];
-        //msg.temperature_2 = counter[2]; 
+
         hid_to_pc.encoder_a = counter[0];
         hid_to_pc.encoder_b = counter[1];
         hid_to_pc.encoder_c = counter[2];
         
-        if(usb_timer.read() > 0.001) {
+        if(usb_timer.read() > 0.00001) {
+            pc.printf("%f\n",usb_timer.read());
             usb_timer.reset();
 
             hid_to_pc.debug++;
@@ -282,8 +267,6 @@
             //Send the report
             hid.send(&send_report);      
             myled4 = !myled4;
-        }      
-               
-        //wait_us(100); // 0.1ms
+        }
     }
 }
\ No newline at end of file