]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - avr/motor_ctrl/main.c
use esum to stop motor when stalling to avoid damage
[ros_wild_thumper.git] / avr / motor_ctrl / main.c
index 66a7c4afd63af534cb47608eb82c805bcf7dd2fd..3dca8cc80bb9fa380d3e9f0d3689a31d28929b09 100644 (file)
@@ -687,7 +687,8 @@ static void update_motor(void) {
        static int16_t m3_old=SHRT_MIN;
        static int16_t m4_old=SHRT_MIN;
 
-       error_state = ~((PIND & 0x40)>>3 | (PINB & 0x07)) & 0xf;
+       error_state &= 0xf0; // clear lower bits
+       error_state |= ~((PIND & 0x40)>>3 | (PINB & 0x07)) & 0xf;
 
        if (m1_old != motor1) { // update only when changed
                if (motor1 == 0) {
@@ -790,7 +791,6 @@ static void update_pos(void) {
        int16_t pos4_diff;
        float diff_left_m, diff_right_m, angle_diff, translation;
        float pos_x_new, pos_y_new, angle_new;
-       int16_t speed_l, speed_r;
        float tmp_speed_lin, tmp_speed_rot;
        int16_t cur_pos1, cur_pos2, cur_pos3, cur_pos4;
        int16_t new_speed1, new_speed2, new_speed3, new_speed4;
@@ -825,10 +825,8 @@ static void update_pos(void) {
        pos_x_new = pos_x.f + cos(angle_new)*translation;
        pos_y_new = pos_y.f + sin(angle_new)*translation;
 
-       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_AVG);
-       tmp_speed_rot = (speed_r - speed_l)/(M_PI*WHEEL_DIST*STEP_PER_M_AVG);
+       tmp_speed_lin = translation/PID_T;
+       tmp_speed_rot = angle_diff/PID_T;
 
        // copy from tmp
        cli();
@@ -860,11 +858,39 @@ static void update_pid(void) {
        static int32_t esum3=0;
        static int32_t esum4=0;
 
+       // protect motors from damage if stalling
+       if (labs(esum1) > 120000 && speed1 == 0) {
+               motor1 = 0;
+               motor1_mode = MOTOR_MANUAL;
+               error_state |= (1<<4);
+               esum1 = 0;
+       }       
+       if (labs(esum2) > 120000 && speed2 == 0) {
+               motor2 = 0;
+               motor2_mode = MOTOR_MANUAL;
+               error_state |= (1<<5);
+               esum2 = 0;
+       }       
+       if (labs(esum3) > 120000 && speed3 == 0) {
+               motor3 = 0;
+               motor3_mode = MOTOR_MANUAL;
+               error_state |= (1<<6);
+               esum3 = 0;
+       }       
+       // protect motors from damage if stalling
+       if (labs(esum4) > 120000 && speed4 == 0) {
+               motor4 = 0;
+               motor4_mode = MOTOR_MANUAL;
+               error_state |= (1<<7);
+               esum4 = 0;
+       }       
+
        if (motor1_mode == MOTOR_PID) {
                if (speed1_wish == 0) {
                        motor1 = 0;
                        eold1 = 0;
                        esum1 = 0;
+                       error_state &= ~(1<<4);
                } else {
                        int16_t e = speed1_wish - speed1;
                        esum1+=e;
@@ -882,6 +908,7 @@ static void update_pid(void) {
                        motor2 = 0;
                        eold2 = 0;
                        esum2 = 0;
+                       error_state &= ~(1<<5);
                } else {
                        int16_t e = speed2_wish - speed2;
                        esum2+=e;
@@ -899,6 +926,7 @@ static void update_pid(void) {
                        motor3 = 0;
                        eold3 = 0;
                        esum3 = 0;
+                       error_state &= ~(1<<6);
                } else {
                        int16_t e = speed3_wish - speed3;
                        esum3+=e;
@@ -916,6 +944,7 @@ static void update_pid(void) {
                        motor4 = 0;
                        eold4 = 0;
                        esum4 = 0;
+                       error_state &= ~(1<<7);
                } else {
                        int16_t e = speed4_wish - speed4;
                        esum4+=e;
@@ -1008,7 +1037,7 @@ int main(void) {
                        cmd_vel.bUpdate = 0;
                        sei();
 
-                       speed_wish_right = angle*M_PI*WHEEL_DIST/2 + speed;
+                       speed_wish_right = (angle*WHEEL_DIST)/2 + speed;
                        speed_wish_left = speed*2-speed_wish_right;
 
                        speed_wish_left*=STEP_PER_M_LEFT;
@@ -1016,17 +1045,17 @@ int main(void) {
 
                        if (aft_handicap > 0) {
                                speed1_wish = speed_wish_left * (100-aft_handicap)/100.0;
-                               speed4_wish = speed_wish_right * (100-aft_handicap)/100.0;
+                               speed3_wish = speed_wish_right * (100-aft_handicap)/100.0;
                        } else {
                                speed1_wish = speed_wish_left;
-                               speed4_wish = speed_wish_right;
+                               speed3_wish = speed_wish_right;
                        }
                        if (front_handicap > 0) {
                                speed2_wish = speed_wish_left * (100-front_handicap)/100.0;
-                               speed3_wish = speed_wish_right * (100-front_handicap)/100.0;
+                               speed4_wish = speed_wish_right * (100-front_handicap)/100.0;
                        } else {
                                speed2_wish = speed_wish_left;
-                               speed3_wish = speed_wish_right;
+                               speed4_wish = speed_wish_right;
                        }
                        motor1_mode = MOTOR_PID;
                        motor2_mode = MOTOR_PID;