int main(void) { Led0 led0;led0.setupDigitalOut(); Led1 led1;led1.setupDigitalOut(); Led2 led2;led2.setupDigitalOut(); Led3 led3;led3.setupDigitalOut(); Buzzer buzzer;buzzer.setupDigitalOut(); Sw0 sw0;sw0.setupDigitalIn(); Sw1 sw1;sw1.setupDigitalIn(); Sw2 sw2;sw2.setupDigitalIn(); Sw3 sw3;sw3.setupDigitalIn(); A0 a0;//a0.setupAnalogIn(); A1 a1;a1.setupAnalogIn(); A2 a2;//a2.setupAnalogIn(); A3 a3;//a3.setupAnalogIn(); A4 a4;a4.setupAnalogIn(); /*Init_ADC1(GPIOC,GPIO_Pin_1); Init_ADC1(GPIOC,GPIO_Pin_2);//2 Init_ADC1(GPIOC,GPIO_Pin_3); Init_ADC1(GPIOC,GPIO_Pin_4);//4 Init_ADC1(GPIOC,GPIO_Pin_5);*/ CW0 cw0;cw0.setupDigitalOut(); CW1 cw1;cw1.setupDigitalOut(); CW2 cw2;cw2.setupDigitalOut(); CW3 cw3;cw3.setupDigitalOut(); CW4 cw4;cw4.setupDigitalOut(); CW5 cw5;cw5.setupDigitalOut(); CCW0 ccw0;ccw0.setupDigitalOut(); CCW1 ccw1;ccw1.setupDigitalOut(); CCW2 ccw2;ccw2.setupDigitalOut(); CCW3 ccw3;ccw3.setupDigitalOut(); CCW4 ccw4;ccw4.setupDigitalOut(); CCW5 ccw5;ccw5.setupDigitalOut(); Pwm0 pwm0;pwm0.setupPwmOut(10000,1); Pwm1 pwm1;pwm1.setupPwmOut(10000,1); Pwm2 pwm2;pwm2.setupPwmOut(10000,1); Pwm3 pwm3;pwm3.setupPwmOut(10000,1); Pwm4 pwm4;pwm4.setupPwmOut(10000,1); Pwm5 pwm5;pwm5.setupPwmOut(10000,1); Enc0 enc0;enc0.setup(); Enc1 enc1;enc1.setup(); Enc2 enc2;enc2.setup(); Serial0 serial0; serial0.setup(115200); //Blink blink(cw0);blink.setup(); //blink.time(500); Blink blink0(led0);blink0.setup();blink0.time(150); Blink blink1(led1);blink1.setup();blink1.time(300); Blink blink2(led2);blink2.setup();blink2.time(450); Blink blink3(led3);blink3.setup();blink3.time(600); //Blink blink4(a4);blink4.setup();blink4.time(2000); float duty=0; int flag=0; int time=0; int led=0; while(1){ blink0.cycle(); blink1.cycle(); blink2.cycle(); blink3.cycle(); //blink4.cycle(); if(millis()-time>=60){ time=millis(); /*if(flag==0){ if(duty>=1){ flag=1; } duty+=0.1; }else{ if(duty<0){ flag=0; } duty-=0.1; } pwm0.pwmWrite(duty); pwm1.pwmWrite(duty); pwm2.pwmWrite(duty); pwm3.pwmWrite(duty); pwm4.pwmWrite(duty); pwm5.pwmWrite(duty);*/ if(!sw0.digitalRead()) Reset_encoder_over_under_flow(); /*serial0.printf("a0:%d, ",a0.analogRead()); serial0.printf("a1:%d, ",a1.analogRead()); serial0.printf("a2:%d, ",a2.analogRead()); serial0.printf("a3:%d, ",a3.analogRead()); serial0.printf("a4:%d\n",a4.analogRead());*/ serial0.printf("a0:%.2f",get_ADC1_value(GPIOC,GPIO_Pin_5)); serial0.printf("a1:%.2f",get_ADC1_value(GPIOC,GPIO_Pin_1)); serial0.printf("a2:%.2f",get_ADC1_value(GPIOC,GPIO_Pin_2)); serial0.printf("a3:%.2f",get_ADC1_value(GPIOC,GPIO_Pin_3)); serial0.printf("a4:%.2f\n",get_ADC1_value(GPIOC,GPIO_Pin_4)); //serial0.printf("s0:%d, s1:%d, s2:%d, s3:%d ",sw0.digitalRead(),sw1.digitalRead(),sw2.digitalRead(),sw3.digitalRead()); //serial0.printf("e0:%d, e1:%d, e2:%d\n\r",enc0.count(),enc1.count(),enc2.count()); } /*if(millis()-led>=150){ led=millis(); cw0.digitalToggle();ccw0.digitalToggle(); cw1.digitalToggle();ccw1.digitalToggle(); cw2.digitalToggle();ccw2.digitalToggle(); cw3.digitalToggle();ccw3.digitalToggle(); cw4.digitalToggle();ccw4.digitalToggle(); cw5.digitalToggle();ccw5.digitalToggle(); }*/ } return 0; }
int main(void) { Can0 can; can.setup(); Buzzer buzzer; Led0 led0; Led1 led1; Led2 led2; Led3 led3; A1 limBack; A3 limFlont; Serial1 serial1; led0.setupDigitalOut(); led1.setupDigitalOut(); led2.setupDigitalOut(); led3.setupDigitalOut(); buzzer.setupDigitalOut(); CanEncoder canEncoder0(can,0,5); CanEncoder canEncoder1(can,1,5); CanEncoder canEncoder2(can,2,5); canEncoder0.setup(); canEncoder1.setup(); canEncoder2.setup(); Motor motor; Connection control; Testmotor t; R1350n r1350n(serial1); r1350n.setup(); int timeLed=0; Position position(canEncoder0,canEncoder1,canEncoder2); buzzer.digitalHigh(); while(1){ if(control.dispose==0){ led0.digitalWrite(1); } else if(control.dispose==1){ led1.digitalWrite(1); } else if(control.dispose==2){ led2.digitalWrite(1); } if(control.member==1){ led3.digitalWrite(1); } else if(control.member==2){ if(millis()-timeLed>=500){ led3.digitalToggle(); timeLed=millis(); } } if(millis()-control.period>=cycle){ control.period=millis(); if(control.sw==0&&millis()-control.time>1000){ control.switch0(); } if(control.sw==1){ position.radian(r1350n.angle()); position.selfPosition(); control.xy(position.integralx,position.integraly); if(control.spinNumber[control.member][control.dispose][control.point]==1){ motor.motorControl(control.devietionX,control.devietionY); motor.degreeLock(position.rad); // motor.testmotor(); motor.last(); motor.dutyCleanUp(); if(control.point<5){ control.coordinatePoint(motor.distance); } } else if(control.spinNumber[control.member][control.dispose][control.point]==0){ motor.angle(position.degree,position.degree); control.spinControl(position.degree); } if(control.actionNumber[control.member][control.dispose][control.point]==1){ if(control.armpwm[control.member][control.dispose][control.point]!=0){ control.armTime(); } control.arm(); motor.armMotor(control.armpwmC,control.armcwC,control.armccwC); } control.indication(position.encf[0],position.encf[1],position.encf[2],position.degree,position.integralx,position.integraly,r1350n.angle()); } if(millis()-control.time>1000){ control.switch0(); } } } return 0; }