IR
Dependencies: mbed QEI ros_lib_kinetic
Revision 1:5c48d64f17cb, committed 2019-05-23
- Comitter:
- Tarzoozoo
- Date:
- Thu May 23 16:47:10 2019 +0000
- Parent:
- 0:18fcf04b703b
- Commit message:
- with IR;
Changed in this revision
main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Mon Apr 29 05:12:42 2019 +0000 +++ b/main.cpp Thu May 23 16:47:10 2019 +0000 @@ -36,6 +36,8 @@ DigitalOut R_NA(PA_7); //old 0 DigitalOut R_NB(PB_6); //old 1 +DigitalIn IR(PA_8); //D7 +DigitalOut led(LED1); // float R = 0.09; // m unit int get_pluse_L , get_pluse_R = 0; @@ -43,7 +45,7 @@ float Omega_e_R, Omega_w_R, V_real_R; float test_time_2; float test_time; -float V_array[2]; +float V_array[3]; float raw_test[2]; //old duble float V_raw, Omega_raw; //old duble float V_cal_L, V_cal_R; @@ -88,6 +90,16 @@ V_array[0] = V_real_L; V_array[1] = V_real_R; + V_array[2] = 0; + + if (IR == 1){ + V_array[2] = 1; + led = 0; + } + else if (IR == 0){ + V_array[2] = 0; + led = 1; + } //V_array[0] = get_pluse_L; //V_array[1] = get_pluse_R; Array_msg.data = V_array; @@ -171,7 +183,7 @@ mypwm_R.period(0.0005); // mypwm_L = 0; // mypwm_R = 0; - + led = 1; while (1) { nh.spinOnce(); wait_ms(1);