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 BX-car by
Revision 10:d2401a243e8d, committed 2014-06-25
- Comitter:
- physicsgood
- Date:
- Wed Jun 25 05:07:13 2014 +0000
- Parent:
- 9:33b99cb45e99
- Child:
- 11:ffd762ae141b
- Commit message:
- for even
Changed in this revision
--- a/camera_api.cpp Tue Jun 24 10:06:54 2014 +0000
+++ b/camera_api.cpp Wed Jun 25 05:07:13 2014 +0000
@@ -1,7 +1,9 @@
#include "mbed.h"
#include "camera_api.h"
+#define clk 2 //ms
-#define clk 2 //ms
+
+
BX_camera::BX_camera(void)
{
@@ -16,160 +18,25 @@
int BX_camera::black_centerR(void)
{
- int l_care=10;
- int r_care=118;
-
-
- // find center
- // case 1 // | //
- // case 2 / | /
-
- char find_type=0x00;
-
- int b_end=0;
- int b_start=0;
-
- int b_w=0;
- int b_center=0;
-
- int b2_end=0;
- int b2_start=0;
- int b2_center=0;
-
- int b2_w=0;
-
- int center=30;
- int j=64;
- bool f1=false;
- bool f2=false;
- bool f3=false;
- bool f4=false;
- int w_thr_up=32;
- int w_thr_dn=0;
-
- if(sign_line_imageR[64]==' ')
- find_type=0x02;
- else
- find_type=0x01;
-
-
- for(int i=64; i<r_care; i++,j--) {
-
-
- switch(find_type) {
-
-
- case 0x01:
-
- if(f1==false&&sign_line_imageR[i]==' ') {
- if(f1==false) {
- b_start=i;
- f1=true;
- }
-
- }
- if(f1== true&& f2==false&&sign_line_imageR[i]=='O') {
- if(f2==false) {
- b_end=i-1;
- f2=true;
- }
-
- }
-
- if(f3==false&&sign_line_imageR[j]==' ') {
- if(f3==false) {
- b2_end=j;
- f3=true;
- }
-
- }
- if(f3==true&&f4==false&&sign_line_imageR[j]=='O') {
- if(f4==false) {
- b2_start=j-1;
- f4=true;
- }
-
- }
+ int black_left , black_right;
+
+ for(int i = 10; i < 115; i++){
+ if(sign_line_imageR[i] == 'O' && sign_line_imageR[i+1] == ' ' && sign_line_imageR[i+2] == ' '){
+ black_left = i;
+ break;
+ }
+ }
+
+ for(int i = 115; i > 10; i--){
+ if(sign_line_imageR[i] == ' ' && sign_line_imageR[i+1] == ' ' && sign_line_imageR[i+2] == ' '){
+ black_right = i+2;
+ break;
+ }
+ }
+
+ return (black_left + black_right) / 2;
- break;
-
-
- case 0x02:
-
- if(sign_line_imageR[i]=='O') {
-
- if(f1==false) {
- b_end=i;
- f1=true;
- }
- }
-
- if(sign_line_imageR[j]=='O') {
-
- if(f2==false) {
- b_start=j;
- f2=true;
- }
-
- }
-
-
- break;
-
- }
-
-
- }
-
- b_w=b_start-b_end;
- b2_w=b2_start-b2_end;
-
- de_v=b2_start;
- de_v2=b2_end;
-
- switch(find_type) {
-
- case 0x01:
- b_center=(b_end+b_start)/2;
- b2_center=(b2_end+b2_start)/2;
-
-
- if(w_thr_up>b_w&&(b_center!=0)&&(b_center-64)<(64-b2_center))
- center=b_center;
- else
- center=b2_center;
-
-
-
-
-
-/* if( ( w_thr_up- (b_w))>0 &&( ( w_thr_up- (b_w)) < (w_thr_up-(b2_w)) ) ) {
- center=(b_end+b_start)/2;
-
-
-
- // } else if( ( w_thr_up- (b2_w) )>0 ) {
- center=(b2_end+b2_start)/2;
-// } else {
-
- center=65;
-
- //????????????????
-
- }
-
-*/
- break;
-
- case 0x02:
- center=(b_end+b_start)/2;
-
-
- break;
- }
-
- return center;
}
@@ -323,7 +190,7 @@
//input 128 //both
- for(int i=0; i<128; i++) {
+ for(int i=127; i>=0; i--) {
*cam_clk=1;
wait_us(5);
@@ -359,7 +226,7 @@
//filter L R //may change
- for(int i=0; i<128; i++) {
+ for(int i=127; i>=0; i--) {
if( (line_imageR[i]-b_f_vR) < (w_f_vR - line_imageR[i] ) )
--- a/controller.cpp Tue Jun 24 10:06:54 2014 +0000
+++ b/controller.cpp Wed Jun 25 05:07:13 2014 +0000
@@ -186,7 +186,7 @@
}
float PID::compute(float pv, float sp) {
-
+ //pv centerR centerL
//enregistrer variables dans var interne
processVariable_ = pv; //ce que l'on mesure
setPoint_ = sp; // ce que l'on veut atteindre
--- a/main.cpp Tue Jun 24 10:06:54 2014 +0000
+++ b/main.cpp Wed Jun 25 05:07:13 2014 +0000
@@ -27,6 +27,10 @@
// 90/30=3
PID cam_to_M_ctrlr(10.0,118.0,0.06,0.11,(0.104/30),0.0,0.0,10);
+//PID(float in_min,float in_max,float out_min,float out_max,float Kc, float tauI, float tauD, float interval)
+//in_min in_out camera array
+//out_min out_max servo range
+//
DigitalOut task_pin(PTD1);
TSISensor tsi;
@@ -34,7 +38,6 @@
pc.baud(115200);
-
while(1){
if(tsi.readPercentage()>0.00011)
@@ -139,11 +142,21 @@
b_r_c=(double)cam.black_centerR();
- PID_v=cam_to_M_ctrlr.compute(b_r_c,15.0);
- pc.printf("%f %d %d speed :%f bk_center %f PID:%f \r\n",cam_to_M_ctrlr.de_v,cam.de_v,cam.de_v2,motor,b_r_c,PID_v);
+ //PID_v=cam_to_M_ctrlr.compute(b_r_c,15.0);
+ //pc.printf("%f %d %d speed :%f bk_center %f PID:%f \r\n",cam_to_M_ctrlr.de_v,cam.de_v,cam.de_v2,motor,b_r_c,PID_v);
+ pc.printf("b_r_c %lf\r\n",b_r_c);
+ int error = b_r_c-64;
+ if(error<8&&error>-8){
+ servo.set_angle(0.085);
+ }
+ else if(error<-8){
+ servo.set_angle(0.1);
+ }
+ else if(error>8){
+ servo.set_angle(0.07);
+ }
-
- servo.set_angle(PID_v);
+ //servo.set_angle(PID_v);
