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
Fork of Robotics_LAB_motor_Done by
Revision 3:36002bcd4d1b, committed 2017-06-08
- Comitter:
- YutingHsiao
- Date:
- Thu Jun 08 13:42:55 2017 +0000
- Parent:
- 2:c95a3cba51e6
- Commit message:
- test servo motor
Changed in this revision
| main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Thu Mar 23 06:36:33 2017 +0000
+++ b/main.cpp Thu Jun 08 13:42:55 2017 +0000
@@ -6,7 +6,7 @@
Serial pc(USBTX, USBRX);
-DigitalOut led1(PC_1);
+//DigitalOut led1(PC_1);
Ticker timer1;
// servo motor
@@ -51,27 +51,27 @@
// DC motor rotation speed control
int speed_count_1 = 0;
float rotation_speed_1 = 0.0;
-float rotation_speed_ref_1 = 150.0;//150rpm
+float rotation_speed_ref_1 = 150.0;//150rpm left
float pwm1_duty = 0.5;
float PI_out_1 = 0.0;
float err_1 = 0.0;
float ierr_1 = 0.0;
int speed_count_2 = 0;
float rotation_speed_2 = 0.0;
-float rotation_speed_ref_2 = -80.0;//-80rpm
+float rotation_speed_ref_2 = -80.0;//-80rpm right
float pwm2_duty = 0.5;
float PI_out_2 = 0.0;
float err_2 = 0.0;
float ierr_2 = 0.0;
//set parameters
-float kp = 0.015;
-float ki = 0.11;
+float kp = 0.002;
+float ki = 0.05;
int main()
{
//pc.printf("hello main()\n");
- led1 = 0;
+ //led1 = 0;
init_TIMER();
init_PWM();
init_CN();
@@ -81,8 +81,8 @@
//pc.printf("state_2 = %d \n", state_2);
//pc.printf("speed_count_1 = %d \n", speed_count_1);
//pc.printf("speed_count_2 = %d \n", speed_count_2);
- //pc.printf("rotation_speed_2 = %f \n", rotation_speed_2);
- //pc.printf("rotation_speed_1 = %f \n", rotation_speed_1);
+ //pc.printf("rotation_speed_2 = %f \n\r", rotation_speed_2);
+ //pc.printf("rotation_speed_1 = %f \n\r", rotation_speed_1);
//pc.printf("error_1 = %f \n\r", err_1);
//pc.printf("ierror_1 = %f \n\r", ierr_1);
//pc.printf("rotation_speed_2 = %f \n", rotation_speed_2);
@@ -160,12 +160,12 @@
if((direction_1 == -1) || (direction_1 == 3))
{
//forward
- speed_count_1 = speed_count_1 + 1;
+ speed_count_1 = speed_count_1 - 1;
}
else if((direction_1 == 1) || (direction_1 == -3))
{
//backward
- speed_count_1 = speed_count_1 - 1;
+ speed_count_1 = speed_count_1 + 1;
}
else
{
@@ -211,12 +211,12 @@
if((direction_2 == 1) || (direction_2 == -3))
{
//forward
- speed_count_2 = speed_count_2 + 1;
+ speed_count_2 = speed_count_2 - 1;
}
else if((direction_2 == -1) || (direction_2 == 3))
{
//backward
- speed_count_2 = speed_count_2 - 1;
+ speed_count_2 = speed_count_2 + 1;
}
else
{
@@ -243,7 +243,7 @@
angle = 15;
//servo_duty output for every call
- servo_duty = servo_duty + 0.088/180*angle/100;
+ servo_duty = servo_duty - 0.088/180*angle/100;
/////////////////////////
/////////////////////////
@@ -270,7 +270,7 @@
if(PI_out_1 >= 0.5f)PI_out_1 = 0.5;
else if(PI_out_1 <= -0.5f)PI_out_1 = -0.5;
- pwm1_duty = - PI_out_1 + 0.5f;
+ pwm1_duty = PI_out_1 + 0.5f;
//pc.printf("pwm1_duty = %d \n\r", pwm1_duty);
pwm1.write(pwm1_duty);
TIM1->CCER |= 0x4;
@@ -293,7 +293,7 @@
if(PI_out_2 >= 0.5f)PI_out_2 = 0.5;
else if(PI_out_2 <= -0.5f)PI_out_2 = -0.5;
- pwm2_duty = PI_out_2 + 0.5f;
+ pwm2_duty = -PI_out_2 + 0.5f;
//pc.printf("pwm2_duty = %d \n\r", pwm2_duty);
pwm2.write(pwm2_duty);
TIM1->CCER |= 0x40;
