2.0.23, Hexa Fix, Baro and Sonar tests now separated.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2464 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-03 18:49:13 +00:00
parent 84ef135856
commit a83bc90759
3 changed files with 14 additions and 23 deletions

View File

@ -19,8 +19,8 @@ void output_motors_armed()
g.rc_4.calc_pwm(); g.rc_4.calc_pwm();
if(g.frame_orientation == X_FRAME){ if(g.frame_orientation == X_FRAME){
roll_out = (float)g.rc_1.pwm_out * .866; roll_out = g.rc_1.pwm_out / 2;
pitch_out = g.rc_2.pwm_out / 2; pitch_out = (float)g.rc_2.pwm_out * .866;
//left side //left side
motor_out[CH_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle motor_out[CH_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle
@ -33,7 +33,7 @@ void output_motors_armed()
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW Back motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW Back
}else{ }else{
roll_out = g.rc_1.pwm_out; roll_out = (float)g.rc_1.pwm_out * .866;
pitch_out = g.rc_2.pwm_out / 2; pitch_out = g.rc_2.pwm_out / 2;
//Front side //Front side

View File

@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
}; };
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, "AC 2.0.22 Beta", main_menu_commands); MENU(main_menu, "AC 2.0.23 Beta", main_menu_commands);
void init_ardupilot() void init_ardupilot()
{ {

View File

@ -18,9 +18,9 @@ static int8_t test_tuning(uint8_t argc, const Menu::arg *argv);
static int8_t test_current(uint8_t argc, const Menu::arg *argv); static int8_t test_current(uint8_t argc, const Menu::arg *argv);
static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
static int8_t test_wp(uint8_t argc, const Menu::arg *argv); static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
static int8_t test_altitude(uint8_t argc, const Menu::arg *argv); static int8_t test_baro(uint8_t argc, const Menu::arg *argv);
static int8_t test_mag(uint8_t argc, const Menu::arg *argv); static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
//static int8_t test_sonar(uint8_t argc, const Menu::arg *argv); static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
static int8_t test_xbee(uint8_t argc, const Menu::arg *argv); static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv); static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv); static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
@ -64,9 +64,9 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
{"relay", test_relay}, {"relay", test_relay},
{"waypoints", test_wp}, {"waypoints", test_wp},
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
{"altitude", test_altitude}, {"altitude", test_baro},
#endif #endif
//{"sonar", test_sonar}, {"sonar", test_sonar},
{"compass", test_mag}, {"compass", test_mag},
{"xbee", test_xbee}, {"xbee", test_xbee},
{"eedump", test_eedump}, {"eedump", test_eedump},
@ -814,10 +814,9 @@ test_xbee(uint8_t argc, const Menu::arg *argv)
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
static int8_t static int8_t
test_altitude(uint8_t argc, const Menu::arg *argv) test_baro(uint8_t argc, const Menu::arg *argv)
{ {
print_hit_enter(); print_hit_enter();
init_barometer(); init_barometer();
while(1){ while(1){
@ -825,14 +824,7 @@ test_altitude(uint8_t argc, const Menu::arg *argv)
baro_alt = read_barometer(); baro_alt = read_barometer();
if(g.sonar_enabled){ Serial.printf_P(PSTR("Baro: %dcm\n"), baro_alt);
// decide which sensor we're usings
sonar_alt = sonar.read();
}
Serial.printf_P(PSTR("B_alt: %d, S_alt: %d\n"),
baro_alt,
sonar_alt);
if(Serial.available() > 0){ if(Serial.available() > 0){
return (0); return (0);
@ -877,22 +869,21 @@ test_mag(uint8_t argc, const Menu::arg *argv)
/* /*
test the sonar test the sonar
*/ */
/*static int8_t static int8_t
test_sonar(uint8_t argc, const Menu::arg *argv) test_sonar(uint8_t argc, const Menu::arg *argv)
{ {
print_hit_enter(); print_hit_enter();
delay(1000);
while(1) { while(1) {
Serial.printf_P(PSTR("%d cm\n"), sonar.read());
delay(100); delay(100);
Serial.printf_P(PSTR("Sonar: %d cm\n"), sonar.read());
if(Serial.available() > 0){ if(Serial.available() > 0){
return (0); return (0);
} }
} }
return (0); return (0);
} }
*/
static int8_t static int8_t
test_mission(uint8_t argc, const Menu::arg *argv) test_mission(uint8_t argc, const Menu::arg *argv)