Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed FastPWM USBDevice
Fork of USBHID_TestCase by
Diff: main.cpp
- Revision:
- 5:2908292a8cf3
- Parent:
- 4:3ab1e94b3bc4
- Child:
- 6:3d15e8b4d035
--- a/main.cpp Fri Mar 27 15:53:41 2015 +0000 +++ b/main.cpp Wed Aug 12 14:58:59 2015 +0000 @@ -3,7 +3,7 @@ #include "WoodenDevice.h" //We declare a USBHID device. Input out output reports have a length of 8 bytes -USBHID hid(48, 48); +USBHID hid(8, 8); //This report will contain data to be sent HID_REPORT send_report; @@ -99,7 +99,21 @@ actual_current_0(0),actual_current_1(0),actual_current_2(0), temperature_0(0),temperature_1(0),temperature_2(0){} }; - + +struct hid_to_pc_message { // 4*2 = 8 bytes + short encoder_a; + short encoder_b; + short encoder_c; + unsigned short debug; +}; + +struct pc_to_hid_message { // 4*2 = 8 bytes + short current_motor_a_mA; + short current_motor_b_mA; + short current_motor_c_mA; + unsigned int debug; +}; + int main(void) { myled1 = 1; // SETUP @@ -135,8 +149,12 @@ pc.baud(115200); - send_report.length = 48; - woodenhaptics_message msg; + send_report.length = 8; + //woodenhaptics_message msg; + + hid_to_pc_message hid_to_pc; + hid_to_pc.debug = 0; + pc_to_hid_message pc_to_hid; Timer t; t.start(); @@ -162,28 +180,29 @@ myled3 = !myled3; // We got data - if(recv_report.length == 4*12){ // It should always be! + if(recv_report.length == 8){ // It should always be! - msg = *reinterpret_cast<woodenhaptics_message*>(recv_report.data); + pc_to_hid = *reinterpret_cast<pc_to_hid_message*>(recv_report.data); - if(debug_t.read() > 0.5){ - pc.printf("Force: %f\n\r",msg.command_force_x); - debug_t.reset(); - } + //if(debug_t.read() > 0.5){ + // pc.printf("Force: %f\n\r",pc_to_hid.current_motor_a_mA); + // debug_t.reset(); + //} //float f[3] = {msg.command_force_x, msg.command_force_y, msg.command_force_z}; - float f[3] = {msg.command_force_x, msg.command_force_y, msg.command_force_z}; + //float f[3] = {msg.command_force_x, msg.command_force_y, msg.command_force_z}; + float f[3] = {pc_to_hid.current_motor_a_mA*0.001, pc_to_hid.current_motor_b_mA*0.001,pc_to_hid.current_motor_c_mA*0.001}; for(int i=0;i<3;i++){ int dir = f[i] > 0 ? 1 : 0; direction[i].write(dir); // 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.3) + if(f[i] > 3.0) pwm[i].write(0.9); else - pwm[i].write(0.8*f[i]/3.3+0.1); + pwm[i].write(0.8*abs_val/3.0+0.1); } @@ -200,15 +219,23 @@ // "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; + //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; - if(usb_timer.read() > 0.01) { + //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) { usb_timer.reset(); - unsigned char* out_buf = reinterpret_cast<unsigned char*>(&msg); + hid_to_pc.debug++; + unsigned char* out_buf = reinterpret_cast<unsigned char*>(&hid_to_pc); //Fill the report for (int i = 0; i < send_report.length; i++) {