mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
minor formatting
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2441 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
f5700c75c8
commit
c66611cceb
@ -379,8 +379,8 @@ void Log_Write_GPS()
|
||||
void Log_Read_GPS()
|
||||
{
|
||||
Serial.printf_P(PSTR("GPS, %ld, %d, %d, "
|
||||
"%4.7f, %4.7f, %4.4f, %4.4f, "
|
||||
"%d, %u\n"),
|
||||
"%4.7f, %4.7f, %4.4f, %4.4f, "
|
||||
"%d, %u\n"),
|
||||
|
||||
DataFlash.ReadLong(), // 1 time
|
||||
(int)DataFlash.ReadByte(), // 2 fix
|
||||
@ -460,16 +460,29 @@ void Log_Write_Nav_Tuning()
|
||||
DataFlash.WriteInt((int)(target_bearing/100)); // 3
|
||||
DataFlash.WriteInt((int)(nav_bearing/100)); // 4
|
||||
|
||||
DataFlash.WriteInt((int)long_error); // 5
|
||||
DataFlash.WriteInt((int)lat_error); // 6
|
||||
DataFlash.WriteInt((int)nav_lon); // 7
|
||||
DataFlash.WriteInt((int)nav_lat); // 8
|
||||
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
|
||||
void Log_Read_Nav_Tuning()
|
||||
{
|
||||
// 1 2 3 4
|
||||
Serial.printf_P(PSTR( "NTUN, %d, %d, %d, %d\n"),
|
||||
Serial.printf_P(PSTR( "NTUN, %d, %d, %d, %d, "
|
||||
"%d, %d, %d, %d\n"),
|
||||
|
||||
DataFlash.ReadInt(), //distance
|
||||
DataFlash.ReadByte(), //bitmask
|
||||
DataFlash.ReadInt(), //target bearing
|
||||
DataFlash.ReadInt(),
|
||||
|
||||
DataFlash.ReadInt(),
|
||||
DataFlash.ReadInt(),
|
||||
DataFlash.ReadInt(),
|
||||
DataFlash.ReadInt()); //nav bearing
|
||||
}
|
||||
|
||||
|
@ -382,7 +382,7 @@
|
||||
# define NAV_LOITER_P 2.5 // upped to be a bit more aggressive
|
||||
#endif
|
||||
#ifndef NAV_LOITER_I
|
||||
# define NAV_LOITER_I 0.10 // upped a bit to deal with wind faster
|
||||
# define NAV_LOITER_I 0.05 // upped a bit to deal with wind faster
|
||||
#endif
|
||||
#ifndef NAV_LOITER_D
|
||||
# define NAV_LOITER_D 0.00
|
||||
@ -433,7 +433,7 @@
|
||||
# define THROTTLE_BARO_D 0.06 //
|
||||
#endif
|
||||
#ifndef THROTTLE_BARO_IMAX
|
||||
# define THROTTLE_BARO_IMAX 20
|
||||
# define THROTTLE_BARO_IMAX 30
|
||||
#endif
|
||||
|
||||
|
||||
@ -447,7 +447,7 @@
|
||||
# define THROTTLE_SONAR_D 0.3 // increasing D by .5
|
||||
#endif
|
||||
#ifndef THROTTLE_SONAR_IMAX
|
||||
# define THROTTLE_SONAR_IMAX 20
|
||||
# define THROTTLE_SONAR_IMAX 30
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -31,6 +31,7 @@ void output_motors_armed()
|
||||
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK
|
||||
|
||||
}else{
|
||||
|
||||
roll_out = g.rc_1.pwm_out;
|
||||
pitch_out = g.rc_2.pwm_out;
|
||||
|
||||
|
@ -52,7 +52,7 @@ void init_barometer(void)
|
||||
// makes the filtering work later
|
||||
abs_pressure = barometer.Press;
|
||||
|
||||
// save home pressure - will be overwritten by init_home, no big deal
|
||||
// save home pressure
|
||||
ground_pressure = abs_pressure;
|
||||
|
||||
//Serial.printf("abs_pressure %ld\n", abs_pressure);
|
||||
|
@ -72,7 +72,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
{"eedump", test_eedump},
|
||||
{"rawgps", test_rawgps},
|
||||
{"mission", test_mission},
|
||||
// {"wp", test_wp_nav},
|
||||
//{"wp", test_wp_nav},
|
||||
};
|
||||
|
||||
// A Macro to create the Menu
|
||||
@ -205,19 +205,24 @@ test_wp_nav(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
g.rc_6.set_range(0,900);
|
||||
g.rc_4.set_angle(9000);
|
||||
dTnav = 200;
|
||||
current_loc.lat = 32.9513090 * t7;
|
||||
current_loc.lng = -117.2381700 * t7;
|
||||
|
||||
do_loiter_at_location();
|
||||
|
||||
wp_control = LOITER_MODE;
|
||||
|
||||
//dTnav: 0, gs: 305, err: 145, int: 0, pitch: 28508160 gps_GC: 0, gps_GS: 305
|
||||
while(1){
|
||||
delay(20);
|
||||
read_radio();
|
||||
current_loc.lng = g.rc_1.control_in;
|
||||
current_loc.lat = g.rc_2.control_in;
|
||||
delay(dTnav);
|
||||
|
||||
calc_loiter_nav();
|
||||
current_loc.lng = (-117.2381700 * t7) + g.rc_1.control_in / 2;
|
||||
current_loc.lat = (32.9513090 * t7) + g.rc_2.control_in / 2;
|
||||
|
||||
navigate();
|
||||
update_nav_wp();
|
||||
|
||||
Serial.printf("Lon_e: %ld, nLon, %ld, Lat_e %ld, nLat %ld\n", long_error, nav_lon, lat_error, nav_lat);
|
||||
|
||||
@ -226,6 +231,7 @@ test_wp_nav(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//*/
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user