X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=avr%2Fmotor_ctrl%2Fmain.c;h=479770a49e404a392faec9696ee555fdb76139e3;hp=bd9fc9e31d634c73f3e622b3508db4d850e4ae3d;hb=f0107d7c53dc0e5d8c0c46311ce92f9fb17027e3;hpb=bd5ce223f2fe077a697352c44a366a33d1f692f0 diff --git a/avr/motor_ctrl/main.c b/avr/motor_ctrl/main.c index bd9fc9e..479770a 100644 --- a/avr/motor_ctrl/main.c +++ b/avr/motor_ctrl/main.c @@ -60,7 +60,6 @@ * 0x3D Angle (rad/s) * 0x3E Angle (rad/s) * 0x3F Angle (rad/s) LSB - * free * 0x40 Position x (m) MSB * 0x41 Position x (m) * 0x42 Position x (m) @@ -87,8 +86,8 @@ * 0x91 Motor 2 switch * 0x92 Motor 3 switch * 0x93 Motor 4 switch - * 0x94 Front Handicap backward - * 0x95 Aft Handicap forward + * 0x94 Front Handicap + * 0x95 Aft Handicap * free * 0xA0 Reset reason * 0xA1 TLE Error status @@ -106,8 +105,11 @@ #define KI 0.051429 #define KD 0.000378 #define PID_T 0.01 -#define STEP_PER_M 3376.1 // wheel diameter=12cm, encoder=48cpr, gear ratio=1:34 -#define WHEEL_DIST 0.252 +// wheel diameter=12cm, encoder=48cpr, gear ratio=1:34, real wheel diameter: 0.12454m +#define STEP_PER_M_AVG 4171.4 +#define STEP_PER_M_LEFT (STEP_PER_M_AVG) +#define STEP_PER_M_RIGHT (STEP_PER_M_AVG) +#define WHEEL_DIST 0.36923 // Real: 0.252 enum mode { MOTOR_MANUAL, @@ -158,8 +160,8 @@ static volatile ufloat_t angle={0.0}; static volatile float cur_speed_lin=0; static volatile float cur_speed_rot=0; static volatile uint8_t count_test=0; -static volatile uint8_t front_handicap_bwd=0; -static volatile uint8_t aft_handicap_fwd=0; +static volatile uint8_t front_handicap=0; +static volatile uint8_t aft_handicap=0; ISR(TWI_vect) { @@ -267,8 +269,8 @@ ISR(TWI_vect) break; case 0x2B: // Left speed wish LSB tmp_speed.i = tmp_speed.i << 8 | TWDR; - speed1_wish = tmp_speed.f*STEP_PER_M; - speed2_wish = tmp_speed.f*STEP_PER_M; + speed1_wish = tmp_speed.f*STEP_PER_M_LEFT; + speed2_wish = tmp_speed.f*STEP_PER_M_LEFT; motor1_mode = MOTOR_PID; motor2_mode = MOTOR_PID; TWI_ACK; @@ -287,8 +289,8 @@ ISR(TWI_vect) break; case 0x2F: // Right speed wish LSB tmp_speed.i = tmp_speed.i << 8 | TWDR; - speed1_wish = tmp_speed.f*STEP_PER_M; - speed2_wish = tmp_speed.f*STEP_PER_M; + speed1_wish = tmp_speed.f*STEP_PER_M_RIGHT; + speed2_wish = tmp_speed.f*STEP_PER_M_RIGHT; motor1_mode = MOTOR_PID; motor2_mode = MOTOR_PID; TWI_ACK; @@ -344,13 +346,13 @@ ISR(TWI_vect) motor4_switch = TWDR; TWI_ACK; break; - case 0x94: // Front Handicap backward - front_handicap_bwd = TWDR; + case 0x94: // Front Handicap + front_handicap = TWDR; cmd_vel.bUpdate = 1; TWI_ACK; break; - case 0x95: // Aft Handicap forward - aft_handicap_fwd = TWDR; + case 0x95: // Aft Handicap + aft_handicap = TWDR; cmd_vel.bUpdate = 1; TWI_ACK; break; @@ -772,13 +774,13 @@ static void update_pos(void) { new_speed3 = pos3_diff/PID_T; new_speed4 = pos4_diff/PID_T; - diff_left_m = (pos1_diff + pos2_diff)/(2*STEP_PER_M); - diff_right_m = (pos3_diff + pos4_diff)/(2*STEP_PER_M); + diff_left_m = (pos1_diff + pos2_diff)/(2*STEP_PER_M_LEFT); + diff_right_m = (pos3_diff + pos4_diff)/(2*STEP_PER_M_RIGHT); angle_diff = (diff_right_m - diff_left_m) / WHEEL_DIST; angle_new = angle.f + angle_diff; if (angle_new > 2*M_PI) angle_new-=2*M_PI; - else if (angle_new < 2*M_PI) angle_new+=2*M_PI; + else if (angle_new < -2*M_PI) angle_new+=2*M_PI; translation = (diff_left_m + diff_right_m)/2.0; pos_x_new = pos_x.f + cos(angle_new)*translation; @@ -786,8 +788,8 @@ static void update_pos(void) { speed_l = (new_speed1+new_speed2)/2; speed_r = (new_speed3+new_speed4)/2; - tmp_speed_lin = (speed_l + speed_r)/(2.0*STEP_PER_M); - tmp_speed_rot = (speed_r - speed_l)/(M_PI*WHEEL_DIST*STEP_PER_M); + tmp_speed_lin = (speed_l + speed_r)/(2.0*STEP_PER_M_AVG); + tmp_speed_rot = (speed_r - speed_l)/(M_PI*WHEEL_DIST*STEP_PER_M_AVG); // copy from tmp cli(); @@ -962,29 +964,23 @@ int main(void) { speed_wish_right = angle*M_PI*WHEEL_DIST/2 + speed; speed_wish_left = speed*2-speed_wish_right; - speed_wish_left*=STEP_PER_M; - speed_wish_right*=STEP_PER_M; + speed_wish_left*=STEP_PER_M_LEFT; + speed_wish_right*=STEP_PER_M_RIGHT; - if (speed_wish_left > 0 && aft_handicap_fwd > 0) { - speed1_wish = speed_wish_left * (100-aft_handicap_fwd)/100.0; + if (aft_handicap > 0) { + speed1_wish = speed_wish_left * (100-aft_handicap)/100.0; + speed4_wish = speed_wish_right * (100-aft_handicap)/100.0; } else { speed1_wish = speed_wish_left; + speed4_wish = speed_wish_right; } - if (speed_wish_left < 0 && front_handicap_bwd > 0) { - speed2_wish = speed_wish_left * (100-front_handicap_bwd)/100.0; + if (front_handicap > 0) { + speed2_wish = speed_wish_left * (100-front_handicap)/100.0; + speed3_wish = speed_wish_right * (100-front_handicap)/100.0; } else { speed2_wish = speed_wish_left; - } - if (speed_wish_right < 0 && front_handicap_bwd > 0) { - speed3_wish = speed_wish_right * (100-front_handicap_bwd)/100.0; - } else { speed3_wish = speed_wish_right; } - if (speed_wish_right > 0 && aft_handicap_fwd > 0) { - speed4_wish = speed_wish_right * (100-aft_handicap_fwd)/100.0; - } else { - speed4_wish = speed_wish_right; - } motor1_mode = MOTOR_PID; motor2_mode = MOTOR_PID; motor3_mode = MOTOR_PID;