mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
removed debug code
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1775 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
41c9b1edd7
commit
c1f785df66
@ -13,14 +13,12 @@ void arm_motors()
|
|||||||
if (arming_counter > ARM_DELAY) {
|
if (arming_counter > ARM_DELAY) {
|
||||||
motor_armed = true;
|
motor_armed = true;
|
||||||
} else{
|
} else{
|
||||||
//Serial.printf("arm %d\n", arming_counter);
|
|
||||||
arming_counter++;
|
arming_counter++;
|
||||||
}
|
}
|
||||||
}else if (g.rc_4.control_in < -2700) {
|
}else if (g.rc_4.control_in < -2700) {
|
||||||
if (arming_counter > DISARM_DELAY){
|
if (arming_counter > DISARM_DELAY){
|
||||||
motor_armed = false;
|
motor_armed = false;
|
||||||
}else{
|
}else{
|
||||||
//Serial.printf("arm %d\n", arming_counter);
|
|
||||||
arming_counter++;
|
arming_counter++;
|
||||||
}
|
}
|
||||||
}else{
|
}else{
|
||||||
@ -69,10 +67,10 @@ set_servos_4()
|
|||||||
motor_out[CH_3] = g.rc_3.radio_out + g.rc_2.pwm_out;
|
motor_out[CH_3] = g.rc_3.radio_out + g.rc_2.pwm_out;
|
||||||
motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
|
motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
|
||||||
|
|
||||||
motor_out[CH_1] += g.rc_4.pwm_out; // CCW
|
motor_out[CH_1] += g.rc_4.pwm_out; // CCW
|
||||||
motor_out[CH_2] += g.rc_4.pwm_out; // CCW
|
motor_out[CH_2] += g.rc_4.pwm_out; // CCW
|
||||||
motor_out[CH_3] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_3] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_4] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_4] -= g.rc_4.pwm_out; // CW
|
||||||
|
|
||||||
}else if(g.frame_type == X_FRAME){
|
}else if(g.frame_type == X_FRAME){
|
||||||
//Serial.println("X_FRAME");
|
//Serial.println("X_FRAME");
|
||||||
@ -125,11 +123,11 @@ set_servos_4()
|
|||||||
//left side
|
//left side
|
||||||
motor_out[CH_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW
|
motor_out[CH_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW
|
||||||
motor_out[CH_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
motor_out[CH_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
||||||
motor_out[CH_8] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
motor_out[CH_8] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
||||||
|
|
||||||
//right side
|
//right side
|
||||||
motor_out[CH_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW
|
motor_out[CH_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW
|
||||||
motor_out[CH_7] = g.rc_3.radio_out - roll_out + pitch_out; // CCW
|
motor_out[CH_7] = g.rc_3.radio_out - roll_out + pitch_out; // CCW
|
||||||
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW
|
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW
|
||||||
|
|
||||||
motor_out[CH_7] += g.rc_4.pwm_out; // CCW
|
motor_out[CH_7] += g.rc_4.pwm_out; // CCW
|
||||||
@ -138,9 +136,9 @@ set_servos_4()
|
|||||||
|
|
||||||
motor_out[CH_3] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_3] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
|
|
||||||
Serial.print("frame error");
|
Serial.print("frame error");
|
||||||
|
|
||||||
@ -159,7 +157,6 @@ set_servos_4()
|
|||||||
}
|
}
|
||||||
|
|
||||||
num++;
|
num++;
|
||||||
|
|
||||||
if (num > 50){
|
if (num > 50){
|
||||||
num = 0;
|
num = 0;
|
||||||
/*
|
/*
|
||||||
@ -197,7 +194,7 @@ set_servos_4()
|
|||||||
init_pids();
|
init_pids();
|
||||||
//*/
|
//*/
|
||||||
|
|
||||||
///*
|
/*
|
||||||
write_int(motor_out[CH_1]);
|
write_int(motor_out[CH_1]);
|
||||||
write_int(motor_out[CH_2]);
|
write_int(motor_out[CH_2]);
|
||||||
write_int(motor_out[CH_3]);
|
write_int(motor_out[CH_3]);
|
||||||
@ -215,13 +212,14 @@ set_servos_4()
|
|||||||
write_int((int)nav_roll);
|
write_int((int)nav_roll);
|
||||||
write_int((int)nav_pitch);
|
write_int((int)nav_pitch);
|
||||||
|
|
||||||
write_long(current_loc.lat); // 28
|
//24
|
||||||
write_long(current_loc.lng); // 32
|
write_long(current_loc.lat); //28
|
||||||
write_int((int)current_loc.alt); // 34
|
write_long(current_loc.lng); //32
|
||||||
|
write_int((int)current_loc.alt); //34
|
||||||
|
|
||||||
write_long(next_WP.lat);
|
write_long(next_WP.lat);
|
||||||
write_long(next_WP.lng);
|
write_long(next_WP.lng);
|
||||||
write_int((int)next_WP.alt); // 44
|
write_int((int)next_WP.alt); //44
|
||||||
|
|
||||||
flush(10);
|
flush(10);
|
||||||
//*/
|
//*/
|
||||||
|
Loading…
Reference in New Issue
Block a user