#define TWI_RESET TWCR &= ~((1 << TWSTO) | (1 << TWEN)); TWI_ACK
#define TWI_NAK TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE)
-#define KP 0.039
-#define KI 0.08
+#define KP 0.06
+#define KI 0.10
#define KD 0.0
#define PID_T 0.01
-// wheel diameter=12cm, encoder=48cpr, gear ratio=1:34, real wheel diameter: 0.12454m
-#define STEP_PER_M_AVG 4171.4
+// wheel diameter=12cm, encoder=48cpr, gear ratio=1:47, real wheel diameter: 0.12454m
+#define STEP_PER_M_AVG 5766.1
#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
static volatile int16_t speed2_wish=0;
static volatile int16_t speed3_wish=0;
static volatile int16_t speed4_wish=0;
+static volatile int16_t speed1_wish_old=0;
+static volatile int16_t speed2_wish_old=0;
+static volatile int16_t speed3_wish_old=0;
+static volatile int16_t speed4_wish_old=0;
static volatile uint8_t run_update=0;
static volatile int16_t speed1=0; // step/s
static volatile int16_t speed2=0;
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) {
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;
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();
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 != speed1_wish_old) {
+ esum1 = 0;
+ speed1_wish_old = speed1_wish;
+ }
+
if (speed1_wish == 0) {
motor1 = 0;
eold1 = 0;
- esum1 = 0;
+ error_state &= ~(1<<4);
} else {
int16_t e = speed1_wish - speed1;
esum1+=e;
}
}
if (motor2_mode == MOTOR_PID) {
+ if (speed2_wish != speed2_wish_old) {
+ esum2 = 0;
+ speed2_wish_old = speed2_wish;
+ }
+
if (speed2_wish == 0) {
motor2 = 0;
eold2 = 0;
- esum2 = 0;
+ error_state &= ~(1<<5);
} else {
int16_t e = speed2_wish - speed2;
esum2+=e;
}
}
if (motor3_mode == MOTOR_PID) {
+ if (speed3_wish != speed3_wish_old) {
+ esum3 = 0;
+ speed3_wish_old = speed3_wish;
+ }
+
if (speed3_wish == 0) {
motor3 = 0;
eold3 = 0;
- esum3 = 0;
+ error_state &= ~(1<<6);
} else {
int16_t e = speed3_wish - speed3;
esum3+=e;
}
}
if (motor4_mode == MOTOR_PID) {
+ if (speed4_wish != speed4_wish_old) {
+ esum4 = 0;
+ speed4_wish_old = speed4_wish;
+ }
+
if (speed4_wish == 0) {
motor4 = 0;
eold4 = 0;
- esum4 = 0;
+ error_state &= ~(1<<7);
} else {
int16_t e = speed4_wish - speed4;
esum4+=e;
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;
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;