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.
Fork of Boboobooov4 by
Revision 22:34a0c436ac45, committed 2014-07-11
- Comitter:
- fhcrcmars
- Date:
- Fri Jul 11 01:25:16 2014 +0000
- Parent:
- 21:4e8a4f66aaef
- Commit message:
- clean some comment
Changed in this revision
diff -r 4e8a4f66aaef -r 34a0c436ac45 camera_api.cpp --- a/camera_api.cpp Thu Jul 10 03:25:59 2014 +0000 +++ b/camera_api.cpp Fri Jul 11 01:25:16 2014 +0000 @@ -26,7 +26,7 @@ bool l_f1=false; bool l_f2=false; bool find=false; - int b_thr_up=32; + int b_thr_up=20; int b_thr_dn=5; int b_w=0; @@ -77,13 +77,13 @@ { int l_care=64; - int r_care=100; + int r_care=115; int b_start=0; int b_end=0; bool l_f1=false; bool l_f2=false; bool find=false; - int b_thr_up=32; + int b_thr_up=20; int b_thr_dn=4; int b_w=0;
diff -r 4e8a4f66aaef -r 34a0c436ac45 main.cpp --- a/main.cpp Thu Jul 10 03:25:59 2014 +0000 +++ b/main.cpp Fri Jul 11 01:25:16 2014 +0000 @@ -198,7 +198,6 @@ for(int i=0;i<n_pointR;i++){ pointsR.pop(&point); pc.printf("%d ",point); - //algorithm if(point>0){ sum_error_R+=point; //because R's black is on the right side of line correct_pointR_number++; @@ -210,7 +209,7 @@ pointsL.pop(&point); pc.printf("%d ",point); if(point>0){ - sum_error_L+=point; //because R's black is on the right side of line + sum_error_L+=point; //because L's black is on the right side of line correct_pointL_number++; } } @@ -218,46 +217,29 @@ int error_R_ave=(correct_pointR_number==0)?0:sum_error_R/correct_pointR_number; int error_L_ave=(correct_pointL_number==0)?0:sum_error_L/correct_pointL_number; - // pc.printf("L: %d R: %d\r\n",error_L_ave,error_R_ave); - //two line if(error_L_ave!=0 && error_R_ave!=0){ - servo.set_angle(cam_to_M_ctrlr.compute((error_L_ave+error_R_ave)/2,center) ); + servo.set_angle(cam_to_M_ctrlr.compute((error_L_ave+error_R_ave)/2,63) ); } //in the correct think, one line should not appear //right line else if(error_L_ave==0 && error_R_ave!=0){ - servo.set_angle(cam_to_M_ctrlr.compute(error_R_ave,30)); + servo.set_angle(cam_to_M_ctrlr.compute(error_R_ave,35)); } //left line else if(error_R_ave==0 && error_L_ave!=0){ - servo.set_angle(cam_to_M_ctrlr.compute(error_L_ave,88)); + servo.set_angle(cam_to_M_ctrlr.compute(error_L_ave,90)); } //no line else if(error_L_ave!=0 && error_R_ave!=0){} - - - // cam_to_M_ctrlr.compute(black_center+sum_error_R/n_pointR,center); - - // servo.set_angle( cam_to_M_ctrlr.compute(black_center+sum_e/n_pointR,center) ); - - // pc.printf("dfdf"); - //if(b_r_c!=-1) - // v_servo=cam_to_M_ctrlr.compute(b_r_c,R_target); - //if(b_l_c!=-1) - // v_servo=cam_to_M_ctrlr.compute(b_l_c,L_target); - - - // v_servo=pot2.read(); #ifdef task_ma_time servo_p=0; #endif - Thread::wait(20);
diff -r 4e8a4f66aaef -r 34a0c436ac45 servo_api.cpp --- a/servo_api.cpp Thu Jul 10 03:25:59 2014 +0000 +++ b/servo_api.cpp Fri Jul 11 01:25:16 2014 +0000 @@ -17,7 +17,7 @@ angle = 0; - servo_in= new PwmOut(PTB0); + servo_in= new PwmOut(PTB1); servo_in->period_ms(20);