This commit is contained in:
Wenyao Xie 2011-12-03 14:00:23 -05:00
commit 29c2dafb94
98 changed files with 299456 additions and 443 deletions

View File

@ -214,6 +214,9 @@ static void init_ardupilot()
gcs3.init(&Serial3);
#endif
// identify ourselves correctly with the ground station
mavlink_system.sysid = g.sysid_this_mav;
#ifdef RADIO_OVERRIDE_DEFAULTS
{
int16_t rc_override[8] = RADIO_OVERRIDE_DEFAULTS;

View File

@ -13,7 +13,6 @@ static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
static int8_t test_gyro(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(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);
@ -57,7 +56,6 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
{"gps", test_gps},
{"rawgps", test_rawgps},
{"imu", test_imu},
{"gyro", test_gyro},
{"airspeed", test_airspeed},
{"airpressure", test_pressure},
{"compass", test_mag},
@ -66,7 +64,6 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
{"adc", test_adc},
{"gps", test_gps},
{"imu", test_imu},
{"gyro", test_gyro},
{"compass", test_mag},
#elif HIL_MODE == HIL_MODE_ATTITUDE
#endif
@ -535,10 +532,14 @@ test_imu(uint8_t argc, const Menu::arg *argv)
// We are using the IMU
// ---------------------
Serial.printf_P(PSTR("r: %d\tp: %d\t y: %d\n"),
(int)dcm.roll_sensor / 100,
(int)dcm.pitch_sensor / 100,
(uint16_t)dcm.yaw_sensor / 100);
Vector3f gyros = imu.get_gyro();
Vector3f accels = imu.get_accel();
Serial.printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
(int)dcm.roll_sensor / 100,
(int)dcm.pitch_sensor / 100,
(uint16_t)dcm.yaw_sensor / 100,
gyros.x, gyros.y, gyros.z,
accels.x, accels.y, accels.z);
}
if(Serial.available() > 0){
return (0);
@ -547,36 +548,6 @@ test_imu(uint8_t argc, const Menu::arg *argv)
}
static int8_t
test_gyro(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
isr_registry.init();
timer_scheduler.init(&isr_registry);
adc.Init(&timer_scheduler);
delay(1000);
Serial.printf_P(PSTR("Gyro | Accel\n"));
delay(1000);
while(1){
imu.update(); // need this because we are not calling the DCM
Vector3f gyros = imu.get_gyro();
Vector3f accels = imu.get_accel();
Serial.printf_P(PSTR("%d\t%d\t%d\t|\t%d\t%d\t%d\n"),
(int)gyros.x,
(int)gyros.y,
(int)gyros.z,
(int)accels.x,
(int)accels.y,
(int)accels.z);
delay(100);
if(Serial.available() > 0){
return (0);
}
}
}
static int8_t
test_mag(uint8_t argc, const Menu::arg *argv)
{

View File

@ -0,0 +1,163 @@
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde: In function 'void update_commands()':
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde:57: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:118: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/events.pde:51: warning: 'void low_battery_event()' defined but not used
autogenerated:183: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:190: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:239: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:250: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:264: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:265: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:272: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:273: warning: 'int read_num_from_serial()' declared 'static' but never defined
autogenerated:288: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:282: warning: 'ch3_failsafe' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1784: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:33: warning: 'int8_t test_eedump(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
%% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o
%% libraries/AP_ADC/AP_ADC_HIL.o
%% libraries/AP_Common/AP_Common.o
%% libraries/AP_Common/AP_Loop.o
%% libraries/AP_Common/AP_MetaClass.o
%% libraries/AP_Common/AP_Var.o
%% libraries/AP_Common/AP_Var_menufuncs.o
%% libraries/AP_Common/c++.o
%% libraries/AP_Common/menu.o
%% libraries/AP_Compass/AP_Compass_HIL.o
%% libraries/AP_Compass/AP_Compass_HMC5843.o
%% libraries/AP_Compass/Compass.o
%% libraries/AP_DCM/AP_DCM.o
%% libraries/AP_DCM/AP_DCM_HIL.o
%% libraries/AP_GPS/AP_GPS_406.o
%% libraries/AP_GPS/AP_GPS_Auto.o
%% libraries/AP_GPS/AP_GPS_HIL.o
%% libraries/AP_GPS/AP_GPS_IMU.o
%% libraries/AP_GPS/AP_GPS_MTK16.o
%% libraries/AP_GPS/AP_GPS_MTK.o
%% libraries/AP_GPS/AP_GPS_NMEA.o
%% libraries/AP_GPS/AP_GPS_SIRF.o
%% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o
%% libraries/FastSerial/FastSerial.o
%% libraries/FastSerial/vprintf.o
%% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o
%% libraries/FastSerial/ultoa_invert.o
%% libraries/SPI/SPI.o
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/Wire/Wire.o
%% libraries/Wire/utility/twi.o
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
%% arduino/HardwareSerial.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/main.o
%% arduino/Print.o
%% arduino/Tone.o
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
%% arduino/WMath.o
%% arduino/WString.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/core.a
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -0,0 +1,623 @@
00000001 b wp_control
00000001 b GPS_enabled
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_yaw_dir
00000001 b failsafeCounter
00000001 b new_radio_frame
00000001 b roll_pitch_mode
00000001 b counter_one_herz
00000001 b did_ground_start
00000001 b in_mavlink_delay
00000001 b invalid_throttle
00000001 b motor_auto_armed
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b failsafe
00000001 b led_mode
00000001 b yaw_mode
00000001 b GPS_light
00000001 b do_simple
00000001 b trim_flag
00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B relay
00000002 T userhook_50Hz()
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
00000002 b ground_temperature
00000002 b waypoint_speed_gov
00000002 b superslow_loopCounter
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r erase_logs(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
00000004 b sin_roll_y
00000004 d cos_pitch_x
00000004 b event_timer
00000004 b loiter_time
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b command_yaw_end
00000004 b condition_start
00000004 b condition_value
00000004 b ground_pressure
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b wp_totalDistance
00000004 b command_yaw_delta
00000004 b command_yaw_start
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
00000004 b original_target_bearing
00000004 d G_Dt
00000004 b dTnav
00000004 b nav_lat
00000004 b nav_lon
00000004 b nav_yaw
00000004 b old_alt
00000004 b auto_yaw
00000004 b nav_roll
00000004 d cos_yaw_x
00000004 b lat_error
00000004 b nav_pitch
00000004 b sin_yaw_y
00000004 b yaw_error
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B tuning_value
00000005 r __menu_name__test_menu
00000005 r report_imu()::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r Log_Read_Raw()::__c
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
00000005 r Log_Read_Mode()::__c
00000005 r report_tuning()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
00000006 r report_gps()::__c
00000006 r zero_eeprom()::__c
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
00000007 b log_menu
00000007 b main_menu
00000007 b test_menu
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r report_frame()::__c
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_tuning()::__c
00000008 r init_ardupilot()::__c
00000008 r print_log_menu()::__c
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
00000009 r print_log_menu()::__c
00000009 r print_log_menu()::__c
00000009 r report_compass()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r print_log_menu()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
0000000d r dump_log(unsigned char, Menu::arg const*)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> >
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r report_compass()::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
00000012 r flight_mode_strings
00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
00000012 W AP_VarT<signed char>::~AP_VarT()
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r __menu_name__main_menu
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a t gcs_update()
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Process(int, int)::__c
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001c r Log_Read(int, int)::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
0000001f r print_log_menu()::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r Log_Read_Current()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000022 r Log_Read(int, int)::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t gcs_send_message(ap_message)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r init_ardupilot()::__c
0000002a t send_heartbeat(mavlink_channel_t)
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t mavlink_msg_statustext_send
00000036 t report_radio()
00000036 t gcs_data_stream_send(unsigned int, unsigned int)
00000036 T GCS_MAVLINK::init(FastSerial*)
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
0000003a t report_gps()
0000003a t report_imu()
0000003d B g_gps_driver
0000003e t startup_ground()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000048 B barometer
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_enabled(unsigned char)
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 r test_menu_commands
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000072 t check_missed_wp()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000082 t Log_Write_Attitude()
00000082 t read_control_switch()
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
00000090 t report_tuning()
00000090 t change_command(unsigned char)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t set_failsafe(unsigned char)
0000009a t init_compass()
0000009c t get_num_logs()
0000009d B gcs0
0000009d B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t planner_gcs(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
000000a0 T GCS_MAVLINK::queued_param_send()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ae t report_frame()
000000b7 B compass
000000be t update_events()
000000c0 t Log_Read(int, int)
000000c0 t dump_log(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c7 B dcm
000000ca t init_barometer()
000000ca t Log_Read_Control_Tuning()
000000cc t Log_Read_Nav_Tuning()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d0 r setup_menu_commands
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000da t reset_nav()
000000e0 t erase_logs(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t get_log_boundaries(unsigned char, int&, int&)
0000010c t test_current(unsigned char, Menu::arg const*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000120 t find_last()
0000012c t find_last_log_page(unsigned int)
00000130 t report_compass()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t Log_Read_Process(int, int)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
0000016a T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016c t read_radio()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000180 t set_next_WP(Location*)
00000188 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001fc t set_mode(unsigned char)
00000210 t setup_motors(unsigned char, Menu::arg const*)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t setup_radio(unsigned char, Menu::arg const*)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
0000026a t send_gps_raw(mavlink_channel_t)
00000362 t tuning()
0000036e t execute_nav_command()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
000003ae t print_log_menu()
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
0000076e t init_ardupilot()
000007e0 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
00000906 b g
0000090c W Parameters::Parameters()
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00002398 T loop

View File

@ -0,0 +1,177 @@
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde: In function 'void update_commands()':
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde:57: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:55: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:56: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:57: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:112: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:118: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/events.pde:51: warning: 'void low_battery_event()' defined but not used
autogenerated:183: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:190: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:239: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
autogenerated:248: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:249: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:250: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_barometer()' declared 'static' but never defined
autogenerated:252: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:253: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:264: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:265: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:272: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:273: warning: 'int read_num_from_serial()' declared 'static' but never defined
autogenerated:288: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:282: warning: 'ch3_failsafe' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:365: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'old_sonar_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1784: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:33: warning: 'int8_t test_eedump(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
%% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o
%% libraries/AP_ADC/AP_ADC_HIL.o
%% libraries/AP_Common/AP_Common.o
%% libraries/AP_Common/AP_Loop.o
%% libraries/AP_Common/AP_MetaClass.o
%% libraries/AP_Common/AP_Var.o
%% libraries/AP_Common/AP_Var_menufuncs.o
%% libraries/AP_Common/c++.o
%% libraries/AP_Common/menu.o
%% libraries/AP_Compass/AP_Compass_HIL.o
%% libraries/AP_Compass/AP_Compass_HMC5843.o
%% libraries/AP_Compass/Compass.o
%% libraries/AP_DCM/AP_DCM.o
%% libraries/AP_DCM/AP_DCM_HIL.o
%% libraries/AP_GPS/AP_GPS_406.o
%% libraries/AP_GPS/AP_GPS_Auto.o
%% libraries/AP_GPS/AP_GPS_HIL.o
%% libraries/AP_GPS/AP_GPS_IMU.o
%% libraries/AP_GPS/AP_GPS_MTK16.o
%% libraries/AP_GPS/AP_GPS_MTK.o
%% libraries/AP_GPS/AP_GPS_NMEA.o
%% libraries/AP_GPS/AP_GPS_SIRF.o
%% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o
%% libraries/FastSerial/FastSerial.o
%% libraries/FastSerial/vprintf.o
%% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o
%% libraries/FastSerial/ultoa_invert.o
%% libraries/SPI/SPI.o
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/Wire/Wire.o
%% libraries/Wire/utility/twi.o
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
%% arduino/HardwareSerial.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/main.o
%% arduino/Print.o
%% arduino/Tone.o
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
%% arduino/WMath.o
%% arduino/WString.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/core.a
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -0,0 +1,619 @@
00000001 b wp_control
00000001 b GPS_enabled
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_yaw_dir
00000001 b failsafeCounter
00000001 b new_radio_frame
00000001 b roll_pitch_mode
00000001 b counter_one_herz
00000001 b did_ground_start
00000001 b in_mavlink_delay
00000001 b invalid_throttle
00000001 b motor_auto_armed
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b failsafe
00000001 b led_mode
00000001 b yaw_mode
00000001 b GPS_light
00000001 b do_simple
00000001 b trim_flag
00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B relay
00000002 T userhook_50Hz()
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b gps_fix_count
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
00000002 b waypoint_speed_gov
00000002 b superslow_loopCounter
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
00000002 b arm_motors()::arming_counter
00000002 r erase_logs(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
00000004 b sin_roll_y
00000004 d cos_pitch_x
00000004 b event_timer
00000004 b loiter_time
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b circle_angle
00000004 b current_amps
00000004 b gps_base_alt
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b command_yaw_end
00000004 b condition_start
00000004 b condition_value
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b wp_totalDistance
00000004 b command_yaw_delta
00000004 b command_yaw_start
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
00000004 b original_target_bearing
00000004 d G_Dt
00000004 b dTnav
00000004 b nav_lat
00000004 b nav_lon
00000004 b nav_yaw
00000004 b old_alt
00000004 b auto_yaw
00000004 b nav_roll
00000004 d cos_yaw_x
00000004 b lat_error
00000004 b nav_pitch
00000004 b sin_yaw_y
00000004 b yaw_error
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B tuning_value
00000005 r __menu_name__test_menu
00000005 r report_imu()::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r Log_Read_Raw()::__c
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
00000005 r Log_Read_Mode()::__c
00000005 r report_tuning()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
00000006 r report_gps()::__c
00000006 r zero_eeprom()::__c
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
00000007 b log_menu
00000007 b main_menu
00000007 b test_menu
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r report_frame()::__c
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_tuning()::__c
00000008 r init_ardupilot()::__c
00000008 r print_log_menu()::__c
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
00000009 r print_log_menu()::__c
00000009 r print_log_menu()::__c
00000009 r report_compass()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r print_log_menu()::__c
0000000b V Parameters::Parameters()::__c
0000000c t setup_accel(unsigned char, Menu::arg const*)
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
0000000d r dump_log(unsigned char, Menu::arg const*)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> >
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r init_arm_motors()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r report_compass()::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r init_disarm_motors()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
00000012 t startup_ground()
00000012 r flight_mode_strings
00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
00000012 W AP_VarT<signed char>::~AP_VarT()
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r __menu_name__main_menu
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B adc
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a t gcs_update()
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Process(int, int)::__c
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001c r Log_Read(int, int)::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e t init_disarm_motors()
0000001e r Log_Read_Optflow()::__c
0000001f r print_log_menu()::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r Log_Read_Current()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000022 r Log_Read(int, int)::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t gcs_send_message(ap_message)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r init_ardupilot()::__c
0000002a t send_heartbeat(mavlink_channel_t)
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000030 B imu
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t mavlink_msg_statustext_send
00000036 t report_radio()
00000036 t gcs_send_text_P(gcs_severity, prog_char_t const*)
00000036 t gcs_data_stream_send(unsigned int, unsigned int)
00000036 T GCS_MAVLINK::init(FastSerial*)
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
0000003a t report_gps()
0000003a t report_imu()
0000003a B g_gps_driver
0000003c t read_AHRS()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000052 W AP_IMU_Shim::update()
00000054 t print_enabled(unsigned char)
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 B dcm
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 r test_menu_commands
00000064 t print_gyro_offsets()
00000064 t print_accel_offsets()
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t init_arm_motors()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000072 t check_missed_wp()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000082 t read_control_switch()
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
00000090 t init_compass()
00000090 t report_tuning()
00000090 t change_command(unsigned char)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t set_failsafe(unsigned char)
0000009a t arm_motors()
0000009a t Log_Read_Motors()
0000009c t get_num_logs()
0000009d B gcs0
0000009d B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t planner_gcs(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
000000a0 T GCS_MAVLINK::queued_param_send()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ab B compass
000000ae t report_frame()
000000be t update_events()
000000c0 t Log_Read(int, int)
000000c0 t dump_log(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c6 t send_radio_in(mavlink_channel_t)
000000ca t Log_Read_Control_Tuning()
000000cc t Log_Read_Nav_Tuning()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d0 r setup_menu_commands
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000da t reset_nav()
000000e0 t erase_logs(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t get_log_boundaries(unsigned char, int&, int&)
0000010c t test_current(unsigned char, Menu::arg const*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
0000011c t get_cmd_with_index(int)
00000120 t find_last()
0000012c t find_last_log_page(unsigned int)
00000130 t report_compass()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t Log_Read_Process(int, int)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
0000016c t read_radio()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000180 t set_next_WP(Location*)
00000188 t verify_nav_wp()
00000190 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001a8 t print_radio_values()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001fc t set_mode(unsigned char)
00000204 t test_imu(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
00000246 t calc_loiter(int, int)
0000026a t send_gps_raw(mavlink_channel_t)
00000362 t tuning()
0000036e t execute_nav_command()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
000003ae t print_log_menu()
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
000005b0 t __static_initialization_and_destruction_0(int, int)
000006aa t init_ardupilot()
00000878 t update_nav_wp()
00000906 b g
0000090c W Parameters::Parameters()
000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001efc T loop

View File

@ -0,0 +1,163 @@
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde: In function 'void update_commands()':
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde:57: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:118: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/events.pde:51: warning: 'void low_battery_event()' defined but not used
autogenerated:183: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:190: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:239: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:250: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:264: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:265: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:272: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:273: warning: 'int read_num_from_serial()' declared 'static' but never defined
autogenerated:288: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:282: warning: 'ch3_failsafe' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1784: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:33: warning: 'int8_t test_eedump(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
%% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o
%% libraries/AP_ADC/AP_ADC_HIL.o
%% libraries/AP_Common/AP_Common.o
%% libraries/AP_Common/AP_Loop.o
%% libraries/AP_Common/AP_MetaClass.o
%% libraries/AP_Common/AP_Var.o
%% libraries/AP_Common/AP_Var_menufuncs.o
%% libraries/AP_Common/c++.o
%% libraries/AP_Common/menu.o
%% libraries/AP_Compass/AP_Compass_HIL.o
%% libraries/AP_Compass/AP_Compass_HMC5843.o
%% libraries/AP_Compass/Compass.o
%% libraries/AP_DCM/AP_DCM.o
%% libraries/AP_DCM/AP_DCM_HIL.o
%% libraries/AP_GPS/AP_GPS_406.o
%% libraries/AP_GPS/AP_GPS_Auto.o
%% libraries/AP_GPS/AP_GPS_HIL.o
%% libraries/AP_GPS/AP_GPS_IMU.o
%% libraries/AP_GPS/AP_GPS_MTK16.o
%% libraries/AP_GPS/AP_GPS_MTK.o
%% libraries/AP_GPS/AP_GPS_NMEA.o
%% libraries/AP_GPS/AP_GPS_SIRF.o
%% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o
%% libraries/FastSerial/FastSerial.o
%% libraries/FastSerial/vprintf.o
%% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o
%% libraries/FastSerial/ultoa_invert.o
%% libraries/SPI/SPI.o
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/Wire/Wire.o
%% libraries/Wire/utility/twi.o
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
%% arduino/HardwareSerial.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/main.o
%% arduino/Print.o
%% arduino/Tone.o
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
%% arduino/WMath.o
%% arduino/WString.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/core.a
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -0,0 +1,623 @@
00000001 b wp_control
00000001 b GPS_enabled
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_yaw_dir
00000001 b failsafeCounter
00000001 b new_radio_frame
00000001 b roll_pitch_mode
00000001 b counter_one_herz
00000001 b did_ground_start
00000001 b in_mavlink_delay
00000001 b invalid_throttle
00000001 b motor_auto_armed
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b failsafe
00000001 b led_mode
00000001 b yaw_mode
00000001 b GPS_light
00000001 b do_simple
00000001 b trim_flag
00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B relay
00000002 T userhook_50Hz()
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
00000002 b ground_temperature
00000002 b waypoint_speed_gov
00000002 b superslow_loopCounter
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r erase_logs(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
00000004 b sin_roll_y
00000004 d cos_pitch_x
00000004 b event_timer
00000004 b loiter_time
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b command_yaw_end
00000004 b condition_start
00000004 b condition_value
00000004 b ground_pressure
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b wp_totalDistance
00000004 b command_yaw_delta
00000004 b command_yaw_start
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
00000004 b original_target_bearing
00000004 d G_Dt
00000004 b dTnav
00000004 b nav_lat
00000004 b nav_lon
00000004 b nav_yaw
00000004 b old_alt
00000004 b auto_yaw
00000004 b nav_roll
00000004 d cos_yaw_x
00000004 b lat_error
00000004 b nav_pitch
00000004 b sin_yaw_y
00000004 b yaw_error
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B tuning_value
00000005 r __menu_name__test_menu
00000005 r report_imu()::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r Log_Read_Raw()::__c
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
00000005 r Log_Read_Mode()::__c
00000005 r report_tuning()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
00000006 r report_gps()::__c
00000006 r zero_eeprom()::__c
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
00000007 b log_menu
00000007 b main_menu
00000007 b test_menu
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r report_frame()::__c
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_tuning()::__c
00000008 r init_ardupilot()::__c
00000008 r print_log_menu()::__c
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
00000009 r print_log_menu()::__c
00000009 r print_log_menu()::__c
00000009 r report_compass()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r print_log_menu()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
0000000d r dump_log(unsigned char, Menu::arg const*)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> >
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r report_compass()::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
00000012 r flight_mode_strings
00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
00000012 W AP_VarT<signed char>::~AP_VarT()
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r __menu_name__main_menu
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a t gcs_update()
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Process(int, int)::__c
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001c r Log_Read(int, int)::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
0000001f r print_log_menu()::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r Log_Read_Current()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000022 r Log_Read(int, int)::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t gcs_send_message(ap_message)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r init_ardupilot()::__c
0000002a t send_heartbeat(mavlink_channel_t)
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t mavlink_msg_statustext_send
00000036 t report_radio()
00000036 t gcs_data_stream_send(unsigned int, unsigned int)
00000036 T GCS_MAVLINK::init(FastSerial*)
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
0000003a t report_gps()
0000003a t report_imu()
0000003d B g_gps_driver
0000003e t startup_ground()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000048 B barometer
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_enabled(unsigned char)
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 r test_menu_commands
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000072 t check_missed_wp()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000082 t Log_Write_Attitude()
00000082 t read_control_switch()
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
00000090 t report_tuning()
00000090 t change_command(unsigned char)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t set_failsafe(unsigned char)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009c t get_num_logs()
0000009d B gcs0
0000009d B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t planner_gcs(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
000000a0 T GCS_MAVLINK::queued_param_send()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ae t report_frame()
000000b7 B compass
000000be t update_events()
000000c0 t Log_Read(int, int)
000000c0 t dump_log(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c7 B dcm
000000ca t init_barometer()
000000ca t Log_Read_Control_Tuning()
000000cc t Log_Read_Nav_Tuning()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d0 r setup_menu_commands
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000da t reset_nav()
000000e0 t erase_logs(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t get_log_boundaries(unsigned char, int&, int&)
0000010c t test_current(unsigned char, Menu::arg const*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000120 t find_last()
0000012c t find_last_log_page(unsigned int)
00000130 t report_compass()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t Log_Read_Process(int, int)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
0000016a T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016c t read_radio()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000180 t set_next_WP(Location*)
00000188 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001fc t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t setup_radio(unsigned char, Menu::arg const*)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
0000026a t send_gps_raw(mavlink_channel_t)
00000362 t tuning()
0000036e t execute_nav_command()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
000003ae t print_log_menu()
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000772 t init_ardupilot()
000007e0 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
00000906 b g
0000090c W Parameters::Parameters()
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00002272 T loop

View File

@ -0,0 +1,163 @@
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde: In function 'void update_commands()':
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde:57: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:118: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/events.pde:51: warning: 'void low_battery_event()' defined but not used
autogenerated:183: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:190: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:239: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:250: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:264: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:265: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:272: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:273: warning: 'int read_num_from_serial()' declared 'static' but never defined
autogenerated:288: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:282: warning: 'ch3_failsafe' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1784: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:33: warning: 'int8_t test_eedump(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
%% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o
%% libraries/AP_ADC/AP_ADC_HIL.o
%% libraries/AP_Common/AP_Common.o
%% libraries/AP_Common/AP_Loop.o
%% libraries/AP_Common/AP_MetaClass.o
%% libraries/AP_Common/AP_Var.o
%% libraries/AP_Common/AP_Var_menufuncs.o
%% libraries/AP_Common/c++.o
%% libraries/AP_Common/menu.o
%% libraries/AP_Compass/AP_Compass_HIL.o
%% libraries/AP_Compass/AP_Compass_HMC5843.o
%% libraries/AP_Compass/Compass.o
%% libraries/AP_DCM/AP_DCM.o
%% libraries/AP_DCM/AP_DCM_HIL.o
%% libraries/AP_GPS/AP_GPS_406.o
%% libraries/AP_GPS/AP_GPS_Auto.o
%% libraries/AP_GPS/AP_GPS_HIL.o
%% libraries/AP_GPS/AP_GPS_IMU.o
%% libraries/AP_GPS/AP_GPS_MTK16.o
%% libraries/AP_GPS/AP_GPS_MTK.o
%% libraries/AP_GPS/AP_GPS_NMEA.o
%% libraries/AP_GPS/AP_GPS_SIRF.o
%% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o
%% libraries/FastSerial/FastSerial.o
%% libraries/FastSerial/vprintf.o
%% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o
%% libraries/FastSerial/ultoa_invert.o
%% libraries/SPI/SPI.o
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/Wire/Wire.o
%% libraries/Wire/utility/twi.o
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
%% arduino/HardwareSerial.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/main.o
%% arduino/Print.o
%% arduino/Tone.o
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
%% arduino/WMath.o
%% arduino/WString.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/core.a
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -0,0 +1,623 @@
00000001 b wp_control
00000001 b GPS_enabled
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_yaw_dir
00000001 b failsafeCounter
00000001 b new_radio_frame
00000001 b roll_pitch_mode
00000001 b counter_one_herz
00000001 b did_ground_start
00000001 b in_mavlink_delay
00000001 b invalid_throttle
00000001 b motor_auto_armed
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b failsafe
00000001 b led_mode
00000001 b yaw_mode
00000001 b GPS_light
00000001 b do_simple
00000001 b trim_flag
00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B relay
00000002 T userhook_50Hz()
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
00000002 b ground_temperature
00000002 b waypoint_speed_gov
00000002 b superslow_loopCounter
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r erase_logs(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
00000004 b sin_roll_y
00000004 d cos_pitch_x
00000004 b event_timer
00000004 b loiter_time
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b command_yaw_end
00000004 b condition_start
00000004 b condition_value
00000004 b ground_pressure
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b wp_totalDistance
00000004 b command_yaw_delta
00000004 b command_yaw_start
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
00000004 b original_target_bearing
00000004 d G_Dt
00000004 b dTnav
00000004 b nav_lat
00000004 b nav_lon
00000004 b nav_yaw
00000004 b old_alt
00000004 b auto_yaw
00000004 b nav_roll
00000004 d cos_yaw_x
00000004 b lat_error
00000004 b nav_pitch
00000004 b sin_yaw_y
00000004 b yaw_error
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B tuning_value
00000005 r __menu_name__test_menu
00000005 r report_imu()::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r Log_Read_Raw()::__c
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
00000005 r Log_Read_Mode()::__c
00000005 r report_tuning()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
00000006 r report_gps()::__c
00000006 r zero_eeprom()::__c
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
00000007 b log_menu
00000007 b main_menu
00000007 b test_menu
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r report_frame()::__c
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_tuning()::__c
00000008 r init_ardupilot()::__c
00000008 r print_log_menu()::__c
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
00000009 r print_log_menu()::__c
00000009 r print_log_menu()::__c
00000009 r report_compass()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r report_frame()::__c
0000000b r print_log_menu()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
0000000d r dump_log(unsigned char, Menu::arg const*)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> >
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r report_compass()::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
00000012 r flight_mode_strings
00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
00000012 W AP_VarT<signed char>::~AP_VarT()
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r __menu_name__main_menu
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a t gcs_update()
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Process(int, int)::__c
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001c r Log_Read(int, int)::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
0000001f r print_log_menu()::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r Log_Read_Current()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000022 r Log_Read(int, int)::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t gcs_send_message(ap_message)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r init_ardupilot()::__c
0000002a t send_heartbeat(mavlink_channel_t)
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t mavlink_msg_statustext_send
00000036 t report_radio()
00000036 t gcs_data_stream_send(unsigned int, unsigned int)
00000036 T GCS_MAVLINK::init(FastSerial*)
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
0000003a t report_gps()
0000003a t report_imu()
0000003d B g_gps_driver
0000003e t startup_ground()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000048 B barometer
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_enabled(unsigned char)
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 r test_menu_commands
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000072 t check_missed_wp()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000082 t Log_Write_Attitude()
00000082 t read_control_switch()
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
00000090 t report_tuning()
00000090 t change_command(unsigned char)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t set_failsafe(unsigned char)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009c t get_num_logs()
0000009d B gcs0
0000009d B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t planner_gcs(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
000000a0 T GCS_MAVLINK::queued_param_send()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ae t report_frame()
000000b7 B compass
000000be t update_events()
000000c0 t Log_Read(int, int)
000000c0 t dump_log(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c7 B dcm
000000ca t init_barometer()
000000ca t Log_Read_Control_Tuning()
000000cc t Log_Read_Nav_Tuning()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d0 r setup_menu_commands
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000da t reset_nav()
000000de t setup_motors(unsigned char, Menu::arg const*)
000000e0 t erase_logs(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t get_log_boundaries(unsigned char, int&, int&)
0000010c t test_current(unsigned char, Menu::arg const*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000120 t find_last()
0000012c t find_last_log_page(unsigned int)
00000130 t report_compass()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t Log_Read_Process(int, int)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
0000016a T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016c t read_radio()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000180 t set_next_WP(Location*)
00000188 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001fc t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t setup_radio(unsigned char, Menu::arg const*)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
0000026a t send_gps_raw(mavlink_channel_t)
00000362 t tuning()
0000036e t execute_nav_command()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
000003ae t print_log_menu()
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000772 t init_ardupilot()
000007e0 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
00000906 b g
0000090c W Parameters::Parameters()
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
000021ae T loop

View File

@ -0,0 +1,163 @@
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde: In function 'void update_commands()':
/root/apm/ardupilot-mega/ArduCopter/commands_process.pde:57: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:118: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/events.pde:51: warning: 'void low_battery_event()' defined but not used
autogenerated:183: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:190: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:239: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:250: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:264: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:265: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:272: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:273: warning: 'int read_num_from_serial()' declared 'static' but never defined
autogenerated:288: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:282: warning: 'ch3_failsafe' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1784: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:33: warning: 'int8_t test_eedump(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
%% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o
%% libraries/AP_ADC/AP_ADC_HIL.o
%% libraries/AP_Common/AP_Common.o
%% libraries/AP_Common/AP_Loop.o
%% libraries/AP_Common/AP_MetaClass.o
%% libraries/AP_Common/AP_Var.o
%% libraries/AP_Common/AP_Var_menufuncs.o
%% libraries/AP_Common/c++.o
%% libraries/AP_Common/menu.o
%% libraries/AP_Compass/AP_Compass_HIL.o
%% libraries/AP_Compass/AP_Compass_HMC5843.o
%% libraries/AP_Compass/Compass.o
%% libraries/AP_DCM/AP_DCM.o
%% libraries/AP_DCM/AP_DCM_HIL.o
%% libraries/AP_GPS/AP_GPS_406.o
%% libraries/AP_GPS/AP_GPS_Auto.o
%% libraries/AP_GPS/AP_GPS_HIL.o
%% libraries/AP_GPS/AP_GPS_IMU.o
%% libraries/AP_GPS/AP_GPS_MTK16.o
%% libraries/AP_GPS/AP_GPS_MTK.o
%% libraries/AP_GPS/AP_GPS_NMEA.o
%% libraries/AP_GPS/AP_GPS_SIRF.o
%% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o
%% libraries/FastSerial/FastSerial.o
%% libraries/FastSerial/vprintf.o
%% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o
%% libraries/FastSerial/ultoa_invert.o
%% libraries/SPI/SPI.o
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/Wire/Wire.o
%% libraries/Wire/utility/twi.o
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
%% arduino/HardwareSerial.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/main.o
%% arduino/Print.o
%% arduino/Tone.o
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
%% arduino/WMath.o
%% arduino/WString.o
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
%% arduino/core.a
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -0,0 +1,623 @@
00000001 b wp_control
00000001 b GPS_enabled
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_yaw_dir
00000001 b failsafeCounter
00000001 b new_radio_frame
00000001 b roll_pitch_mode
00000001 b counter_one_herz
00000001 b did_ground_start
00000001 b in_mavlink_delay
00000001 b invalid_throttle
00000001 b motor_auto_armed
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b failsafe
00000001 b led_mode
00000001 b yaw_mode
00000001 b GPS_light
00000001 b do_simple
00000001 b trim_flag
00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B relay
00000002 T userhook_50Hz()
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
00000002 b ground_temperature
00000002 b waypoint_speed_gov
00000002 b superslow_loopCounter
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r erase_logs(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
00000004 b sin_roll_y
00000004 d cos_pitch_x
00000004 b event_timer
00000004 b loiter_time
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b command_yaw_end
00000004 b condition_start
00000004 b condition_value
00000004 b ground_pressure
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b wp_totalDistance
00000004 b command_yaw_delta
00000004 b command_yaw_start
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
00000004 b original_target_bearing
00000004 d G_Dt
00000004 b dTnav
00000004 b nav_lat
00000004 b nav_lon
00000004 b nav_yaw
00000004 b old_alt
00000004 b auto_yaw
00000004 b nav_roll
00000004 d cos_yaw_x
00000004 b lat_error
00000004 b nav_pitch
00000004 b sin_yaw_y
00000004 b yaw_error
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B tuning_value
00000005 r __menu_name__test_menu
00000005 r report_imu()::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
00000005 r Log_Read_Raw()::__c
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
00000005 r Log_Read_Mode()::__c
00000005 r report_tuning()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
00000006 r report_gps()::__c
00000006 r zero_eeprom()::__c
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
00000007 b log_menu
00000007 b main_menu
00000007 b test_menu
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
00000007 r report_frame()::__c
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
00000008 r report_tuning()::__c
00000008 r init_ardupilot()::__c
00000008 r print_log_menu()::__c
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
00000009 r print_log_menu()::__c
00000009 r print_log_menu()::__c
00000009 r report_compass()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r report_frame()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r print_log_menu()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
0000000d r dump_log(unsigned char, Menu::arg const*)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> >
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r report_compass()::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
00000012 r flight_mode_strings
00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
00000012 W AP_VarT<signed char>::~AP_VarT()
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r __menu_name__main_menu
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a t gcs_update()
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Process(int, int)::__c
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001c r Log_Read(int, int)::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
0000001f r print_log_menu()::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r Log_Read_Current()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000022 r Log_Read(int, int)::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t gcs_send_message(ap_message)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r init_ardupilot()::__c
0000002a t send_heartbeat(mavlink_channel_t)
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t mavlink_msg_statustext_send
00000036 t report_radio()
00000036 t gcs_data_stream_send(unsigned int, unsigned int)
00000036 T GCS_MAVLINK::init(FastSerial*)
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
0000003a t report_gps()
0000003a t report_imu()
0000003d B g_gps_driver
0000003e t startup_ground()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000048 B barometer
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_enabled(unsigned char)
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 r test_menu_commands
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000072 t check_missed_wp()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000082 t Log_Write_Attitude()
00000082 t read_control_switch()
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
00000090 t report_tuning()
00000090 t change_command(unsigned char)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t set_failsafe(unsigned char)
0000009a t init_compass()
0000009c t get_num_logs()
0000009d B gcs0
0000009d B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t planner_gcs(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
000000a0 T GCS_MAVLINK::queued_param_send()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ae t report_frame()
000000b7 B compass
000000be t update_events()
000000c0 t Log_Read(int, int)
000000c0 t dump_log(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c7 B dcm
000000ca t init_barometer()
000000ca t Log_Read_Control_Tuning()
000000cc t Log_Read_Nav_Tuning()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d0 r setup_menu_commands
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000da t reset_nav()
000000e0 t erase_logs(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t get_log_boundaries(unsigned char, int&, int&)
0000010c t test_current(unsigned char, Menu::arg const*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000120 t find_last()
0000012c t find_last_log_page(unsigned int)
00000130 t report_compass()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t Log_Read_Process(int, int)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t setup_motors(unsigned char, Menu::arg const*)
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
0000016a T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016c t read_radio()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000180 t set_next_WP(Location*)
00000188 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001fc t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t setup_radio(unsigned char, Menu::arg const*)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
0000026a t send_gps_raw(mavlink_channel_t)
00000362 t tuning()
0000036e t execute_nav_command()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
000003ae t print_log_menu()
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
0000076e t init_ardupilot()
000007e0 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
00000906 b g
0000090c W Parameters::Parameters()
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
000024cc T loop

View File

@ -1,17 +1,17 @@
<?xml version="1.0" encoding="utf-8" ?>
<options>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex</url2560-2>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 </name>
<desc></desc>
<format_version>12</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex</url2560-2>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 HIL</name>
<desc>
#define FLIGHT_MODE_CHANNEL 8
@ -44,18 +44,18 @@
<format_version>12</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560-2.hex</url2560-2>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 APM trunk</name>
<desc></desc>
<format_version>12</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Quad</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Quad</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -64,10 +64,10 @@
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Tri</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Tri</name>
<desc>
#define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -76,10 +76,10 @@
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Hexa</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Hexa</name>
<desc>
#define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -88,10 +88,10 @@
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Y6</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Y6</name>
<desc>
#define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -100,10 +100,10 @@
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Heli (2560 only)</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Heli (2560 only)</name>
<desc>
#define AUTO_RESET_LOITER 0
#define FRAME_CONFIG HELI_FRAME
@ -145,13 +145,13 @@
#define NAV_LOITER_IMAX 10
</desc>
<format_version>112</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Quad Hil</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Quad Hil</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME
@ -164,10 +164,10 @@
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Heli Hil</name>
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex</url2560>
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.54 Heli Hil</name>
<desc>
#define HIL_MODE HIL_MODE_ATTITUDE
@ -213,6 +213,6 @@
</desc>
<format_version>112</format_version>
<format_version>113</format_version>
</Firmware>
</options>

View File

@ -16,9 +16,9 @@
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
<F4>CH1 out</F4>
<F5>CH2 out</F5>
<F6>CH4 out</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
@ -33,28 +33,28 @@
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>climb rate</F10>
<F11></F11>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
<F1>Roll IN</F1>
<F2>Pitch IN</F2>
<F3>Thr IN</F3>
<F4>Yaw IN</F4>
<F5>Sonar Alt</F5>
<F6>Baro Alt</F6>
<F7>Next WP Alt</F7>
<F8>Nav Throttle</F8>
<F9>Angle boost</F9>
<F10>Manual boost</F10>
<F11>Climb Rate</F11>
<F12>rc3 servo out</F12>
<F13>alt hold int</F13>
<F14>Thr int</F14>
</CTUN>
<PM>
<F1>time</F1>
<F2>gyro sat</F2>
<F3>adc const</F3>
<F4>renorm sqrt</F4>
<F5>renorm blowup</F5>
<F6>fix count</F6>
<F1>Perf Timer</F1>
<F2>Gyro Saturation</F2>
<F3>ADC Constraints</F3>
<F4>DCM renorms</F4>
<F5>DCM Blowups</F5>
<F6>GPS Fix Count</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
@ -71,6 +71,17 @@
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
<CMD>
<F1>Cmmd Total</F1>
<F2>Current #</F2>
<F3>ID</F3>
<F4>options</F4>
<F5></F5>
</CMD>
<MOD>
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>
</MOD>
</AC2>
<!-- -->
<APM>

View File

@ -16,9 +16,9 @@
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
<F4>CH1 out</F4>
<F5>CH2 out</F5>
<F6>CH4 out</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
@ -33,28 +33,28 @@
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>climb rate</F10>
<F11></F11>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
<F1>Roll IN</F1>
<F2>Pitch IN</F2>
<F3>Thr IN</F3>
<F4>Yaw IN</F4>
<F5>Sonar Alt</F5>
<F6>Baro Alt</F6>
<F7>Next WP Alt</F7>
<F8>Nav Throttle</F8>
<F9>Angle boost</F9>
<F10>Manual boost</F10>
<F11>Climb Rate</F11>
<F12>rc3 servo out</F12>
<F13>alt hold int</F13>
<F14>Thr int</F14>
</CTUN>
<PM>
<F1>time</F1>
<F2>gyro sat</F2>
<F3>adc const</F3>
<F4>renorm sqrt</F4>
<F5>renorm blowup</F5>
<F6>fix count</F6>
<F1>Perf Timer</F1>
<F2>Gyro Saturation</F2>
<F3>ADC Constraints</F3>
<F4>DCM renorms</F4>
<F5>DCM Blowups</F5>
<F6>GPS Fix Count</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
@ -71,6 +71,17 @@
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
<CMD>
<F1>Cmmd Total</F1>
<F2>Current #</F2>
<F3>ID</F3>
<F4>options</F4>
<F5></F5>
</CMD>
<MOD>
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>
</MOD>
</AC2>
<!-- -->
<APM>

View File

@ -1,5 +1,14 @@
LOG_BITMASK 4095
SWITCH_ENABLE 0
MAG_ENABLE 0
TRIM_ARSPD_CM 2200
ARSPD_ENABLE 1
ARSP2PTCH_I 0.1
ARSPD_FBW_MAX 30
ARSPD_FBW_MIN 10
KFF_RDDRMIX 0
KFF_PTCHCOMP 0.2
THR_MAX 100
RC2_REV -1
RC1_MAX 2000
RC1_MIN 1000
@ -33,6 +42,5 @@ FLTMODE5 2
FLTMODE6 0
FLTMODE_CH 8
PTCH2SRV_P 2
RLL2SRV_I 0.1
RLL2SRV_I 0
RLL2SRV_P 1.2
INVERTEDFLT_CH 7

View File

@ -0,0 +1,92 @@
<?xml version="1.0"?>
<PropertyList>
<name>rascal-config</name>
<layout>vbox</layout>
<x>40</x>
<y>40</y>
<group>
<layout>hbox</layout>
<empty><stretch>true</stretch></empty>
<text>
<label>Rascal Configuration</label>
</text>
<empty><stretch>true</stretch></empty>
<button>
<pref-width>16</pref-width>
<pref-height>16</pref-height>
<legend></legend>
<default>1</default>
<keynum>27</keynum>
<border>2</border>
<binding>
<command>nasal</command>
<script>rascal.dialog.close()</script>
</binding>
</button>
</group>
<hrule/>
<group>
<layout>table</layout>
<!-- row zero -->
<checkbox>
<row>0</row> <col>0</col>
<halign>left</halign>
<label>External Autopilot Enable</label>
<property>/ugear/settings/ap-enable</property>
<live>true</live>
<binding>
<command>dialog-apply</command>
</binding>
</checkbox>
<!-- row one -->
<checkbox>
<row>1</row> <col>0</col>
<halign>left</halign>
<label>External Turret Control Enable</label>
<property>/ugear/settings/turret-enable</property>
<live>true</live>
<binding>
<command>dialog-apply</command>
</binding>
</checkbox>
<!-- row two -->
<checkbox>
<row>2</row> <col>0</col>
<halign>left</halign>
<label>Smoke</label>
<property>/sim/multiplay/generic/int[0]</property>
<live>true</live>
<binding>
<command>dialog-apply</command>
</binding>
</checkbox>
<!-- row three -->
<checkbox>
<row>3</row> <col>0</col>
<halign>left</halign>
<label>Trajectory Markers</label>
<property>/sim/multiplay/generic/int[1]</property>
<live>true</live>
<binding>
<command>dialog-apply</command>
</binding>
</checkbox>
</group>
<hrule/>
</PropertyList>

View File

@ -0,0 +1,51 @@
<?xml version="1.0"?>
<!-- Generated by Aero-Matic v 0.7
Inputs:
horsepower: 3.8
pitch: fixed
Outputs:
linear-blade-inches: 10.331602005498
-->
<propeller name="Rascal Propeller">
<ixx> 0.00085 </ixx>
<diameter unit="IN"> 18.0 </diameter>
<numblades> 2 </numblades>
<minpitch> 30 </minpitch>
<maxpitch> 30 </maxpitch>
<table name="C_THRUST" type="internal">
<tableData>
0.0 0.0776
0.1 0.0744
0.2 0.0712
0.3 0.0655
0.4 0.0588
0.5 0.0518
0.6 0.0419
0.7 0.0318
0.8 0.0172
1.0 -0.0058
1.4 -0.0549
</tableData>
</table>
<table name="C_POWER" type = "internal">
<tableData>
0.0 0.0902
0.1 0.0893
0.2 0.0880
0.3 0.0860
0.4 0.0810
0.5 0.0742
0.6 0.0681
0.7 0.0572
0.8 0.0467
1.0 0.0167
1.4 -0.0803
</tableData>
</table>
</propeller>

View File

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<!-- Zenoah G-26A -->
<!-- 2.96 hp engine -->
<!-- one horsepower equals 745.69987 Watts -->
<electric_engine name="electric_1mw">
<power unit="WATTS"> 2207.27 </power>
</electric_engine>

Binary file not shown.

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,87 @@
<?xml version="1.0"?>
<PropertyList>
<path>Rascal110-000-013.ac</path>
<model>
<path>Aircraft/Rascal/Models/smokeW.xml</path>
<offsets>
<x-m> 2.0</x-m>
<y-m> 0.0</y-m>
<z-m> 0.0</z-m>
<roll-deg> 0</roll-deg>
<pitch-deg> 0</pitch-deg>
<heading-deg>0</heading-deg>
</offsets>
</model>
<animation>
<type>rotate</type>
<object-name>L_Aileron</object-name>
<property>/surface-positions/left-aileron-pos-norm</property>
<factor>20.0</factor> <!-- fixme -->
<center>
<x-m>0.735</x-m>
<y-m>-0.450</y-m>
<z-m>0.139</z-m>
</center>
<axis>
<x>0.037</x>
<y>1.0</y>
<z>-0.029</z>
</axis>
</animation>
<animation>
<type>rotate</type>
<object-name>R_Aileron</object-name>
<property>/surface-positions/right-aileron-pos-norm</property>
<factor>20.0</factor> <!-- fixme -->
<center>
<x-m>0.735</x-m>
<y-m>0.450</y-m>
<z-m>0.139</z-m>
</center>
<axis>
<x>-0.037</x>
<y>1.0</y>
<z>0.029</z>
</axis>
</animation>
<animation>
<type>rotate</type>
<object-name>Elevator</object-name>
<property>/surface-positions/elevator-pos-norm</property>
<factor>35.0</factor> <!-- fixme -->
<center>
<x-m>1.752</x-m>
<y-m>0.0</y-m>
<z-m>0.051</z-m>
</center>
<axis>
<x>0.0</x>
<y>1.0</y>
<z>0.0</z>
</axis>
</animation>
<animation>
<type>rotate</type>
<object-name>Rudder</object-name>
<property>/surface-positions/rudder-pos-norm</property>
<factor>35.0</factor> <!-- fixme -->
<center>
<x-m>1.752</x-m>
<y-m>0.0</y-m>
<z-m>0.0</z-m>
</center>
<axis>
<x>0.0</x>
<y>0.0</y>
<z>1.0</z>
</axis>
</animation>
</PropertyList>

View File

@ -0,0 +1,30 @@
AC3Db
MATERIAL "ac3dmat9" rgb 0 0 1 amb 0 0 1 emis 0 0 1 spec 0 0 1 shi 0 trans 0
MATERIAL "ac3dmat3" rgb 1 0 0 amb 1 0 0 emis 1 0 0 spec 1 0 0 shi 0 trans 0
OBJECT world
kids 2
OBJECT poly
name "line"
loc 0 0.5 0
numvert 2
0 0.5 0
0 -0.5 0
numsurf 1
SURF 0x22
mat 0
refs 2
0 0 1
1 0 0
kids 0
OBJECT poly
name "line"
numvert 2
0 0 -3
0 0 3
numsurf 1
SURF 0x22
mat 1
refs 2
0 0 1
1 0 0
kids 0

View File

@ -0,0 +1,9 @@
<?xml version="1.0"?>
<!-- Trajectory Marker config file - Lee Elliott -->
<PropertyList>
<path>Trajectory-Marker.ac</path>
</PropertyList>

View File

@ -0,0 +1,102 @@
<?xml version="1.0" encoding="UTF-8"?>
<!-- New version May, 07, 2009 by 102nd-YU-Nitro -->
<PropertyList>
<!-- OSG Particles -->
<particlesystem>
<name>smoke</name>
<offsets>
<x-m> 0.000 </x-m>
<y-m> 0.000 </y-m>
<z-m> -0.000 </z-m>
<roll-deg> 0.000 </roll-deg>
<pitch-deg> 0.000 </pitch-deg>
<heading-deg> 0.000 </heading-deg>
</offsets>
<texture>smoke.png</texture>
<condition>
<property>sim/multiplay/generic/int[0]</property>
</condition>
<emissive>false</emissive>
<lighting>false</lighting>
<align>billboard</align> <!-- billboard / fixed -->
<attach>world</attach> <!-- world / local-->
<placer>
<type>point</type> <!-- sector / segments / point -->
</placer>
<shooter>
<theta-min-deg>10</theta-min-deg>
<theta-max-deg>86</theta-max-deg>
<phi-min-deg>-1.5</phi-min-deg>
<phi-max-deg>8</phi-max-deg>
<speed-mps>
<value>10</value>
<spread>2.5</spread>
</speed-mps>
<rotation-speed>
<x-min-deg-sec>5</x-min-deg-sec>
<y-min-deg-sec>5</y-min-deg-sec>
<z-min-deg-sec>5</z-min-deg-sec>
<x-max-deg-sec>60</x-max-deg-sec>
<y-max-deg-sec>60</y-max-deg-sec>
<z-max-deg-sec>60</z-max-deg-sec>
</rotation-speed>
</shooter>
<counter>
<particles-per-sec>
<value>100</value>
<spread>1</spread>
</particles-per-sec>
</counter>
<particle>
<start>
<color>
<red><value> 0.9 </value></red>
<green><value> 0.9 </value></green>
<blue><value> 0.9 </value></blue>
<alpha><value> 0.3 </value></alpha>
</color>
<size>
<value>0.3</value>
</size>
</start>
<end>
<color>
<red><value> 0.900 </value></red>
<green><value> 0.900 </value></green>
<blue><value> 0.900 </value></blue>
<alpha><value> 0.001 </value></alpha>
</color>
<size>
<value>10.0</value>
</size>
</end>
<life-sec>
<value>60</value>
</life-sec>
<mass-kg>0.001</mass-kg>
<radius-m>1.0</radius-m>
</particle>
<program>
<fluid>air</fluid> <!-- air / water -->
<gravity>false</gravity>
<wind>true</wind>
</program>
</particlesystem>
</PropertyList>

View File

@ -0,0 +1,244 @@
This model is based on the Rascal110 from FlightGear, and adapted for
use in the ArduPilot test system. Many thanks to all who have
contributed!
This information has not been updated for the Rascal, please ignore, we
are still at pre-pre-pre-alpha with this model!
PIPER J3 CUB PERFORMANCE DATA
=============================
[This information is copied from the 1946 J3C-65 owner's handbook.]
FLYING HINTS
The Piper Cub Special represents more than 15 years of diligent
aircraft engineering and manufacturing experience. Its simplicity of
design and construction, its low operating and maintenance costs, its
inherent stability, ruggedness, and its outstanding safety and ease of
flying, have made it the most popular airplane in aviation history.
The Piper Cub Special is the time-tested product of millions of hours
of flying under all conceivable conditions both in the military and in
peace time.
There are hints on starting, flying, stopping, and other related
topics that are important to the owner who wants to conserve his
airplane -- keep it in maximum airworthy condition -- and enjoy a full
measure of flying satisfaction.
First, each pilot should become familiar enough with his Piper Cub
Special that he can accomplish a satisfactory pre-flight inspection.
This check is simple and requires only a few minutes. See Section IX
for check list. Daily check of airplane prior to flight should be the
first in a number of safe flying habits the pilot should acquire.
A. BEFORE STARTING ENGINE
(1) Make routine check of gasoline supply. Visible fuel gauge is
integral part of gas tank cap; it will not show number of gallons but
will show proportion of fuel in tank by length of rod which extends
upward from cap. A full tank of 12 U.S. gallons will be indicated by
11 inches of rod extending beyond cap. Keep gas gauge rod clean and
smooth with crocus cloth for accuracy and freedom of movement.
(2) Check oil level in engine sump by removing oil cap and gauge. Oil
stick should indicate oil level up to index mark of 4 quarts.
(3) Check freedom of movement of flight and engine controls.
B. STARTING ENGINE
(1) Chock wheels, or have occupant who is familiar with controls set
brakes in cabin.
(2) Ignition switch OFF. Verify.
(3) Set throttle approximately 1/10 open.
(4) Push fuel shut-off ON.
(5) Turn propeller through several times.
(6) Turn ignition switch ON.
(7) Start engine by pulling propeller through with a snap.
CAUTION -- Always handle propeller as if switch were "ON." Stand as
far in front of propeller as possible. Use both hands and grasp one
blad approximately midway from tip. Do not overgrasp blade. Do not
wear long, loose clothing. Make sure footing is sure to preclude
possibility of feet slipping.
(8) If engine does not start, turn switch OFF. Turn primer knob to
unlock, pull out, pump three or four times, then reseat primer and
lock by turning in opposite direction. In extremely cold weather a
few strokes of the primer as the engine starts will enable it to keep
running. NOTE -- Avoid excessive priming as it causes raw gasoline to
wash lubricating oil from engine cylinder walls. Do not prime warm
engine.
(9) Repeat starting procedures 6, 7.
(10) If engine loads up and refuses to start, turn ignition switch
"OFF,", open throttle wide and turn propeller through backwards
several times to unload excessive gas mixture in cylinders. Then
close throttle and repeat starting procedure.
C. ENGINE WARM-UP
(1) As soon as engine starts, advance throttle slightly to idle at 700
R.P.M. Check engine instruments. If oil pressure gauge does not
indicate pressure within 30 seconds, stop engine immediately, check
and correct trouble before any further operation. Oil temperature
during operating should not rise above 200° F. and oil pressure should
not fall below 30 pounds. With engine warm, idling speed should be
550-600 R.P.M.
(2) Rev engine up to 2100 R.P.M. on both magnetos. Switch to LEFT and
RIGHT magnetos. R.P.M. drop should not be over 75 R.P.M. CAUTION
--Do not operate engine on either single magneto for more than 30
seconds at a time, as this tends to foul the non-operating spark plugs
in the ignition circuit of the magneto that is switched off.
D. STOPPING ENGINE
(1) Never cut switch immediately after landing as this causes engine
to cool too rapidly.
(2) Idle engine, especially in high temperature operating conditions,
for several minutes. It is advisable to switch to each magneto for 30
second intervals to allow gradual cooling of engine. This helps to
prevent overheating of spark plug insulators and will lessen tendency
for "after-firing."
(3) Check for carburetor heat OFF during idling.
E. TAXIING
(1) Open throttle to start airplane in motion; then close throttle to
a setting sufficient to keep airplane rolling. Do not keep throttle
advanced so that it is necessary to control taxi speed of airplane
with brakes. This causes unnecessary wear and tear on brakes and
tires.
(2) Taxi slowly (speed of a fast walk) controlling direction with
rudder which is connected to a steerable tail wheel. Use brakes only
for positive, precision ground control when necessary.
(3) Taxi upwind with stick back; downwind with stick foreward. When
ground winds are in excess of 15 M.P.H., turn into wind using ailerons
in direction of turn; apply ailerons away from the turn when turning
downwind. This procedure helps to prevent the wind "picking up" a
wing during windy, gusty conditions. Always make ground turns slowly.
F. GENERAL FLYING
(1) For takeoff use full throttle, heading into wind. Airplane loaded
will become airborne at approximately 39 M.P.H. Best climb speed is
an indicated 55 M.P.H.
(2) Indicated R.P.M. for cruising speed of 73 M.P.H. is 2150.
Take-off R.P.M. is 2300. Do not fly at full throttle over 3 minutes.
(3) Use CARBURETOR AIR HEAT when engine runs "rough" and tachometer
shows drop in R.P.M. which may be due to ice forming in carburetor.
Tachometer should recover to within 50 R.P.M. below normal when using
carburetor heat. Push heater to "OFF" position, and if icing
condition has been cleared, R.P.M. should return to normal. Continued
use of carburetor heat will only cause increased fuel consumption and
loss of power.
(4) Maximum permissible diving speed is 122 M.P.H.
G. APPROACH AND LANDING
(1) Push carburetor heat ON prior to throttling back for glide, or for
any other flight maneuver.
(2) Glide between 50-60 M.P.H. depending upon loading of airplane and
gust conditions.
NOTE -- "Clear" engine by opening throttle gently, every 200-250 feet
of descent during a long glide so that engine temperature will be
maintained.
Throttle action on the part of the pilot should be smooth and gentle
at all times.
H. PARKING AND MOORING
(1) After termination of flight, enter flying time in aircraft and
engine log books.
(2) Turn ignition and fuel OFF.
(3) Chcok the wheels of airplane.
(4) If airplane is not to be flown for some time, it should be
hangared or tied down. Use good quality 1/2" - 5/8" diameter rope.
Secure to lift assist handle at aft end of fuselage; also at upper end
of both front wing lift struts where they attach to wing. Make sure
that rope passes between aileron cable and lift strut. Mooring ropes,
when airplane is tied down, should have no slack.
(5) Lock aileron and elevator controls by wrapping front seat belt
completely around rear control stick, tighten and buckle.
(6) Under excessively wind conditions, airplane should be tailed into
wind for mooring.
[Here is my older information.]
These are the only numbers I could find. They are for a J3 Cub with
an 85HP engine rather than 65 hp, so some adjustments may be
necessary. The source is
http://www.evergreenfs.com/planedata.htm
Speeds
------
Best rate of climb (Vy): 65 mph (57 kt)
Best angle of climb (Vx): 55 mph (48 kt)
Cruise: 70 mph (61 kt)
Never-exceed (Vne): 122 mph (106 kt)
Best Glide (Vglide): 60 mph (52 kt)
Stall (Vs): 38 mph (33 kt)
Maneuvering (Va): 70 mph (61 kt)
Approach: 50-60 mph (44-52 kt)
Power
-----
Take off: full
Climb: 50 rpm below full
Cruise: 2300 rpm
Approach: 1200 rpm
Practice stalls: 1200 rpm
Distances
---------
Take-off: 450-800 ft
Landing: 200-800 ft
Fuel
----
Total fuel: 12 gal US
Usable fuel: 12 gal US
Grade: 80/87
GPH: 5 gal US/hr

View File

@ -0,0 +1,23 @@
<?xml version="1.0" encoding="UTF-8"?>
<PropertyList>
<key n="9">
<name>Ctrl-I</name>
<desc>Show configuration dialog</desc>
<binding>
<command>nasal</command>
<script>rascal.dialog.toggle()</script>
</binding>
</key>
<key n="83">
<name>S</name>
<desc>Toggle smoke</desc>
<binding>
<command>property-toggle</command>
<property>sim/multiplay/generic/int[0]</property>
</binding>
</key>
</PropertyList>

View File

@ -0,0 +1,25 @@
<?xml version="1.0"?>
<PropertyList>
<submodel>
<name>trajectory marker</name>
<model>Aircraft/Rascal/Models/Trajectory-Marker.xml</model>
<trigger>/sim/multiplay/generic/int[1]</trigger>
<speed>0</speed>
<repeat>true</repeat>
<delay>0.75</delay>
<count>-1</count>
<x-offset>-0.5</x-offset>
<y-offset>0.0</y-offset>
<z-offset>-0.08</z-offset>
<yaw-offset>0.0</yaw-offset>
<pitch-offset>0.0</pitch-offset>
<eda>1000000000.00</eda>
<life>600</life>
<buoyancy>32</buoyancy>
<wind>false</wind>
<aero-stabilised>false</aero-stabilised>
</submodel>
</PropertyList>

View File

@ -0,0 +1,527 @@
<?xml version="1.0"?>
<?xml-stylesheet href="http://jsbsim.sourceforge.net/JSBSim.xsl" type="text/xsl"?>
<fdm_config name="rascal" version="2.0" release="BETA"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> Author Name </author>
<filecreationdate> Creation Date </filecreationdate>
<version> Version </version>
<description> Models a rascal </description>
</fileheader>
<metrics>
<wingarea unit="FT2"> 10.57 </wingarea>
<wingspan unit="FT"> 9.17 </wingspan>
<chord unit="FT"> 1.15 </chord>
<htailarea unit="FT2"> 1.69 </htailarea>
<htailarm unit="FT"> 3.28 </htailarm>
<vtailarea unit="FT2"> 1.06 </vtailarea>
<vtailarm unit="FT"> 0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 37.4 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 20 </x>
<y> 0 </y>
<z> 5 </z>
</location>
<location name="VRP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</metrics>
<mass_balance>
<ixx unit="SLUG*FT2"> 1.95 </ixx>
<iyy unit="SLUG*FT2"> 1.55 </iyy>
<izz unit="SLUG*FT2"> 1.91 </izz>
<ixy unit="SLUG*FT2"> 0 </ixy>
<ixz unit="SLUG*FT2"> 0 </ixz>
<iyz unit="SLUG*FT2"> 0 </iyz>
<emptywt unit="LBS"> 13 </emptywt>
<location name="CG" unit="IN">
<x> 36.4 </x>
<y> 0 </y>
<z> 4 </z>
</location>
</mass_balance>
<ground_reactions>
<contact type="BOGEY" name="LEFT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> -9.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="BOGEY" name="RIGHT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> 9.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
<contact type="BOGEY" name="TAIL_LG">
<location unit="IN">
<x> 68.9 </x>
<y> 0 </y>
<!-- this sets the position of the tail wheel much
lower than it should be, so that we start with
zero pitch, which makes for a better simulation
of ground start on the accelerometers/gyros in
ArduPlane -->
<z> -7.8 </z>
</location>
<static_friction> 1.0 </static_friction>
<dynamic_friction> 0.8 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
<max_steer unit="DEG"> 360.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
</ground_reactions>
<propulsion>
<engine file="Zenoah_G-26A">
<location unit="IN">
<x> 36 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<orient unit="DEG">
<roll> 0.0 </roll>
<pitch> 0 </pitch>
<yaw> 0 </yaw>
</orient>
<feed>0</feed>
<thruster file="18x8">
<location unit="IN">
<x> 1 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<orient unit="DEG">
<roll> 0.0 </roll>
<pitch> 0.0 </pitch>
<yaw> 0.0 </yaw>
</orient>
<p_factor>1.0</p_factor>
</thruster>
</engine>
<tank type="FUEL"> <!-- Tank number 0 -->
<location unit="IN">
<x> 36.36 </x>
<y> 0 </y>
<z> -1.89375 </z>
</location>
<capacity unit="LBS"> 1.5 </capacity>
<contents unit="LBS"> 1.5 </contents>
</tank>
</propulsion>
<flight_control name="FCS: rascal">
<channel name="All">
<summer name="Pitch Trim Sum">
<input>fcs/elevator-cmd-norm</input>
<input>fcs/pitch-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Elevator Control">
<input>fcs/pitch-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.3</max>
</range>
<output>fcs/elevator-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Elevator Normalized">
<input>fcs/elevator-pos-rad</input>
<domain>
<min>-0.3</min>
<max> 0.3</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/elevator-pos-norm</output>
</aerosurface_scale>
<summer name="Roll Trim Sum">
<input>fcs/aileron-cmd-norm</input>
<input>fcs/roll-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Left Aileron Control">
<input>fcs/roll-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/left-aileron-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Right Aileron Control">
<input>-fcs/roll-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/right-aileron-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Left aileron Normalized">
<input>fcs/left-aileron-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/left-aileron-pos-norm</output>
</aerosurface_scale>
<aerosurface_scale name="Right aileron Normalized">
<input>fcs/right-aileron-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/right-aileron-pos-norm</output>
</aerosurface_scale>
<summer name="Rudder Command Sum">
<input>fcs/rudder-cmd-norm</input>
<input>fcs/yaw-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Rudder Control">
<input>fcs/rudder-command-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/rudder-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Rudder Normalized">
<input>fcs/rudder-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/rudder-pos-norm</output>
</aerosurface_scale>
</channel>
</flight_control>
<aerodynamics>
<axis name="DRAG">
<function name="aero/coefficient/CD0">
<description>Drag_at_zero_lift</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/alpha-rad</independentVar>
<tableData>
-1.5700 1.5000
-0.2600 0.0560
0.0000 0.0280
0.2600 0.0560
1.5700 1.5000
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CDi">
<description>Induced_drag</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>aero/cl-squared</property>
<value>0.0400</value>
</product>
</function>
<function name="aero/coefficient/CDbeta">
<description>Drag_due_to_sideslip</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/beta-rad</independentVar>
<tableData>
-1.5700 1.2300
-0.2600 0.0500
0.0000 0.0000
0.2600 0.0500
1.5700 1.2300
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CDde">
<description>Drag_due_to_Elevator_Deflection</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>fcs/elevator-pos-norm</property>
<value>0.0300</value>
</product>
</function>
</axis>
<axis name="SIDE">
<function name="aero/coefficient/CYb">
<description>Side_force_due_to_beta</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>aero/beta-rad</property>
<value>-1.0000</value>
</product>
</function>
</axis>
<axis name="LIFT">
<function name="aero/coefficient/CLalpha">
<description>Lift_due_to_alpha</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/alpha-rad</independentVar>
<tableData>
-0.2000 -0.7500
0.0000 0.2500
0.2300 1.4000
0.6000 0.7100
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CLde">
<description>Lift_due_to_Elevator_Deflection</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>fcs/elevator-pos-rad</property>
<value>0.2000</value>
</product>
</function>
</axis>
<axis name="ROLL">
<function name="aero/coefficient/Clb">
<description>Roll_moment_due_to_beta</description>
<!-- aka dihedral effect -->
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/beta-rad</property>
<value>-0.1000</value>
</product>
</function>
<function name="aero/coefficient/Clp">
<description>Roll_moment_due_to_roll_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/p-aero-rad_sec</property>
<value>-0.4000</value>
</product>
</function>
<function name="aero/coefficient/Clr">
<description>Roll_moment_due_to_yaw_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/r-aero-rad_sec</property>
<value>0.1500</value>
</product>
</function>
<function name="aero/coefficient/Clda">
<description>Roll_moment_due_to_aileron</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/left-aileron-pos-rad</property>
<table>
<independentVar>velocities/mach</independentVar>
<tableData>
0.0000 0.1300
2.0000 0.0570
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/Cldr">
<description>Roll_moment_due_to_rudder</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/rudder-pos-rad</property>
<value>0.0100</value>
</product>
</function>
</axis>
<axis name="PITCH">
<function name="aero/coefficient/Cmalpha">
<description>Pitch_moment_due_to_alpha</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/alpha-rad</property>
<value>-0.5000</value>
</product>
</function>
<function name="aero/coefficient/Cmde">
<description>Pitch_moment_due_to_elevator</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>fcs/elevator-pos-rad</property>
<table>
<independentVar>velocities/mach</independentVar>
<tableData>
0.0000 -0.5000 <!-- was -1.1 -->
2.0000 -0.2750
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/Cmq">
<description>Pitch_moment_due_to_pitch_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/ci2vel</property>
<property>velocities/q-aero-rad_sec</property>
<value>-12.0000</value>
</product>
</function>
<function name="aero/coefficient/Cmadot">
<description>Pitch_moment_due_to_alpha_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/ci2vel</property>
<property>aero/alphadot-rad_sec</property>
<value>-7.0000</value>
</product>
</function>
</axis>
<axis name="YAW">
<function name="aero/coefficient/Cnb">
<description>Yaw_moment_due_to_beta</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/beta-rad</property>
<value>0.1200</value>
</product>
</function>
<function name="aero/coefficient/Cnr">
<description>Yaw_moment_due_to_yaw_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/r-aero-rad_sec</property>
<value>-0.1500</value>
</product>
</function>
<function name="aero/coefficient/Cndr">
<description>Yaw_moment_due_to_rudder</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/rudder-pos-rad</property>
<value>-0.0500</value>
</product>
</function>
<function name="aero/coefficient/Cnda">
<description>Adverse_yaw</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/left-aileron-pos-rad</property>
<value>-0.0300</value>
</product>
</function>
<function name="aero/coefficient/Cndi">
<description>Yaw_moment_due_to_tail_incidence</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<value>0.0007</value>
</product>
</function>
</axis>
</aerodynamics>
</fdm_config>

View File

@ -0,0 +1,172 @@
<?xml version="1.0"?>
<!--
************************************************************************
Rascal 110 R/C airplane config. This files ties together all the components
used by FGFS to represent the Rascal 110 (by Sig Mfg) including the flight
dynamics model, and external 3D model.
************************************************************************
-->
<PropertyList>
<sim>
<description>Rascal 110 (R/C)</description>
<author>Lee Elliot (3D) Dave Culp (JSBsim dynamics) and Curt Olson</author>
<aircraft-version>0.1</aircraft-version>
<model-hz>400</model-hz>
<startup>
<splash-texture>Aircraft/Rascal/Rascal110-splash.rgb</splash-texture>
</startup>
<flight-model>jsb</flight-model>
<aero>Rascal110-JSBSim</aero>
<fuel-fraction>0.8</fuel-fraction>
<systems>
<autopilot>
<path>Aircraft/Rascal/Systems/110-autopilot.xml</path>
</autopilot>
<electrical>
<path>Aircraft/Rascal/Systems/electrical.xml</path>
</electrical>
</systems>
<sound>
<path>Aircraft/Generic/generic-sound.xml</path>
</sound>
<panel>
<visibility archive="n">false</visibility>
</panel>
<model>
<path archive="y">Aircraft/Rascal/Models/Rascal110.xml</path>
</model>
<view>
<internal archive="y">true</internal>
<config>
<x-offset-m archive="y">0.0</x-offset-m>
<y-offset-m archive="y">-0.15</y-offset-m>
<z-offset-m archive="y">0.9</z-offset-m>
<pitch-offset-deg>0</pitch-offset-deg>
</config>
</view>
<submodels>
<serviceable type="bool">1</serviceable>
<path>Aircraft/Rascal/Rascal-submodels.xml</path>
</submodels>
<view n="1">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<view n="2">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<view n="3">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<view n="4">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<view n="5">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<view n="6">
<config>
<target-z-offset-m archive="y" type="double">0.5</target-z-offset-m>
</config>
</view>
<multiplay>
<chat_display>1</chat_display>
<generic>
<int type="bool">0</int> <!-- smoke -->
<int type="bool">0</int> <!-- trajectory markers -->
</generic>
</multiplay>
<help>
<title>Rascal 110 (Sig Mfg)</title>
<line>Cruise speed: 60 kts</line>
<line>Never-exceed (Vne): 85 kts</line>
<line>Best Glide (Vglide): 20 kts</line>
<line>Maneuvering (Va): 50 kts</line>
<line>Approach speed: 20-25 kts</line>
<line>Stall speed (Vs): 15 kts</line>
</help>
</sim>
<nasal>
<rascal>
<file>Aircraft/Rascal/Systems/main.nas</file>
<file>Aircraft/Rascal/Systems/airdata.nas</file>
<file>Aircraft/Rascal/Systems/ugear.nas</file>
<script>
setlistener("/sim/signals/fdm-initialized", func {
var left = screen.display.new(20, 10);
left.add("/surface-positions/right-aileron-pos-norm");
left.add("/surface-positions/elevator-pos-norm");
left.add("/surface-positions/rudder-pos-norm");
left.add("/engines/engine/rpm");
var right = screen.display.new(-250, 20);
right.add("/orientation/pitch-deg");
right.add("/orientation/roll-deg");
right.add("/position/altitude-agl-ft");
right.add("/velocities/airspeed-kt");
});
</script>
</rascal>
</nasal>
<yasim>
<Rascal110>
<pilot-lb>2</pilot-lb>
</Rascal110>
</yasim>
<input>
<keyboard include="Rascal-keyboard.xml"/>
</input>
<controls>
<flight>
<aileron-trim>-0.01</aileron-trim> <!-- fixed -->
<elevator-trim>0.00</elevator-trim> <!-- controllable -->
<rudder-trim>0.00</rudder-trim> <!-- fixed -->
</flight>
<engines>
<engine n="0">
<magnetos>3</magnetos>
</engine>
</engines>
<smoke alias="/sim/multiplay/generic/int[0]"/>
<trajectory-markers alias="/sim/multiplay/generic/int[1]"/>
</controls>
<engines>
<engine>
<rpm type="double">700</rpm>
</engine>
</engines>
</PropertyList>

View File

@ -0,0 +1,522 @@
<?xml version="1.0"?>
<?xml-stylesheet href="http://jsbsim.sourceforge.net/JSBSim.xsl" type="text/xsl"?>
<fdm_config name="rascal" version="2.0" release="BETA"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> Author Name </author>
<filecreationdate> Creation Date </filecreationdate>
<version> Version </version>
<description> Models a rascal </description>
</fileheader>
<metrics>
<wingarea unit="FT2"> 10.57 </wingarea>
<wingspan unit="FT"> 9.17 </wingspan>
<chord unit="FT"> 1.15 </chord>
<htailarea unit="FT2"> 1.69 </htailarea>
<htailarm unit="FT"> 3.28 </htailarm>
<vtailarea unit="FT2"> 1.06 </vtailarea>
<vtailarm unit="FT"> 0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 37.4 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 20 </x>
<y> 0 </y>
<z> 5 </z>
</location>
<location name="VRP" unit="IN">
<x> 0 </x>
<y> 0 </y>
<z> 0 </z>
</location>
</metrics>
<mass_balance>
<ixx unit="SLUG*FT2"> 1.95 </ixx>
<iyy unit="SLUG*FT2"> 1.55 </iyy>
<izz unit="SLUG*FT2"> 1.91 </izz>
<ixy unit="SLUG*FT2"> 0 </ixy>
<ixz unit="SLUG*FT2"> 0 </ixz>
<iyz unit="SLUG*FT2"> 0 </iyz>
<emptywt unit="LBS"> 13 </emptywt>
<location name="CG" unit="IN">
<x> 36.4 </x>
<y> 0 </y>
<z> 4 </z>
</location>
</mass_balance>
<ground_reactions>
<contact type="BOGEY" name="LEFT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> -9.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 120 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 20 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> LEFT </brake_group>
<retractable>0</retractable>
</contact>
<contact type="BOGEY" name="RIGHT_MLG">
<location unit="IN">
<x> 33.1 </x>
<y> 9.9 </y>
<z> -13.1 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 120 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 20 </damping_coeff>
<max_steer unit="DEG"> 0.0 </max_steer>
<brake_group> RIGHT </brake_group>
<retractable>0</retractable>
</contact>
<contact type="BOGEY" name="TAIL_LG">
<location unit="IN">
<x> 68.9 </x>
<y> 0 </y>
<z> -6.6 </z>
</location>
<static_friction> 0.8 </static_friction>
<dynamic_friction> 0.5 </dynamic_friction>
<rolling_friction> 0.02 </rolling_friction>
<spring_coeff unit="LBS/FT"> 24 </spring_coeff>
<damping_coeff unit="LBS/FT/SEC"> 20 </damping_coeff>
<max_steer unit="DEG"> 360.0 </max_steer>
<brake_group> NONE </brake_group>
<retractable>0</retractable>
</contact>
</ground_reactions>
<propulsion>
<engine file="Zenoah_G-26A">
<location unit="IN">
<x> 36 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<orient unit="DEG">
<roll> 0.0 </roll>
<pitch> 0 </pitch>
<yaw> 0 </yaw>
</orient>
<feed>0</feed>
<thruster file="18x8">
<location unit="IN">
<x> 1 </x>
<y> 0 </y>
<z> 0 </z>
</location>
<orient unit="DEG">
<roll> 0.0 </roll>
<pitch> 0.0 </pitch>
<yaw> 0.0 </yaw>
</orient>
<p_factor>1.0</p_factor>
</thruster>
</engine>
<tank type="FUEL"> <!-- Tank number 0 -->
<location unit="IN">
<x> 36.36 </x>
<y> 0 </y>
<z> -1.89375 </z>
</location>
<capacity unit="LBS"> 1.5 </capacity>
<contents unit="LBS"> 1.5 </contents>
</tank>
</propulsion>
<flight_control name="FCS: rascal">
<channel name="All">
<summer name="Pitch Trim Sum">
<input>fcs/elevator-cmd-norm</input>
<input>fcs/pitch-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Elevator Control">
<input>fcs/pitch-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.3</max>
</range>
<output>fcs/elevator-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Elevator Normalized">
<input>fcs/elevator-pos-rad</input>
<domain>
<min>-0.3</min>
<max> 0.3</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/elevator-pos-norm</output>
</aerosurface_scale>
<summer name="Roll Trim Sum">
<input>fcs/aileron-cmd-norm</input>
<input>fcs/roll-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Left Aileron Control">
<input>fcs/roll-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/left-aileron-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Right Aileron Control">
<input>-fcs/roll-trim-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/right-aileron-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Left aileron Normalized">
<input>fcs/left-aileron-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/left-aileron-pos-norm</output>
</aerosurface_scale>
<aerosurface_scale name="Right aileron Normalized">
<input>fcs/right-aileron-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/right-aileron-pos-norm</output>
</aerosurface_scale>
<summer name="Rudder Command Sum">
<input>fcs/rudder-cmd-norm</input>
<input>fcs/yaw-trim-cmd-norm</input>
<clipto>
<min>-1</min>
<max>1</max>
</clipto>
</summer>
<aerosurface_scale name="Rudder Control">
<input>fcs/rudder-command-sum</input>
<range>
<min>-0.35</min>
<max>0.35</max>
</range>
<output>fcs/rudder-pos-rad</output>
</aerosurface_scale>
<aerosurface_scale name="Rudder Normalized">
<input>fcs/rudder-pos-rad</input>
<domain>
<min>-0.35</min>
<max> 0.35</max>
</domain>
<range>
<min>-1</min>
<max> 1</max>
</range>
<output>fcs/rudder-pos-norm</output>
</aerosurface_scale>
</channel>
</flight_control>
<aerodynamics>
<axis name="DRAG">
<function name="aero/coefficient/CD0">
<description>Drag_at_zero_lift</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/alpha-rad</independentVar>
<tableData>
-1.5700 1.5000
-0.2600 0.0560
0.0000 0.0280
0.2600 0.0560
1.5700 1.5000
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CDi">
<description>Induced_drag</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>aero/cl-squared</property>
<value>0.0400</value>
</product>
</function>
<function name="aero/coefficient/CDbeta">
<description>Drag_due_to_sideslip</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/beta-rad</independentVar>
<tableData>
-1.5700 1.2300
-0.2600 0.0500
0.0000 0.0000
0.2600 0.0500
1.5700 1.2300
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CDde">
<description>Drag_due_to_Elevator_Deflection</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>fcs/elevator-pos-norm</property>
<value>0.0300</value>
</product>
</function>
</axis>
<axis name="SIDE">
<function name="aero/coefficient/CYb">
<description>Side_force_due_to_beta</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>aero/beta-rad</property>
<value>-1.0000</value>
</product>
</function>
</axis>
<axis name="LIFT">
<function name="aero/coefficient/CLalpha">
<description>Lift_due_to_alpha</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<table>
<independentVar>aero/alpha-rad</independentVar>
<tableData>
-0.2000 -0.7500
0.0000 0.2500
0.2300 1.4000
0.6000 0.7100
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/CLde">
<description>Lift_due_to_Elevator_Deflection</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>fcs/elevator-pos-rad</property>
<value>0.2000</value>
</product>
</function>
</axis>
<axis name="ROLL">
<function name="aero/coefficient/Clb">
<description>Roll_moment_due_to_beta</description>
<!-- aka dihedral effect -->
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/beta-rad</property>
<value>-0.1000</value>
</product>
</function>
<function name="aero/coefficient/Clp">
<description>Roll_moment_due_to_roll_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/p-aero-rad_sec</property>
<value>-0.4000</value>
</product>
</function>
<function name="aero/coefficient/Clr">
<description>Roll_moment_due_to_yaw_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/r-aero-rad_sec</property>
<value>0.1500</value>
</product>
</function>
<function name="aero/coefficient/Clda">
<description>Roll_moment_due_to_aileron</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/left-aileron-pos-rad</property>
<table>
<independentVar>velocities/mach</independentVar>
<tableData>
0.0000 0.1300
2.0000 0.0570
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/Cldr">
<description>Roll_moment_due_to_rudder</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/rudder-pos-rad</property>
<value>0.0100</value>
</product>
</function>
</axis>
<axis name="PITCH">
<function name="aero/coefficient/Cmalpha">
<description>Pitch_moment_due_to_alpha</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/alpha-rad</property>
<value>-0.5000</value>
</product>
</function>
<function name="aero/coefficient/Cmde">
<description>Pitch_moment_due_to_elevator</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>fcs/elevator-pos-rad</property>
<table>
<independentVar>velocities/mach</independentVar>
<tableData>
0.0000 -0.5000 <!-- was -1.1 -->
2.0000 -0.2750
</tableData>
</table>
</product>
</function>
<function name="aero/coefficient/Cmq">
<description>Pitch_moment_due_to_pitch_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/ci2vel</property>
<property>velocities/q-aero-rad_sec</property>
<value>-12.0000</value>
</product>
</function>
<function name="aero/coefficient/Cmadot">
<description>Pitch_moment_due_to_alpha_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/cbarw-ft</property>
<property>aero/ci2vel</property>
<property>aero/alphadot-rad_sec</property>
<value>-7.0000</value>
</product>
</function>
</axis>
<axis name="YAW">
<function name="aero/coefficient/Cnb">
<description>Yaw_moment_due_to_beta</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/beta-rad</property>
<value>0.1200</value>
</product>
</function>
<function name="aero/coefficient/Cnr">
<description>Yaw_moment_due_to_yaw_rate</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>aero/bi2vel</property>
<property>velocities/r-aero-rad_sec</property>
<value>-0.1500</value>
</product>
</function>
<function name="aero/coefficient/Cndr">
<description>Yaw_moment_due_to_rudder</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/rudder-pos-rad</property>
<value>-0.0500</value>
</product>
</function>
<function name="aero/coefficient/Cnda">
<description>Adverse_yaw</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<property>fcs/left-aileron-pos-rad</property>
<value>-0.0300</value>
</product>
</function>
<function name="aero/coefficient/Cndi">
<description>Yaw_moment_due_to_tail_incidence</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<property>metrics/bw-ft</property>
<value>0.0007</value>
</product>
</function>
</axis>
</aerodynamics>
</fdm_config>

Binary file not shown.

View File

@ -0,0 +1,767 @@
<?xml version="1.0"?>
<!-- Generic Autopilot Configuration -->
<!-- Each component is evaluated in the order specified. You can make up -->
<!-- property names to pass the result of one component on to a subsequent -->
<!-- component. -->
<PropertyList>
<!-- =============================================================== -->
<!-- Roll Axis Modes -->
<!-- =============================================================== -->
<!-- Wing leveler -->
<pid-controller>
<name>Wing Leveler (Turn Coordinator based)</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>wing-leveler</value>
</enable>
<input>
<prop>/orientation/roll-deg</prop>
</input>
<reference>
<value>0.0</value>
</reference>
<output>
<prop>/controls/flight/aileron</prop>
</output>
<config>
<Kp>0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.01</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Bank hold -->
<pid-controller>
<name>Bank Hold</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>bank-hold</value>
</enable>
<input>
<prop>/orientation/roll-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-bank-deg</prop>
</reference>
<output>
<prop>/controls/flight/aileron</prop>
</output>
<config>
<Kp>0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.01</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Heading Bug Hold. 2 stage cascade controller. -->
<!-- Stage #1 sets target roll based on diff between current heading -->
<!-- and heading bug. -->
<pid-controller>
<name>Heading Bug Hold (DG based) Stage 1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>dg-heading-hold</value>
</enable>
<input>
<prop>/autopilot/internal/fdm-heading-bug-error-deg</prop>
</input>
<reference>
<value>0.0</value>
</reference>
<output>
<prop>/autopilot/internal/target-roll-deg</prop>
</output>
<config>
<Kp>-0.1</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>10.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-20.0</u_min> <!-- minimum output clamp -->
<u_max>20.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Stage #2 drives the ailerons to achieve the desired roll deg. -->
<pid-controller>
<name>Heading Bug Hold (DG based) Stage 2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>dg-heading-hold</value>
</enable>
<input>
<prop>/orientation/roll-deg</prop>
</input>
<reference>
<prop>/autopilot/internal/target-roll-deg</prop>
</reference>
<output>
<prop>/controls/flight/aileron</prop>
</output>
<config>
<Kp>0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.01</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- True Heading hold. 2 stage cascade controller. -->
<!-- Stage #1 sets target roll based on diff between current heading -->
<!-- and target heading. -->
<pid-controller>
<name>True Heading Hold (DG based) Stage 1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>true-heading-hold</value>
</enable>
<input>
<prop>/autopilot/internal/true-heading-error-deg</prop>
</input>
<reference>
<value>0.0</value>
</reference>
<output>
<prop>/autopilot/internal/target-roll-deg</prop>
</output>
<config>
<Kp>-1.0</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>10.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-20.0</u_min> <!-- minimum output clamp -->
<u_max>20.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Stage #2 drives the ailerons to achieve the desired roll deg. -->
<pid-controller>
<name>True Heading Hold (DG based) Stage 2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>true-heading-hold</value>
</enable>
<input>
<prop>/orientation/roll-deg</prop>
</input>
<reference>
<prop>/autopilot/internal/target-roll-deg</prop>
</reference>
<output>
<prop>/controls/flight/aileron</prop>
</output>
<config>
<Kp>0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.01</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Nav1 hold. 2 stage cascade controller. -->
<!-- Stage #1 sets target roll based on diff between current heading -->
<!-- and target heading. -->
<pid-controller>
<name>Nav1 Hold Stage 1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>nav1-hold</value>
</enable>
<input>
<prop>/autopilot/internal/nav1-heading-error-deg</prop>
</input>
<reference>
<value>0.0</value>
</reference>
<output>
<prop>/autopilot/internal/target-roll-deg</prop>
</output>
<config>
<Kp>-1.0</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>10.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-20.0</u_min> <!-- minimum output clamp -->
<u_max>20.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Stage #2 drives the ailerons to achieve the desired roll deg. -->
<pid-controller>
<name>Nav1 Hold Stage 2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/heading</prop>
<value>nav1-hold</value>
</enable>
<input>
<prop>/orientation/roll-deg</prop>
</input>
<reference>
<prop>/autopilot/internal/target-roll-deg</prop>
</reference>
<output>
<prop>/controls/flight/aileron</prop>
</output>
<config>
<Kp>0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.01</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- =============================================================== -->
<!-- Pitch Axis Modes -->
<!-- =============================================================== -->
<!-- Simple pitch hold -->
<pid-controller>
<name>Pitch hold</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>pitch-hold</value>
</enable>
<input>
<prop>/orientation/pitch-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-pitch-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Simple pitch hold with yoke -->
<pid-controller>
<name>Pitch hold w/ yoke</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>pitch-hold-yoke</value>
</enable>
<input>
<prop>/orientation/pitch-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-pitch-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Simple angle of attack hold -->
<pid-controller>
<name>AOA hold</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>aoa-hold</value>
</enable>
<input>
<prop>/orientation/alpha-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-aoa-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Altitude hold. 3 stage cascade controller. -->
<!-- Stage #1 sets target rate of climb based on diff between current alt -->
<!-- and target altitude. -->
<pi-simple-controller>
<name>Altitude Hold (Altimeter based) Stage 1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>altitude-hold</value>
</enable>
<input>
<prop>/position/altitude-ft</prop>
</input>
<reference>
<prop>/autopilot/settings/target-altitude-ft</prop>
</reference>
<output>
<prop>/autopilot/internal/target-climb-rate-fps</prop>
</output>
<config>
<Kp>0.3</Kp> <!-- proportional gain -->
<Ki>0.0</Ki> <!-- integral gain -->
<u_min>-8.33</u_min> <!-- minimum output clamp -->
<u_max>8.33</u_max> <!-- maximum output clamp -->
</config>
</pi-simple-controller>
<!-- Stage #2 drives the target-pitch to achieve the desired climb -->
<!-- rate. -->
<pid-controller>
<name>Altitude Hold (Altimeter based) Stage 2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>altitude-hold</value>
</enable>
<input>
<prop>/velocities/vertical-speed-fps</prop>
</input>
<reference>
<prop>/autopilot/internal/target-climb-rate-fps</prop>
</reference>
<output>
<prop>/autopilot/settings/target-pitch-deg</prop>
</output>
<config>
<Kp>0.5</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>1.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-5.0</u_min> <!-- minimum output clamp -->
<u_max>5.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Stage #3 drives the elevator trim to achieve the desired pitch -->
<!-- angle -->
<pid-controller>
<name>Pitch hold</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>altitude-hold</value>
<honor-passive>true</honor-passive>
</enable>
<input>
<prop>/orientation/pitch-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-pitch-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- AGL hold. 2 stage cascade controller. -->
<!-- Stage #1 sets target rate of climb based on diff between current agl -->
<!-- and target agl. -->
<pid-controller>
<name>AGL Hold (Altimeter based) Stage 1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>agl-hold</value>
</enable>
<input>
<prop>/position/altitude-agl-ft</prop>
</input>
<reference>
<prop>/autopilot/settings/target-agl-ft</prop>
</reference>
<output>
<prop>/autopilot/internal/target-climb-rate-fps</prop>
</output>
<config>
<Kp>1.0</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>25.0</Ti> <!-- integrator time -->
<Td>0.000000001</Td> <!-- derivator time -->
<u_min>-16.67</u_min> <!-- minimum output clamp -->
<u_max>8.33</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Stage #2 drives the elevator-trim to achieve the desired climb rate. -->
<pid-controller>
<name>Altitude Hold (Altimeter based) Stage 2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>agl-hold</value>
</enable>
<input>
<prop>/velocities/vertical-speed-fps</prop>
</input>
<reference>
<prop>/autopilot/internal/target-climb-rate-fps</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Glideslope hold. -->
<!-- Stage #2 drives the elevator-trim to achieve the desired climb rate. -->
<pid-controller>
<name>Glideslop Hold</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/altitude</prop>
<value>gs1-hold</value>
</enable>
<input>
<prop>/velocities/vertical-speed-fps</prop>
</input>
<reference>
<prop>/instrumentation/nav[0]/gs-rate-of-climb</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- =============================================================== -->
<!-- Velocity Modes -->
<!-- =============================================================== -->
<!-- Auto throttle -->
<pid-controller>
<name>Auto Throttle (5 sec lookahead)</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-throttle</value>
</enable>
<input>
<!-- <prop>/autopilot/internal/lookahead-5-sec-airspeed-kt</prop> -->
<prop>/velocities/airspeed-kt</prop>
</input>
<reference>
<prop>/autopilot/settings/target-speed-kt</prop>
</reference>
<output>
<prop>/controls/engines/engine[0]/throttle</prop>
<prop>/controls/engines/engine[1]/throttle</prop>
<prop>/controls/engines/engine[2]/throttle</prop>
<prop>/controls/engines/engine[3]/throttle</prop>
<prop>/controls/engines/engine[4]/throttle</prop>
<prop>/controls/engines/engine[5]/throttle</prop>
<prop>/controls/engines/engine[6]/throttle</prop>
<prop>/controls/engines/engine[7]/throttle</prop>
</output>
<config>
<Kp>0.1</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>1.0</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>0.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Hold speed by varying pitch trim (Two stage cascading controller) -->
<pid-controller>
<name>Speed hold (vary pitch trim) Stage #1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-trim</value>
</enable>
<input>
<!-- <prop>/autopilot/internal/lookahead-5-sec-airspeed-kt</prop> -->
<prop>/velocities/airspeed-kt</prop>
</input>
<reference>
<prop>/autopilot/settings/target-speed-kt</prop>
</reference>
<output>
<prop>/autopilot/settings/target-pitch-deg</prop>
</output>
<config>
<Kp>-1.0</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>2.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-15.0</u_min><!-- minimum output clamp -->
<u_max>15.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<pid-controller>
<name>Speed hold (vary pitch trim) Stage #2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-trim</value>
</enable>
<input>
<prop>/orientation/pitch-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-pitch-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator-trim</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Hold speed by varying elevator (2 stage cascading controller)-->
<!-- Stage 1, command a forward acceleration rate based on velocity error -->
<pi-simple-controller>
<name>Speed hold (vary elevator)</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-yoke</value>
</enable>
<input>
<prop>/velocities/airspeed-kt</prop>
</input>
<reference>
<prop>/autopilot/settings/target-speed-kt</prop>
</reference>
<output>
<prop>/autopilot/settings/target-accel-ktps</prop>
</output>
<config>
<Kp>0.2</Kp> <!-- proportional gain -->
<Ki>0.0</Ki> <!-- integral gain -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pi-simple-controller>
<!-- Stage 2, command elevator to achieve target acceleration rate -->
<pid-controller>
<name>Speed hold (vary elevator)</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-yoke</value>
</enable>
<input>
<prop>/accelerations/airspeed-ktps</prop>
</input>
<reference>
<prop>//autopilot/settings/target-accel-ktps</prop>
</reference>
<output>
<prop>/controls/flight/elevator</prop>
</output>
<config>
<Kp>0.02</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>8.0</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-0.25</u_min> <!-- minimum output clamp -->
<u_max>0.25</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<!-- Hold speed by varying pitch via yoke (Two stage cascading controller) -->
<pid-controller>
<name>Speed hold (vary pitch via yoke) Stage #1</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-yoke-pitch</value>
</enable>
<input>
<!-- <prop>/autopilot/internal/lookahead-5-sec-airspeed-kt</prop> -->
<prop>/velocities/airspeed-kt</prop>
</input>
<reference>
<prop>/autopilot/settings/target-speed-kt</prop>
</reference>
<output>
<prop>/autopilot/settings/target-pitch-deg</prop>
</output>
<config>
<Kp>-1.0</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>2.0</Ti> <!-- integrator time -->
<Td>0.00001</Td> <!-- derivator time -->
<u_min>-15.0</u_min><!-- minimum output clamp -->
<u_max>15.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
<pid-controller>
<name>Speed hold (vary pitch via yoke) Stage #2</name>
<debug>false</debug>
<enable>
<prop>/autopilot/locks/speed</prop>
<value>speed-with-pitch-yoke-pitch</value>
</enable>
<input>
<prop>/orientation/pitch-deg</prop>
</input>
<reference>
<prop>/autopilot/settings/target-pitch-deg</prop>
</reference>
<output>
<prop>/controls/flight/elevator</prop>
</output>
<config>
<Kp>-0.05</Kp> <!-- proportional gain -->
<beta>1.0</beta> <!-- input value weighing factor -->
<alpha>0.1</alpha> <!-- low pass filter weighing factor -->
<gamma>0.0</gamma> <!-- input value weighing factor for -->
<!-- unfiltered derivative error -->
<Ti>0.5</Ti> <!-- integrator time -->
<Td>0.001</Td> <!-- derivator time -->
<u_min>-1.0</u_min> <!-- minimum output clamp -->
<u_max>1.0</u_max> <!-- maximum output clamp -->
</config>
</pid-controller>
</PropertyList>

View File

@ -0,0 +1,40 @@
var last_time = 0.0;
var last_speed = 0.0;
var speed_sensed = 0.0;
var sensor_step = 1.0;
var speed_filt = 0.0;
var accel_filt = 0.0;
var compute_airspeed_accel = func( speed_filt, dt ) {
# print ( "computing forward acceleration ", dt );
var delta_speed = speed_filt - last_speed;
last_speed = speed_filt;
var accel = delta_speed / dt;
return accel;
}
var update_airdata = func( dt ) {
# crude model of a noisy electronic pitot tube
sensed_speed = getprop("/velocities/airspeed-kt");
var r = rand();
if ( r < 0.3333 ) {
sensed_speed = sensed_speed - sensor_step;
} elsif ( r > 0.6666 ) {
sensed_speed = sensed_speed + sensor_step;
}
speed_filt = 0.97 * speed_filt + 0.03 * sensed_speed;
var sensed_accel = 0.0;
if ( dt > 0 ) {
sensed_accel = compute_airspeed_accel( speed_filt, dt );
}
accel_filt = 0.97 * accel_filt + 0.03 * sensed_accel;
setprop("/accelerations/airspeed-ktps", accel_filt);
}

View File

@ -0,0 +1,140 @@
<?xml version="1.0"?>
<!-- The cub doesn't really have an electrical system but let's give -->
<!-- it a little bit of something since we don't have a virtual ground -->
<!-- crew to go out and flip the prop for us. -->
<PropertyList>
<!-- Supplier list -->
<supplier>
<name>Battery 1</name>
<prop>/systems/electrical/suppliers/battery[0]</prop>
<kind>battery</kind>
<volts>28</volts> <!-- needs to be > 24.5, but this is a guess -->
<amps>60</amps> <!-- I have no idea! -->
</supplier>
<supplier>
<name>Alternator 1</name>
<prop>/systems/electrical/suppliers/alternator[0]</prop>
<kind>alternator</kind>
<rpm-source>/engines/engine[0]/rpm</rpm-source>
<volts>28</volts> <!-- stubbed in -->
<amps>60</amps> <!-- from the 172S Skyhawk Information Manual -->
</supplier>
<!-- Bus list -->
<bus>
<name>Master Bus</name>
<prop>/systems/electrical/outputs/bus[0]</prop>
<prop>/systems/electrical/outputs/transponder</prop>
</bus>
<!-- Generic Outputs -->
<output>
<name>Starter 1 Power</name>
<prop>/systems/electrical/outputs/starter[0]</prop>
</output>
<output>
<name>Landing Light Power</name>
<prop>/systems/electrical/outputs/landing-light</prop>
</output>
<output>
<name>Beacon Power</name>
<prop>/systems/electrical/outputs/beacon</prop>
</output>
<output>
<name>Strobe Lights Power</name>
<prop>/systems/electrical/outputs/strobe-lights</prop>
</output>
<output>
<name>Taxi Lights Power</name>
<prop>/systems/electrical/outputs/taxi-lights</prop>
</output>
<output>
<name>Pitot Heat Power</name>
<prop>/systems/electrical/outputs/pitot-heat</prop>
</output>
<!-- connect in power sources -->
<connector>
<input>Alternator 1</input>
<output>Master Bus</output>
<switch>
<prop>/controls/engines/engine[0]/master-alt</prop>
</switch>
</connector>
<connector>
<input>Battery 1</input>
<output>Master Bus</output>
<switch>
<prop>/controls/engines/engine[0]/master-bat</prop>
</switch>
</connector>
<!-- connect starter output -->
<connector>
<input>Master Bus</input>
<output>Starter 1 Power</output>
<switch>
<prop>/controls/engines/engine[0]/starter</prop>
<initial-state>off</initial-state>
</switch>
</connector>
<!-- connect master bus outputs -->
<connector>
<input>Master Bus</input>
<output>Landing Light Power</output>
<switch>
<prop>/controls/switches/landing-light</prop>
</switch>
</connector>
<connector>
<input>Master Bus</input>
<output>Beacon Power</output>
<switch>
<prop>/controls/switches/flashing-beacon</prop>
</switch>
</connector>
<connector>
<input>Master Bus</input>
<output>Strobe Lights Power</output>
<switch>
<prop>/controls/switches/strobe-lights</prop>
</switch>
</connector>
<connector>
<input>Master Bus</input>
<output>Taxi Lights Power</output>
<switch>
<prop>/controls/switches/taxi-lights</prop>
</switch>
</connector>
<connector>
<input>Master Bus</input>
<output>Pitot Heat Power</output>
<switch>
<prop>/controls/switches/pitot-heat</prop>
</switch>
</connector>
</PropertyList>

View File

@ -0,0 +1,22 @@
var dialog = gui.Dialog.new("/sim/gui/dialogs/rascal/config/dialog",
"Aircraft/Rascal/Dialogs/config.xml");
var last_time = 0.0;
var main_loop = func {
var time = getprop("/sim/time/elapsed-sec");
var dt = time - last_time;
last_time = time;
update_airdata( dt );
update_ugear( dt );
settimer(main_loop, 0);
}
setlistener("/sim/signals/fdm-initialized",
func {
main_loop();
});

View File

@ -0,0 +1,54 @@
var update_ugear = func( dt ) {
var max_zoom_rate = 10*dt;
var max_pan_rate = 30*dt;
var max_tilt_rate = 45*dt;
var ap_enable = props.globals.getNode("/ugear/settings/ap-enable");
if ( ap_enable == nil ) {
props.globals.initNode("/ugear/settings/ap-enable", 0, "BOOL", 1);
ap_enable = props.globals.getNode("/ugear/settings/ap-enable");
}
if ( ap_enable.getBoolValue() ) {
setprop( "/controls/flight/aileron", getprop("/ugear/act/aileron") );
setprop( "/controls/flight/elevator", getprop("/ugear/act/elevator") );
}
var turret_enable = props.globals.getNode("/ugear/settings/turret-enable");
if ( turret_enable == nil ) {
props.globals.initNode("/ugear/settings/turret-enable", 0, "BOOL", 1);
turret_enable = props.globals.getNode("/ugear/settings/turret-enable");
}
if ( (getprop("/sim/current-view/name") == "Camera View")
and turret_enable.getBoolValue() )
{
var target_zoom = getprop("/ugear/act/channel6");
var target_pan = -getprop("/ugear/act/channel7");
if ( target_pan < -180.0 ) { target_pan += 360.0; }
if ( target_pan > 180.0 ) { target_pan -= 360.0; }
var target_tilt = -getprop("/ugear/act/channel8");
var cur_zoom = getprop("/sim/current-view/field-of-view");
var cur_pan = getprop("/sim/current-view/heading-offset-deg");
var cur_tilt = getprop("/sim/current-view/pitch-offset-deg");
var diff = 0.0;
diff = target_zoom - cur_zoom;
if ( diff > max_zoom_rate ) { diff = max_zoom_rate; }
if ( diff < -max_zoom_rate ) { diff = -max_zoom_rate; }
setprop("/sim/current-view/field-of-view", cur_zoom + diff);
diff = target_pan - cur_pan;
if ( diff > 180 ) { diff -= 360; }
if ( diff < -180 ) { diff += 360; }
if ( diff > max_pan_rate ) { diff = max_pan_rate; }
if ( diff < -max_pan_rate ) { diff = -max_pan_rate; }
setprop("/sim/current-view/heading-offset-deg", cur_pan + diff);
diff = target_tilt - cur_tilt;
if ( diff > 90 ) { diff = 90; }
if ( diff < -90 ) { diff = -90; }
if ( diff > max_tilt_rate ) { diff = max_tilt_rate; }
if ( diff < -max_tilt_rate ) { diff = -max_tilt_rate; }
setprop("/sim/current-view/pitch-offset-deg", cur_tilt + diff);
}
}

View File

@ -0,0 +1,11 @@
<?xml version="1.0"?>
<initialize name="Start up at Canberra Model Aircraft Club">
<latitude unit="DEG"> -35.362851 </latitude>
<longitude unit="DEG"> 149.165223 </longitude>
<altitude unit="M"> 0 </altitude>
<vt unit="FT/SEC"> 0.0 </vt>
<gamma unit="DEG"> 0.0 </gamma>
<phi unit="DEG"> 0.0 </phi>
<theta unit="DEG"> 0.0 </theta>
<psi unit="DEG"> 0.0 </psi>
</initialize>

View File

@ -0,0 +1,4 @@
<?xml version="1.0"?>
<electric_engine name="a2830-12">
<power unit="WATTS"> 187 </power>
</electric_engine>

View File

@ -0,0 +1,76 @@
<?xml version="1.0"?>
<!-- Generated by Aero-Matic v 1.1
Inputs:
horsepower: 0.250767
pitch: fixed
max engine rpm: 9435
prop diameter (ft): 0.83333333333333
Outputs:
max prop rpm: 22515.60
gear ratio: 0.42
Cp0: 0.002731
Ct0: 0.003823
static thrust (lbs): 0.66
-->
<propeller name="prop">
<!--<ixx> 0.00 </ixx>-->
<ixx> 0.000041666666 </ixx>
<!--assuming solid rod of mass 8 g-->
<diameter unit="IN"> 10.0 </diameter>
<numblades> 2 </numblades>
<gearratio> 1.0 </gearratio>
<p_factor> 0.79 </p_factor>
<table name="C_THRUST" type="internal">
<tableData><!--experimentally measured-->
0.0 0.0054513
1.4 0.0054513
<!--aeromatic generated-->
<!--0.0 0.0042-->
<!--0.1 0.0040-->
<!--0.2 0.0038-->
<!--0.3 0.0035-->
<!--0.4 0.0032-->
<!--0.5 0.0028-->
<!--0.6 0.0023-->
<!--0.7 0.0017-->
<!--0.8 0.0009-->
<!--1.0 -0.0003-->
<!--1.2 -0.0016-->
<!--1.4 -0.0030-->
</tableData>
</table>
<table name="C_POWER" type="internal">
<tableData>
0.0 0.0028
0.1 0.0028
0.2 0.0027
0.3 0.0027
0.4 0.0025
0.5 0.0023
0.6 0.0021
0.7 0.0018
0.8 0.0015
1.0 0.0005
1.2 -0.0008
1.4 -0.0025
1.6 -0.0042
</tableData>
</table>
<!-- thrust effects of helical tip Mach -->
<table name="CT_MACH" type="internal">
<tableData>
0.85 1.0
1.05 0.8
</tableData>
</table>
<!-- power-required effects of helical tip Mach -->
<table name="CP_MACH" type="internal">
<tableData>
0.85 1.0
1.05 1.8
2.00 1.4
</tableData>
</table>
</propeller>

File diff suppressed because it is too large Load Diff

Binary file not shown.

File diff suppressed because it is too large Load Diff

Binary file not shown.

Binary file not shown.

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,88 @@
<?xml version="1.0"?>
<PropertyList>
<!--Airframe-->
<path>arducopter.ac</path>
<offsets>
<z-m>0.0</z-m>
<y-m>0</y-m>
<x-m>0.0</x-m>
<pitch-deg>0</pitch-deg>
<heading-deg>180</heading-deg>
</offsets>
<!--Propeller Right-->
<animation>
<type>noshadow</type>
<object-name>propeller0</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>propeller0</object-name>
<property>/engines/engine[0]/rpm</property>
<factor>100</factor>
<axis>
<x1-m>0.000</x1-m>
<y1-m>-0.288</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.000</x2-m>
<y2-m>-0.288</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Left-->
<animation>
<type>noshadow</type>
<object-name>propeller1</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>propeller1</object-name>
<property>/engines/engine[1]/rpm</property>
<factor>100</factor>
<axis>
<x1-m>0.000</x1-m>
<y1-m>0.288</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.000</x2-m>
<y2-m>0.288</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Front-->
<animation>
<type>noshadow</type>
<object-name>propeller2</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>propeller2</object-name>
<property>/engines/engine[2]/rpm</property>
<factor>100</factor>
<axis>
<x1-m>0.288</x1-m>
<y1-m>0.000</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.288</x2-m>
<y2-m>0.000</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Back-->
<animation>
<type>noshadow</type>
<object-name>propeller3</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>propeller3</object-name>
<property>/engines/engine[3]/rpm</property>
<factor>100</factor>
<axis>
<x1-m>-0.288</x1-m>
<y1-m>0.000</y1-m>
<z1-m>0.046</z1-m>
<x2-m>-0.288</x2-m>
<y2-m>0.000</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
</PropertyList>

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,88 @@
<?xml version="1.0"?>
<PropertyList>
<!--Airframe-->
<path>plus_quad2.ac</path>
<offsets>
<z-m>0.0</z-m>
<y-m>0</y-m>
<x-m>0.0</x-m>
<pitch-deg>0</pitch-deg>
<heading-deg>180</heading-deg>
</offsets>
<!--Propeller Right-->
<animation>
<type>noshadow</type>
<object-name>prop0</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>prop0</object-name>
<property>/controls/engines/engine[0]/throttle</property>
<factor>12000</factor>
<axis>
<x1-m>0.000</x1-m>
<y1-m>-0.288</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.000</x2-m>
<y2-m>-0.288</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Left-->
<animation>
<type>noshadow</type>
<object-name>prop1</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>prop1</object-name>
<property>/controls/engines/engine[1]/throttle</property>
<factor>12000</factor>
<axis>
<x1-m>0.000</x1-m>
<y1-m>0.288</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.000</x2-m>
<y2-m>0.288</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Front-->
<animation>
<type>noshadow</type>
<object-name>prop2</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>prop2</object-name>
<property>/controls/engines/engine[2]/throttle</property>
<factor>12000</factor>
<axis>
<x1-m>0.288</x1-m>
<y1-m>0.000</y1-m>
<z1-m>0.046</z1-m>
<x2-m>0.288</x2-m>
<y2-m>0.000</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
<!--Propeller Back-->
<animation>
<type>noshadow</type>
<object-name>prop3</object-name>
</animation>
<animation>
<type>spin</type>
<object-name>prop3</object-name>
<property>/controls/engines/engine[3]/throttle</property>
<factor>12000</factor>
<axis>
<x1-m>-0.288</x1-m>
<y1-m>0.000</y1-m>
<z1-m>0.046</z1-m>
<x2-m>-0.288</x2-m>
<y2-m>0.000</y2-m>
<z2-m>0.012</z2-m>
</axis>
</animation>
</PropertyList>

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,3 @@
This model is based on the arducopter mode from James Goppert, and
adapted for use in the ArduPilot test system. Many thanks to all who
have contributed!

View File

@ -0,0 +1,93 @@
<?xml version="1.0"?>
<!--
************************************************************************
Arducotper UAV Model
************************************************************************
-->
<PropertyList>
<sim>
<description>Arducopter UAV (R/C)</description>
<author>James Goppert</author>
<aircraft-version>0.0</aircraft-version>
<status>experimental</status>
<flight-model>jsb</flight-model>
<aero>arducopter</aero>
<model-hz>50</model-hz>
<sound>
<path>Aircraft/Generic/generic-sound.xml</path>
</sound>
<panel>
<visibility archive="n">false</visibility>
</panel>
<model>
<path archive="y">Aircraft/arducopter/Models/arducopter.xml</path>
</model>
<view>
<internal archive="y">true</internal>
<config>
<x-offset-m archive="y">0.0</x-offset-m>
<y-offset-m archive="y">0.15</y-offset-m>
<z-offset-m archive="y">0.90</z-offset-m>
<pitch-offset-deg>0</pitch-offset-deg>
</config>
</view>
<chase-distance-m archive="y" type="double">-5.5</chase-distance-m>
<help>
<title>arducopter UAV</title>
<line>Cruise speed: ? mph</line>
<line>Never-exceed (Vne): ? mph</line>
<line>Best Glide (Vglide): ? mph</line>
<line>Maneuvering (Va): ? mph</line>
<line>Approach speed: ? mph</line>
<line>Stall speed (Vs): ? mph</line>
</help>
<startup>
<splash-title>Arducopter UAV DIY Drones/ OPENMAV</splash-title>
<splash-texture>Aircraft/arducopter/arducopter.jpg</splash-texture>
</startup>
</sim>
<controls>
<flight>
<aileron-trim>0.00</aileron-trim>
<!-- fixed -->
<elevator-trim>0.00</elevator-trim>
<!-- controllable -->
</flight>
</controls>
<consumables>
<fuel>
<tank n="0">
<level-gal_us>0</level-gal_us>
</tank>
</fuel>
</consumables>
<payload>
<weight>
<name type="string">Payload</name>
<weight-lb alias="/fdm/jsbsim/inertia/pointmass-weight-lbs[0]"/>
<min-lb type="double">0.0</min-lb>
<max-lb type="double">1.0</max-lb>
</weight>
</payload>
<nasal>
<arducopter>
<script>
setlistener("/sim/signals/fdm-initialized", func {
var left = screen.display.new(20, 10);
left.add("/engines/engine[0]/rpm");
left.add("/engines/engine[1]/rpm");
left.add("/engines/engine[2]/rpm");
left.add("/engines/engine[3]/rpm");
var right = screen.display.new(-250, 20);
right.add("/position/altitude-agl-ft");
right.add("/orientation/roll-deg");
right.add("/orientation/pitch-deg");
right.add("/orientation/heading-deg");
right.add("/instrumentation/gps/indicated-ground-speed-kt");
});
</script>
</arducopter>
</nasal>
</PropertyList>
<!-- vim:sw=4:ts=4:expandtab -->

View File

@ -0,0 +1,248 @@
<?xml version="1.0"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>
<fdm_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" name="dflyer" version="2.0" release="ALPHA" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> James Goppert </author>
<filecreationdate> 2010-03-11 </filecreationdate>
<version>0.0 </version>
<description> Arducopter DIY Drones UAV. </description>
</fileheader>
<metrics>
<wingarea unit="M2"> 0.017</wingarea>
<wingspan unit="M"> 0.13 </wingspan>
<chord unit="FT"> 0.0 </chord>
<htailarea unit="FT2"> 0.0 </htailarea>
<htailarm unit="FT"> 0.0 </htailarm>
<vtailarea unit="FT2"> 0.0 </vtailarea>
<vtailarm unit="FT"> 0.0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 0.00 </x>
<y> 0.00 </y>
<z> 0.00 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
<location name="VRP" unit="IN">
<x>0</x>
<y>0</y>
<z>0</z>
</location>
</metrics>
<mass_balance>
<!--roughtly approximating this as a solid sphere with correct mass-->
<ixx unit="KG*M2"> 0.036 </ixx>
<iyy unit="KG*M2"> 0.036 </iyy>
<izz unit="KG*M2"> 0.036 </izz>
<emptywt unit="KG"> 1.0 </emptywt>
<location name="CG" unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
<pointmass name="Payload">
<weight unit="KG"> 0.0 </weight>
<location unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
</pointmass>
</mass_balance>
<ground_reactions>
<contact type="BOGEY" name="frontbase">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="rearbase">
<location unit="M">
<x> 0.283 </x>
<y> 0.00 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="leftbase">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="rightbase">
<location unit="M">
<x> 0.00 </x>
<y> -0.283 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
</ground_reactions>
<!-- the front and rear motors spin clockwise, and the left and right motors spin counter-clockwise. -->
<propulsion>
<engine file="a2830-12" name="front">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> 1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="rear">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> 1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="left">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> -1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="right">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> -1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<tank type="FUEL" number="0">
<location unit="M">
<x> 0.00 </x>
<y> 0.00 </y>
<z> -0.07 </z>
</location>
<!--have to have a fuel capacity, so setting it small-->
<capacity unit="KG"> 0.00000000001 </capacity>
<contents unit="KG"> 0.0 </contents>
</tank>
</propulsion>
<aerodynamics>
<axis name="LIFT">
</axis>
<axis name="DRAG">
<function name="aero/coefficient/CD0">
<description>Overall Drag</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<value>1</value>
</product>
</function>
</axis>
<axis name="SIDE">
</axis>
<axis name="ROLL">
</axis>
<axis name="PITCH">
</axis>
<axis name="YAW">
</axis>
</aerodynamics>
</fdm_config>
<!-- vim:ts=2:sw=2:expandtab -->

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,12 @@
<?xml version="1.0"?>
<initialize name="reset00">
<ubody unit="M/SEC"> nan </ubody>
<vbody unit="M/SEC"> nan </vbody>
<wbody unit="M/SEC"> nan </wbody>
<phi unit="DEG"> nan </phi>
<theta unit="DEG"> -nan </theta>
<psi unit="DEG"> nan </psi>
<longitude unit="DEG"> nan </longitude>
<latitude unit="DEG"> nan </latitude>
<altitude unit="M"> nan </altitude>
</initialize>

View File

@ -0,0 +1,93 @@
<?xml version="1.0"?>
<!--
************************************************************************
Arducotper UAV Model
************************************************************************
-->
<PropertyList>
<sim>
<description>Arducopter UAV (R/C) (plus quad)</description>
<author>James Goppert</author>
<aircraft-version>0.0</aircraft-version>
<status>experimental</status>
<flight-model>jsb</flight-model>
<aero>plus_quad2</aero>
<model-hz>50</model-hz>
<sound>
<path>Aircraft/Generic/generic-sound.xml</path>
</sound>
<panel>
<visibility archive="n">false</visibility>
</panel>
<model>
<path archive="y">Aircraft/arducopter/Models/plus_quad2.xml</path>
</model>
<view>
<internal archive="y">true</internal>
<config>
<x-offset-m archive="y">0.0</x-offset-m>
<y-offset-m archive="y">0.15</y-offset-m>
<z-offset-m archive="y">0.90</z-offset-m>
<pitch-offset-deg>0</pitch-offset-deg>
</config>
</view>
<chase-distance-m archive="y" type="double">-5.5</chase-distance-m>
<help>
<title>plus_quad UAV</title>
<line>Cruise speed: ? mph</line>
<line>Never-exceed (Vne): ? mph</line>
<line>Best Glide (Vglide): ? mph</line>
<line>Maneuvering (Va): ? mph</line>
<line>Approach speed: ? mph</line>
<line>Stall speed (Vs): ? mph</line>
</help>
<startup>
<splash-title>Arducopter UAV DIY Drones/ OPENMAV</splash-title>
<splash-texture>Aircraft/arducopter/arducopter.jpg</splash-texture>
</startup>
</sim>
<controls>
<flight>
<aileron-trim>0.00</aileron-trim>
<!-- fixed -->
<elevator-trim>0.00</elevator-trim>
<!-- controllable -->
</flight>
</controls>
<consumables>
<fuel>
<tank n="0">
<level-gal_us>0</level-gal_us>
</tank>
</fuel>
</consumables>
<payload>
<weight>
<name type="string">Payload</name>
<weight-lb alias="/fdm/jsbsim/inertia/pointmass-weight-lbs[0]"/>
<min-lb type="double">0.0</min-lb>
<max-lb type="double">1.0</max-lb>
</weight>
</payload>
<nasal>
<plus_quad2>
<script>
setlistener("/sim/signals/fdm-initialized", func {
var left = screen.display.new(20, 10);
left.add("/controls/engines/engine[0]/throttle");
left.add("/controls/engines/engine[1]/throttle");
left.add("/controls/engines/engine[2]/throttle");
left.add("/controls/engines/engine[3]/throttle");
var right = screen.display.new(-250, 20);
right.add("/position/altitude-agl-ft");
right.add("/orientation/roll-deg");
right.add("/orientation/pitch-deg");
right.add("/orientation/heading-deg");
right.add("/instrumentation/gps/indicated-ground-speed-kt");
});
</script>
</plus_quad2>
</nasal>
</PropertyList>
<!-- vim:sw=4:ts=4:expandtab -->

View File

@ -0,0 +1,248 @@
<?xml version="1.0"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>
<fdm_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" name="dflyer" version="2.0" release="ALPHA" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">
<fileheader>
<author> James Goppert </author>
<filecreationdate> 2010-03-11 </filecreationdate>
<version>0.0 </version>
<description> Arducopter DIY Drones UAV. </description>
</fileheader>
<metrics>
<wingarea unit="M2"> 0.017</wingarea>
<wingspan unit="M"> 0.13 </wingspan>
<chord unit="FT"> 0.0 </chord>
<htailarea unit="FT2"> 0.0 </htailarea>
<htailarm unit="FT"> 0.0 </htailarm>
<vtailarea unit="FT2"> 0.0 </vtailarea>
<vtailarm unit="FT"> 0.0 </vtailarm>
<location name="AERORP" unit="IN">
<x> 0.00 </x>
<y> 0.00 </y>
<z> 0.00 </z>
</location>
<location name="EYEPOINT" unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
<location name="VRP" unit="IN">
<x>0</x>
<y>0</y>
<z>0</z>
</location>
</metrics>
<mass_balance>
<!--roughtly approximating this as a solid sphere with correct mass-->
<ixx unit="KG*M2"> 0.036 </ixx>
<iyy unit="KG*M2"> 0.036 </iyy>
<izz unit="KG*M2"> 0.036 </izz>
<emptywt unit="KG"> 1.0 </emptywt>
<location name="CG" unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
<pointmass name="Payload">
<weight unit="KG"> 0.0 </weight>
<location unit="IN">
<x> 0.0 </x>
<y> 0.0 </y>
<z> 0.0 </z>
</location>
</pointmass>
</mass_balance>
<ground_reactions>
<contact type="BOGEY" name="frontbase">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="rearbase">
<location unit="M">
<x> 0.283 </x>
<y> 0.00 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="leftbase">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
<contact type="BOGEY" name="rightbase">
<location unit="M">
<x> 0.00 </x>
<y> -0.283 </y>
<z> -0.033</z>
</location>
<static_friction> 0.80 </static_friction>
<dynamic_friction> 0.50 </dynamic_friction>
<spring_coeff unit="N/M"> 800 </spring_coeff>
<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>
<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>
</contact>
</ground_reactions>
<!-- the front and rear motors spin clockwise, and the left and right motors spin counter-clockwise. -->
<propulsion>
<engine file="a2830-12" name="front">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> 1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="rear">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> 1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="left">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> -1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="right">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
<roll> 0.00 </roll>
<yaw> 0.00 </yaw>
</orient>
<sense> -1 </sense>
<p_factor> 10 </p_factor>
</thruster>
</engine>
<tank type="FUEL" number="0">
<location unit="M">
<x> 0.00 </x>
<y> 0.00 </y>
<z> -0.07 </z>
</location>
<!--have to have a fuel capacity, so setting it small-->
<capacity unit="KG"> 0.00000000001 </capacity>
<contents unit="KG"> 0.0 </contents>
</tank>
</propulsion>
<aerodynamics>
<axis name="LIFT">
</axis>
<axis name="DRAG">
<function name="aero/coefficient/CD0">
<description>Overall Drag</description>
<product>
<property>aero/qbar-psf</property>
<property>metrics/Sw-sqft</property>
<value>1</value>
</product>
</function>
</axis>
<axis name="SIDE">
</axis>
<axis name="ROLL">
</axis>
<axis name="PITCH">
</axis>
<axis name="YAW">
</axis>
</aerodynamics>
</fdm_config>
<!-- vim:ts=2:sw=2:expandtab -->

View File

@ -2,12 +2,11 @@
import util, pexpect, sys, time, math, shutil, os
from common import *
import mavutil, mavwp, random
# get location of scripts
testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil, mavwp
HOME=location(-35.362938,149.165085,584,270)
@ -229,12 +228,12 @@ def fly_ArduCopter(viewerip=None):
you can pass viewerip as an IP address to optionally send fg and
mavproxy packets too for local viewing of the flight in real time
'''
global expect_list, homeloc
global homeloc
hquad_cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%f,%f,%u,%u' % (
simquad_cmd = util.reltopdir('Tools/autotest/pysim/sim_quad.py') + ' --rate=400 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
if viewerip:
hquad_cmd += ' --fgout=192.168.2.15:9123'
simquad_cmd += ' --fgout=%s:5503' % viewerip
sil = util.start_SIL('ArduCopter', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduCopter')
@ -248,6 +247,7 @@ def fly_ArduCopter(viewerip=None):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduCopter.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')
@ -256,8 +256,9 @@ def fly_ArduCopter(viewerip=None):
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter', height=HOME.alt)
hquad = pexpect.spawn(hquad_cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad)
simquad = pexpect.spawn(simquad_cmd, logfile=sys.stdout, timeout=10)
simquad.delaybeforesend = 0
util.pexpect_autoclose(simquad)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
if viewerip:
options += ' --out=%s:14550' % viewerip
@ -277,7 +278,8 @@ def fly_ArduCopter(viewerip=None):
util.expect_setup_callback(mavproxy, expect_callback)
expect_list.extend([hquad, sil, mavproxy])
expect_list_clear()
expect_list_extend([simquad, sil, mavproxy])
# get a mavlink connection going
try:
@ -351,9 +353,10 @@ def fly_ArduCopter(viewerip=None):
except pexpect.TIMEOUT, e:
failed = True
mav.close()
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
util.pexpect_close(hquad)
util.pexpect_close(simquad)
if os.path.exists('ArduCopter-valgrind.log'):
os.chmod('ArduCopter-valgrind.log', 0644)

View File

@ -2,12 +2,11 @@
import util, pexpect, sys, time, math, shutil, os
from common import *
import mavutil, random
# get location of scripts
testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil
HOME_LOCATION='-35.362938,149.165085,584,270'
@ -21,8 +20,8 @@ def takeoff(mavproxy, mav):
# some rudder to counteract the prop torque
mavproxy.send('rc 4 1600\n')
# get it moving a bit first to avoid bad fgear ground physics
mavproxy.send('rc 3 1150\n')
# get it moving a bit first to avoid bad JSBSim ground physics
mavproxy.send('rc 3 1040\n')
mav.recv_match(condition='VFR_HUD.groundspeed>3', blocking=True)
# a bit faster
@ -35,7 +34,7 @@ def takeoff(mavproxy, mav):
mavproxy.send('rc 3 1800\n')
# gain a bit of altitude
wait_altitude(mav, homeloc.alt+30, homeloc.alt+40, timeout=30)
wait_altitude(mav, homeloc.alt+30, homeloc.alt+60, timeout=30)
# level off
mavproxy.send('rc 2 1500\n')
@ -47,6 +46,7 @@ def fly_left_circuit(mavproxy, mav):
'''fly a left circuit, 200m on a side'''
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
mavproxy.send('rc 3 2000\n')
wait_level_flight(mavproxy, mav)
print("Flying left circuit")
@ -64,15 +64,17 @@ def fly_left_circuit(mavproxy, mav):
def fly_RTL(mavproxy, mav):
'''fly to home'''
print("Flying home in RTL")
mavproxy.send('switch 2\n')
wait_mode(mav, 'RTL')
wait_location(mav, homeloc, accuracy=30,
wait_location(mav, homeloc, accuracy=80,
target_altitude=100, height_accuracy=10)
print("RTL Complete")
return True
def fly_LOITER(mavproxy, mav):
'''loiter where we are'''
print("Testing LOITER")
mavproxy.send('switch 3\n')
wait_mode(mav, 'LOITER')
while True:
@ -193,17 +195,18 @@ def fly_ArduPlane(viewerip=None):
you can pass viewerip as an IP address to optionally send fg and
mavproxy packets too for local viewing of the flight in real time
'''
global expect_list, homeloc
global homeloc
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
if viewerip:
options += ' --out=%s:14550' % viewerip
options += " --out=%s:14550" % viewerip
sil = util.start_SIL('ArduPlane', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduPlane.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')
@ -211,6 +214,17 @@ def fly_ArduPlane(viewerip=None):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
cmd = util.reltopdir("Tools/autotest/jsbsim/runsim.py")
cmd += " --home=%s --script=%s/rascal_test.xml" % (
HOME_LOCATION, util.reltopdir("Tools/autotest/jsbsim"))
if viewerip:
cmd += " --fgout=%s:5503" % viewerip
runsim = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
runsim.delaybeforesend = 0
util.pexpect_autoclose(runsim)
runsim.expect('Simulator ready to fly')
sil = util.start_SIL('ArduPlane')
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
mavproxy.expect('Logging to (\S+)')
@ -227,57 +241,10 @@ def fly_ArduPlane(viewerip=None):
util.expect_setup_callback(mavproxy, expect_callback)
fg_scenery = os.getenv("FG_SCENERY")
if not fg_scenery:
raise RuntimeError("You must set the FG_SCENERY environment variable")
expect_list_clear()
expect_list_extend([runsim, sil, mavproxy])
fgear_options = '''
--generic=socket,in,25,,5502,udp,MAVLink \
--generic=socket,out,50,,5501,udp,MAVLink \
--aircraft=Rascal110-JSBSim \
--control=mouse \
--disable-intro-music \
--airport=YKRY \
--lat=-35.362851 \
--lon=149.165223 \
--heading=350 \
--altitude=0 \
--geometry=650x550 \
--jpg-httpd=5502 \
--disable-anti-alias-hud \
--disable-hud-3d \
--disable-enhanced-lighting \
--disable-distance-attenuation \
--disable-horizon-effect \
--shading-flat \
--disable-textures \
--timeofday=noon \
--fdm=jsb \
--disable-sound \
--disable-fullscreen \
--disable-random-objects \
--disable-ai-models \
--shading-flat \
--fog-disable \
--disable-specular-highlight \
--disable-skyblend \
--fg-scenery=%s \
--disable-anti-alias-hud \
--wind=0@0 \
''' % fg_scenery
# start fgear
if os.getenv('DISPLAY'):
cmd = 'fgfs %s' % fgear_options
fgear = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
else:
cmd = "xvfb-run --server-num=42 -s '-screen 0 800x600x24' fgfs --enable-wireframe %s" % fgear_options
util.kill_xvfb(42)
fgear = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
fgear.xvfb_server_num = 42
util.pexpect_autoclose(fgear)
fgear.expect('creating 3D noise', timeout=30)
expect_list.extend([fgear, sil, mavproxy])
print("Started simulator")
# get a mavlink connection going
try:
@ -293,7 +260,8 @@ def fly_ArduPlane(viewerip=None):
try:
mav.wait_heartbeat()
setup_rc(mavproxy)
mav.recv_match(type='GPS_RAW', condition='GPS_RAW.lat != 0 and GPS_RAW.alt != 0 and VFR_HUD.alt != 0',
mavproxy.expect('APM: init home')
mav.recv_match(type='GPS_RAW', condition='MAV.flightmode!="INITIALISING" and GPS_RAW.fix_type==2 and GPS_RAW.lat != 0 and GPS_RAW.alt != 0 and VFR_HUD.alt > 10',
blocking=True)
homeloc = current_location(mav)
print("Home location: %s" % homeloc)
@ -319,9 +287,10 @@ def fly_ArduPlane(viewerip=None):
except pexpect.TIMEOUT, e:
failed = True
mav.close()
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
util.pexpect_close(fgear)
util.pexpect_close(runsim)
if os.path.exists('ArduPlane-valgrind.log'):
os.chmod('ArduPlane-valgrind.log', 0644)

View File

@ -2,10 +2,13 @@
# APM automatic test suite
# Andrew Tridgell, October 2011
import pexpect, os, util, sys, shutil
import arducopter, arduplane
import pexpect, os, sys, shutil, atexit
import optparse, fnmatch, time, glob, traceback
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), 'pysim'))
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), 'pymavlink'))
import util, arducopter, arduplane
os.environ['PYTHONUNBUFFERED'] = '1'
os.putenv('TMPDIR', util.reltopdir('tmp'))
@ -165,9 +168,6 @@ def run_step(step):
return arducopter.fly_ArduCopter(viewerip=opts.viewerip)
if step == 'fly.ArduPlane':
if not opts.experimental:
print("DISABLED: use --experimental to enable fly.ArduPlane")
return True
return arduplane.fly_ArduPlane(viewerip=opts.viewerip)
if step == 'convertgpx':
@ -235,6 +235,7 @@ def run_tests(steps):
passed = True
failed = []
for step in steps:
util.pexpect_close_all()
if skip_step(step):
continue
@ -253,13 +254,14 @@ def run_tests(steps):
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
traceback.print_exc(file=sys.stdout)
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
util.pexpect_close_all()
continue
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
if not passed:
print("FAILED %u tests: %s" % (len(failed), failed))
util.pexpect_close_all()
results.addglob("Google Earth track", '*.kmz')
results.addfile('Full Logs', 'autotest-output.txt')
results.addglob('DataFlash Log', '*.flashlog')
@ -284,6 +286,8 @@ if lck is None:
print("autotest is locked - exiting")
sys.exit(0)
atexit.register(util.pexpect_close_all)
try:
if not run_tests(steps):
sys.exit(1)

View File

@ -4,14 +4,22 @@ import util, pexpect, time, math
# messages. This keeps the output to stdout flowing
expect_list = []
def expect_list_clear():
'''clear the expect list'''
global expect_list
for p in expect_list[:]:
expect_list.remove(p)
def expect_list_extend(list):
'''extend the expect list'''
global expect_list
expect_list.extend(list)
def idle_hook(mav):
'''called when waiting for a mavlink message'''
global expect_list
for p in expect_list:
try:
p.read_nonblocking(100, timeout=0)
except pexpect.TIMEOUT:
pass
util.pexpect_drain(p)
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
@ -25,12 +33,7 @@ def expect_callback(e):
for p in expect_list:
if p == e:
continue
try:
while p.read_nonblocking(100, timeout=0):
pass
except pexpect.TIMEOUT:
pass
util.pexpect_drain(p)
class location(object):
'''represent a GPS coordinate'''

121
Tools/autotest/fakepos.py Executable file
View File

@ -0,0 +1,121 @@
#!/usr/bin/env python
import socket, struct, time
from math import *
class udp_out(object):
'''a UDP output socket'''
def __init__(self, device):
a = device.split(':')
if len(a) != 2:
print("UDP ports must be specified as host:port")
sys.exit(1)
self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
self.destination_addr = (a[0], int(a[1]))
self.port.setblocking(0)
self.last_address = None
def recv(self,n=None):
try:
data, self.last_address = self.port.recvfrom(300)
except socket.error as e:
if e.errno in [ 11, 35 ]:
return ""
raise
return data
def write(self, buf):
try:
self.port.sendto(buf, self.destination_addr)
except socket.error:
pass
def ft2m(x):
return x * 0.3048
def m2ft(x):
return x / 0.3048
def kt2mps(x):
return x * 0.514444444
def mps2kt(x):
return x / 0.514444444
udp = udp_out("127.0.0.1:5501")
latitude = -35
longitude = 149
altitude = 600.0
heading = 0.0
speedN = 0
speedE = 0.0
xAccel = 0.0
yAccel = 0.0
zAccel = 0.0
rollRate = 0.0
pitchRate = 0.0
yawRate = 0.0
rollDeg = 0.0
pitchDeg = 0.0
yawDeg = 0.0
airspeed = 0
magic = 0x4c56414e
deltaT = 0.005
rollDeg = 45
pitchDeg = 0
pitchMax = None
rollMax = None
if True:
pitchRate = 1
pitchMax = 45
rollMax = 45
while True:
xAccel = sin(radians(pitchDeg)) * cos(radians(rollDeg))
yAccel = -sin(radians(rollDeg)) * cos(radians(pitchDeg))
zAccel = -cos(radians(rollDeg)) * cos(radians(pitchDeg))
scale = 9.81 / sqrt((xAccel*xAccel)+(yAccel*yAccel)+(zAccel*zAccel))
xAccel *= scale;
yAccel *= scale;
zAccel *= scale;
buf = struct.pack('<16dI',
latitude, longitude, altitude, heading,
speedN, speedE,
xAccel, yAccel, zAccel,
rollRate, pitchRate, yawRate,
rollDeg, pitchDeg, yawDeg,
airspeed, magic)
udp.write(buf)
time.sleep(deltaT)
yawDeg += yawRate * deltaT
if yawDeg > 180:
yawDeg -= 360
if yawDeg < -180:
yawDeg += 360
heading = yawDeg
if pitchMax is not None and fabs(pitchDeg) > pitchMax:
pitchRate = -pitchRate
if rollMax is not None and fabs(rollDeg) > rollMax:
rollRate = -rollRate
pitchDeg += pitchRate * deltaT
if pitchDeg > 180:
pitchDeg -= 360
if pitchDeg < -180:
pitchDeg += 360
rollDeg += rollRate * deltaT
if rollDeg > 180:
rollDeg -= 360
if rollDeg < -180:
rollDeg += 360

28
Tools/autotest/fg_plane_view.sh Executable file
View File

@ -0,0 +1,28 @@
#!/bin/sh
AUTOTESTDIR=$(dirname $0)
fgfs \
--native-fdm=socket,in,10,,5503,udp \
--fdm=external \
--aircraft=Rascal110-JSBSim \
--control=mouse \
--fg-aircraft="$AUTOTESTDIR/aircraft" \
--disable-intro-music \
--airport=YKRY \
--geometry=650x550 \
--bpp=32 \
--disable-anti-alias-hud \
--disable-hud-3d \
--disable-horizon-effect \
--timeofday=noon \
--disable-sound \
--disable-fullscreen \
--disable-random-objects \
--disable-ai-models \
--fog-disable \
--disable-specular-highlight \
--disable-skyblend \
--disable-anti-alias-hud \
--wind=0@0 \
$*

28
Tools/autotest/fg_quad_view.sh Executable file
View File

@ -0,0 +1,28 @@
#!/bin/sh
AUTOTESTDIR=$(dirname $0)
fgfs \
--native-fdm=socket,in,10,,5503,udp \
--fdm=external \
--aircraft=arducopter \
--control=mouse \
--fg-aircraft="$AUTOTESTDIR/aircraft" \
--disable-intro-music \
--airport=YKRY \
--geometry=650x550 \
--bpp=32 \
--disable-anti-alias-hud \
--disable-hud-3d \
--disable-horizon-effect \
--timeofday=noon \
--disable-sound \
--disable-fullscreen \
--disable-random-objects \
--disable-ai-models \
--fog-disable \
--disable-specular-highlight \
--disable-skyblend \
--disable-anti-alias-hud \
--wind=0@0 \
$*

View File

@ -0,0 +1,2 @@
<?xml version="1.0"?>
<output name="localhost" type="FLIGHTGEAR" port="5123" protocol="udp" rate="1000"/>

View File

@ -0,0 +1,33 @@
<?xml version="1.0" encoding="utf-8"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sf.net/JSBSimScript.xsl"?>
<runscript xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="http://jsbsim.sf.net/JSBSimScript.xsd"
name="Testing Rascal110">
<description>
test ArduPlane using Rascal110 and JSBSim
</description>
<use aircraft="Rascal" initialize="reset_CMAC"/>
<!-- we control the servos via the jsbsim console
interface on TCP 5124 -->
<input port="5124"/>
<run start="0" end="10000000" dt="0.001">
<property value="0"> simulation/notify-time-trigger </property>
<event name="start engine">
<condition> simulation/sim-time-sec le 0.01 </condition>
<set name="propulsion/engine[0]/set-running" value="1"/>
<notify/>
</event>
<event name="Trim">
<condition>simulation/sim-time-sec ge 0.01</condition>
<set name="simulation/do_simple_trim" value="2"/>
<notify/>
</event>
</run>
</runscript>

262
Tools/autotest/jsbsim/runsim.py Executable file
View File

@ -0,0 +1,262 @@
#!/usr/bin/env python
# run a jsbsim model as a child process
import sys, os, pexpect, fdpexpect, socket
import math, time, select, struct, signal
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', 'pysim'))
import util, fgFDM, atexit
class control_state(object):
def __init__(self):
self.aileron = 0
self.elevator = 0
self.throttle = 0
self.rudder = 0
self.ground_height = 0
sitl_state = control_state()
def interpret_address(addrstr):
'''interpret a IP:port string'''
a = addrstr.split(':')
a[1] = int(a[1])
return tuple(a)
def jsb_set(variable, value):
'''set a JSBSim variable'''
global jsb_console
jsb_console.send('set %s %s\r\n' % (variable, value))
def setup_home(home):
'''setup home location'''
v = home.split(',')
if len(v) != 4:
print("home should be lat,lng,alt,hdg")
sys.exit(1)
latitude = float(v[0])
longitude = float(v[1])
altitude = float(v[2])
heading = float(v[3])
sitl_state.ground_height = altitude
jsb_set('position/lat-gc-deg', latitude)
jsb_set('position/long-gc-deg', longitude)
jsb_set('attitude/psi-rad', math.radians(heading))
jsb_set('attitude/phi-rad', 0)
jsb_set('attitude/theta-rad', 0)
def process_sitl_input(buf):
'''process control changes from SITL sim'''
pwm = list(struct.unpack('<11H', buf))
aileron = (pwm[0]-1500)/500.0
elevator = (pwm[1]-1500)/500.0
throttle = (pwm[2]-1000)/1000.0
rudder = (pwm[3]-1500)/500.0
if aileron != sitl_state.aileron:
jsb_set('fcs/aileron-cmd-norm', aileron)
sitl_state.aileron = aileron
if elevator != sitl_state.elevator:
jsb_set('fcs/elevator-cmd-norm', elevator)
sitl_state.elevator = elevator
if rudder != sitl_state.rudder:
jsb_set('fcs/rudder-cmd-norm', rudder)
sitl_state.rudder = rudder
if throttle != sitl_state.throttle:
jsb_set('fcs/throttle-cmd-norm', throttle)
sitl_state.throttle = throttle
def process_jsb_input(buf):
'''process FG FDM input from JSBSim'''
global fdm, fg_out, sim_out
fdm.parse(buf)
if fg_out:
try:
agl = fdm.get('agl', units='meters')
fdm.set('altitude', agl+sitl_state.ground_height, units='meters')
fdm.set('rpm', sitl_state.throttle*1000)
fg_out.send(fdm.pack())
except socket.error as e:
if e.errno not in [ 111 ]:
raise
simbuf = struct.pack('<16dI',
fdm.get('latitude', units='degrees'),
fdm.get('longitude', units='degrees'),
fdm.get('altitude', units='meters'),
fdm.get('psi', units='degrees'),
fdm.get('v_north', units='mps'),
fdm.get('v_east', units='mps'),
fdm.get('A_X_pilot', units='mpss'),
fdm.get('A_Y_pilot', units='mpss'),
fdm.get('A_Z_pilot', units='mpss'),
fdm.get('phidot', units='dps'),
fdm.get('thetadot', units='dps'),
fdm.get('psidot', units='dps'),
fdm.get('phi', units='degrees'),
fdm.get('theta', units='degrees'),
fdm.get('psi', units='degrees'),
fdm.get('vcas', units='mps'),
0x4c56414e)
try:
sim_out.send(simbuf)
except socket.error as e:
if e.errno not in [ 111 ]:
raise
##################
# main program
from optparse import OptionParser
parser = OptionParser("hil_quad.py [options]")
parser.add_option("--simin", help="SITL input (IP:port)", default="127.0.0.1:5502")
parser.add_option("--simout", help="SITL output (IP:port)", default="127.0.0.1:5501")
parser.add_option("--fgout", help="FG display output (IP:port)")
parser.add_option("--home", type='string', help="home lat,lng,alt,hdg (required)")
parser.add_option("--script", type='string', help='jsbsim model script (required)')
parser.add_option("--options", type='string', help='jsbsim startup options')
(opts, args) = parser.parse_args()
for m in [ 'home', 'script' ]:
if not opts.__dict__[m]:
print("Missing required option '%s'" % m)
parser.print_help()
sys.exit(1)
os.chdir(util.reltopdir('Tools/autotest'))
# kill off child when we exit
atexit.register(util.pexpect_close_all)
# start child
cmd = "JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=jsbsim/fgout.xml --script=%s" % opts.script
if opts.options:
cmd += ' %s' % opts.options
jsb = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
jsb.delaybeforesend = 0
util.pexpect_autoclose(jsb)
i = jsb.expect(["Successfully bound to socket for input on port (\d+)",
"Could not bind to socket for input"])
if i == 1:
print("Failed to start JSBSim - is another copy running?")
sys.exit(1)
jsb_out_address = interpret_address("127.0.0.1:%u" % int(jsb.match.group(1)))
jsb.expect("Creating UDP socket on port (\d+)")
jsb_in_address = interpret_address("127.0.0.1:%u" % int(jsb.match.group(1)))
jsb.expect("Successfully connected to socket for output")
jsb.expect("JSBSim Execution beginning")
# setup output to jsbsim
print("JSBSim console on %s" % str(jsb_out_address))
jsb_out = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
jsb_out.connect(jsb_out_address)
jsb_console = fdpexpect.fdspawn(jsb_out.fileno(), logfile=sys.stdout)
jsb_console.delaybeforesend = 0
# setup input from jsbsim
print("JSBSim FG FDM input on %s" % str(jsb_in_address))
jsb_in = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
jsb_in.bind(jsb_in_address)
jsb_in.setblocking(0)
# socket addresses
sim_out_address = interpret_address(opts.simout)
sim_in_address = interpret_address(opts.simin)
# setup input from SITL sim
sim_in = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sim_in.bind(sim_in_address)
sim_in.setblocking(0)
# setup output to SITL sim
sim_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sim_out.connect(interpret_address(opts.simout))
sim_out.setblocking(0)
# setup possible output to FlightGear for display
fg_out = None
if opts.fgout:
fg_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
fg_out.connect(interpret_address(opts.fgout))
setup_home(opts.home)
fdm = fgFDM.fgFDM()
jsb_console.send('info\n')
jsb_console.send('resume\n')
jsb.expect("trim computation time")
time.sleep(1.5)
jsb_console.logfile = None
print("Simulator ready to fly")
def main_loop():
'''run main loop'''
last_report = time.time()
frame_count = 0
while True:
rin = [jsb_in.fileno(), sim_in.fileno(), jsb_console.fileno(), jsb.fileno()]
try:
(rin, win, xin) = select.select(rin, [], [], 1.0)
except select.error:
util.check_parent()
continue
if jsb_in.fileno() in rin:
buf = jsb_in.recv(fdm.packet_size())
process_jsb_input(buf)
frame_count += 1
if sim_in.fileno() in rin:
simbuf = sim_in.recv(22)
process_sitl_input(simbuf)
# show any jsbsim console output
if jsb_console.fileno() in rin:
util.pexpect_drain(jsb_console)
if jsb.fileno() in rin:
util.pexpect_drain(jsb)
if time.time() - last_report > 0.5:
print("FPS %u asl=%.1f agl=%.1f roll=%.1f pitch=%.1f a=(%.2f %.2f %.2f)" % (
frame_count / (time.time() - last_report),
fdm.get('altitude', units='meters'),
fdm.get('agl', units='meters'),
fdm.get('phi', units='degrees'),
fdm.get('theta', units='degrees'),
fdm.get('A_X_pilot', units='mpss'),
fdm.get('A_Y_pilot', units='mpss'),
fdm.get('A_Z_pilot', units='mpss')))
frame_count = 0
last_report = time.time()
def exit_handler():
'''exit the sim'''
signal.signal(signal.SIGINT, signal.SIG_IGN)
signal.signal(signal.SIGTERM, signal.SIG_IGN)
# JSBSim really doesn't like to die ...
if getattr(jsb, 'pid', None) is not None:
os.kill(jsb.pid, signal.SIGKILL)
jsb_console.send('quit\n')
jsb.close(force=True)
util.pexpect_close_all()
sys.exit(1)
signal.signal(signal.SIGINT, exit_handler)
signal.signal(signal.SIGTERM, exit_handler)
try:
main_loop()
except:
exit_handler()
raise

View File

@ -0,0 +1,34 @@
#!/usr/bin/env python
'''
useful extra functions for use by mavlink clients
Copyright Andrew Tridgell 2011
Released under GNU GPL version 3 or later
'''
from math import *
def norm_heading(RAW_IMU, ATTITUDE, declination):
'''calculate heading from RAW_IMU and ATTITUDE'''
xmag = RAW_IMU.xmag
ymag = RAW_IMU.ymag
zmag = RAW_IMU.zmag
pitch = ATTITUDE.pitch
roll = ATTITUDE.roll
headX = xmag*cos(pitch) + ymag*sin(roll)*sin(pitch) + zmag*cos(roll)*sin(pitch)
headY = ymag*cos(roll) - zmag*sin(roll)
heading = atan2(-headY, headX)
heading = fmod(degrees(heading) + declination + 360, 360)
return heading
def TrueHeading(SERVO_OUTPUT_RAW):
rc3_min = 1060
rc3_max = 1850
p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min)
return 172 + (1.0-p)*(326 - 172)
def kmh(mps):
'''convert m/s to Km/h'''
return mps*3.6

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,653 @@
#!/usr/bin/env python
'''
mavlink python utility functions
Copyright Andrew Tridgell 2011
Released under GNU GPL version 3 or later
'''
import socket, math, struct, time, os, fnmatch, array, sys
from math import *
from mavextra import *
if os.getenv('MAVLINK10'):
import mavlinkv10 as mavlink
else:
import mavlink
def evaluate_expression(expression, vars):
'''evaluation an expression'''
try:
v = eval(expression, globals(), vars)
except NameError:
return None
return v
def evaluate_condition(condition, vars):
'''evaluation a conditional (boolean) statement'''
if condition is None:
return True
v = evaluate_expression(condition, vars)
if v is None:
return False
return v
class mavfile(object):
'''a generic mavlink port'''
def __init__(self, fd, address, source_system=255):
self.fd = fd
self.address = address
self.messages = { 'MAV' : self }
if mavlink.WIRE_PROTOCOL_VERSION == "1.0":
self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0)
mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message
else:
self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0)
self.params = {}
self.mav = None
self.target_system = 0
self.target_component = 0
self.mav = mavlink.MAVLink(self, srcSystem=source_system)
self.mav.robust_parsing = True
self.logfile = None
self.logfile_raw = None
self.param_fetch_in_progress = False
self.param_fetch_complete = False
self.start_time = time.time()
self.flightmode = "UNKNOWN"
self.timestamp = 0
self.message_hooks = []
self.idle_hooks = []
def recv(self, n=None):
'''default recv method'''
raise RuntimeError('no recv() method supplied')
def close(self, n=None):
'''default close method'''
raise RuntimeError('no close() method supplied')
def write(self, buf):
'''default write method'''
raise RuntimeError('no write() method supplied')
def pre_message(self):
'''default pre message call'''
return
def post_message(self, msg):
'''default post message call'''
msg._timestamp = time.time()
type = msg.get_type()
self.messages[type] = msg
self.timestamp = msg._timestamp
if type == 'HEARTBEAT':
self.target_system = msg.get_srcSystem()
self.target_component = msg.get_srcComponent()
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.flightmode = mode_string_v10(msg)
elif type == 'PARAM_VALUE':
self.params[str(msg.param_id)] = msg.param_value
if msg.param_index+1 == msg.param_count:
self.param_fetch_in_progress = False
self.param_fetch_complete = True
elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9':
self.flightmode = mode_string_v09(msg)
elif type == 'GPS_RAW':
if self.messages['HOME'].fix_type < 2:
self.messages['HOME'] = msg
for hook in self.message_hooks:
hook(self, msg)
def recv_msg(self):
'''message receive routine'''
self.pre_message()
while True:
n = self.mav.bytes_needed()
s = self.recv(n)
if len(s) == 0 and len(self.mav.buf) == 0:
return None
if self.logfile_raw:
self.logfile_raw.write(str(s))
msg = self.mav.parse_char(s)
if msg:
self.post_message(msg)
return msg
def recv_match(self, condition=None, type=None, blocking=False):
'''recv the next MAVLink message that matches the given condition'''
while True:
m = self.recv_msg()
if m is None:
if blocking:
for hook in self.idle_hooks:
hook(self)
time.sleep(0.01)
continue
return None
if type is not None and type != m.get_type():
continue
if not evaluate_condition(condition, self.messages):
continue
return m
def setup_logfile(self, logfile, mode='w'):
'''start logging to the given logfile, with timestamps'''
self.logfile = open(logfile, mode=mode)
def setup_logfile_raw(self, logfile, mode='w'):
'''start logging raw bytes to the given logfile, without timestamps'''
self.logfile_raw = open(logfile, mode=mode)
def wait_heartbeat(self, blocking=True):
'''wait for a heartbeat so we know the target system IDs'''
return self.recv_match(type='HEARTBEAT', blocking=blocking)
def param_fetch_all(self):
'''initiate fetch of all parameters'''
if time.time() - getattr(self, 'param_fetch_start', 0) < 2.0:
# don't fetch too often
return
self.param_fetch_start = time.time()
self.param_fetch_in_progress = True
self.mav.param_request_list_send(self.target_system, self.target_component)
def time_since(self, mtype):
'''return the time since the last message of type mtype was received'''
if not mtype in self.messages:
return time.time() - self.start_time
return time.time() - self.messages[mtype]._timestamp
def param_set_send(self, parm_name, parm_value, parm_type=None):
'''wrapper for parameter set'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
if parm_type == None:
parm_type = mavlink.MAV_VAR_FLOAT
self.mav.param_set_send(self.target_system, self.target_component,
parm_name, parm_value, parm_type)
else:
self.mav.param_set_send(self.target_system, self.target_component,
parm_name, parm_value)
def waypoint_request_list_send(self):
'''wrapper for waypoint_request_list_send'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.mav.mission_request_list_send(self.target_system, self.target_component)
else:
self.mav.waypoint_request_list_send(self.target_system, self.target_component)
def waypoint_clear_all_send(self):
'''wrapper for waypoint_clear_all_send'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.mav.mission_clear_all_send(self.target_system, self.target_component)
else:
self.mav.waypoint_clear_all_send(self.target_system, self.target_component)
def waypoint_request_send(self, seq):
'''wrapper for waypoint_request_send'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.mav.mission_request_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_request_send(self.target_system, self.target_component, seq)
def waypoint_set_current_send(self, seq):
'''wrapper for waypoint_set_current_send'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.mav.mission_set_current_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq)
def waypoint_count_send(self, seq):
'''wrapper for waypoint_count_send'''
if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
self.mav.mission_count_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_count_send(self.target_system, self.target_component, seq)
class mavserial(mavfile):
'''a serial mavlink port'''
def __init__(self, device, baud=115200, autoreconnect=False, source_system=255):
import serial
self.baud = baud
self.device = device
self.autoreconnect = autoreconnect
self.port = serial.Serial(self.device, self.baud, timeout=0,
dsrdtr=False, rtscts=False, xonxoff=False)
try:
fd = self.port.fileno()
except Exception:
fd = None
mavfile.__init__(self, fd, device, source_system=source_system)
def close(self):
self.port.close()
def recv(self,n=None):
if n is None:
n = self.mav.bytes_needed()
if self.fd is None:
waiting = self.port.inWaiting()
if waiting < n:
n = waiting
return self.port.read(n)
def write(self, buf):
try:
return self.port.write(buf)
except OSError:
if self.autoreconnect:
self.reset()
return -1
def reset(self):
import serial
self.port.close()
while True:
try:
self.port = serial.Serial(self.device, self.baud, timeout=1,
dsrdtr=False, rtscts=False, xonxoff=False)
try:
self.fd = self.port.fileno()
except Exception:
self.fd = None
return
except Exception:
print("Failed to reopen %s" % self.device)
time.sleep(1)
class mavudp(mavfile):
'''a UDP mavlink socket'''
def __init__(self, device, input=True, source_system=255):
a = device.split(':')
if len(a) != 2:
print("UDP ports must be specified as host:port")
sys.exit(1)
self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
self.udp_server = input
if input:
self.port.bind((a[0], int(a[1])))
else:
self.destination_addr = (a[0], int(a[1]))
self.port.setblocking(0)
self.last_address = None
mavfile.__init__(self, self.port.fileno(), device, source_system=source_system)
def close(self):
self.port.close()
def recv(self,n=None):
try:
data, self.last_address = self.port.recvfrom(300)
except socket.error as e:
if e.errno in [ 11, 35 ]:
return ""
raise
return data
def write(self, buf):
try:
if self.udp_server:
if self.last_address:
self.port.sendto(buf, self.last_address)
else:
self.port.sendto(buf, self.destination_addr)
except socket.error:
pass
def recv_msg(self):
'''message receive routine for UDP link'''
self.pre_message()
s = self.recv()
if len(s) == 0:
return None
msg = self.mav.decode(s)
if msg:
self.post_message(msg)
return msg
class mavtcp(mavfile):
'''a TCP mavlink socket'''
def __init__(self, device, source_system=255):
a = device.split(':')
if len(a) != 2:
print("TCP ports must be specified as host:port")
sys.exit(1)
self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.destination_addr = (a[0], int(a[1]))
self.port.connect(self.destination_addr)
self.port.setblocking(0)
self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
mavfile.__init__(self, self.port.fileno(), device, source_system=source_system)
def close(self):
self.port.close()
def recv(self,n=None):
if n is None:
n = self.mav.bytes_needed()
try:
data = self.port.recv(n)
except socket.error as e:
if e.errno in [ 11, 35 ]:
return ""
raise
return data
def write(self, buf):
try:
self.port.send(buf)
except socket.error:
pass
class mavlogfile(mavfile):
'''a MAVLink logfile reader/writer'''
def __init__(self, filename, planner_format=None,
write=False, append=False,
robust_parsing=True, notimestamps=False, source_system=255):
self.filename = filename
self.writeable = write
self.robust_parsing = robust_parsing
self.planner_format = planner_format
self.notimestamps = notimestamps
self._two64 = math.pow(2.0, 63)
if planner_format is None and self.filename.endswith(".tlog"):
self.planner_format = True
mode = 'rb'
if self.writeable:
if append:
mode = 'ab'
else:
mode = 'wb'
self.f = open(filename, mode)
mavfile.__init__(self, None, filename, source_system=source_system)
def close(self):
self.f.close()
def recv(self,n=None):
if n is None:
n = self.mav.bytes_needed()
return self.f.read(n)
def write(self, buf):
self.f.write(buf)
def pre_message(self):
'''read timestamp if needed'''
# read the timestamp
if self.notimestamps:
return
if self.planner_format:
tbuf = self.f.read(21)
if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':':
raise RuntimeError('bad planner timestamp %s' % tbuf)
hnsec = self._two64 + float(tbuf[0:20])
t = hnsec * 1.0e-7 # convert to seconds
t -= 719163 * 24 * 60 * 60 # convert to 1970 base
else:
tbuf = self.f.read(8)
if len(tbuf) != 8:
return
(tusec,) = struct.unpack('>Q', tbuf)
t = tusec * 1.0e-6
self._timestamp = t
def post_message(self, msg):
'''add timestamp to message'''
# read the timestamp
super(mavlogfile, self).post_message(msg)
if self.notimestamps:
msg._timestamp = time.time()
else:
msg._timestamp = self._timestamp
if self.planner_format:
self.f.read(1) # trailing newline
self.timestamp = msg._timestamp
class mavchildexec(mavfile):
'''a MAVLink child processes reader/writer'''
def __init__(self, filename, source_system=255):
from subprocess import Popen, PIPE
import fcntl
self.filename = filename
self.child = Popen(filename, shell=True, stdout=PIPE, stdin=PIPE)
self.fd = self.child.stdout.fileno()
fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL)
fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK)
mavfile.__init__(self, self.fd, filename, source_system=source_system)
def close(self):
self.child.close()
def recv(self,n=None):
try:
x = self.child.stdout.read(1)
except Exception:
return ''
return x
def write(self, buf):
self.child.stdin.write(buf)
def mavlink_connection(device, baud=115200, source_system=255,
planner_format=None, write=False, append=False,
robust_parsing=True, notimestamps=False, input=True):
'''make a serial or UDP mavlink connection'''
if device.startswith('tcp:'):
return mavtcp(device[4:], source_system=source_system)
if device.startswith('udp:'):
return mavudp(device[4:], input=input, source_system=source_system)
if device.find(':') != -1:
return mavudp(device, source_system=source_system, input=input)
if os.path.isfile(device):
if device.endswith(".elf"):
return mavchildexec(device, source_system=source_system)
else:
return mavlogfile(device, planner_format=planner_format, write=write,
append=append, robust_parsing=robust_parsing, notimestamps=notimestamps,
source_system=source_system)
return mavserial(device, baud=baud, source_system=source_system)
class periodic_event(object):
'''a class for fixed frequency events'''
def __init__(self, frequency):
self.frequency = float(frequency)
self.last_time = time.time()
def trigger(self):
'''return True if we should trigger now'''
tnow = time.time()
if self.last_time + (1.0/self.frequency) <= tnow:
self.last_time = tnow
return True
return False
try:
from curses import ascii
have_ascii = True
except:
have_ascii = False
def is_printable(c):
'''see if a character is printable'''
global have_ascii
if have_ascii:
return ascii.isprint(c)
return ord(c) >= 32 and ord(c) <= 126
def all_printable(buf):
'''see if a string is all printable'''
for c in buf:
if not is_printable(c) and not c in ['\r', '\n', '\t']:
return False
return True
class SerialPort(object):
'''auto-detected serial port'''
def __init__(self, device, description=None, hwid=None):
self.device = device
self.description = description
self.hwid = hwid
def __str__(self):
ret = self.device
if self.description is not None:
ret += " : " + self.description
if self.hwid is not None:
ret += " : " + self.hwid
return ret
def auto_detect_serial_win32(preferred_list=['*']):
'''try to auto-detect serial ports on win32'''
try:
import scanwin32
list = sorted(scanwin32.comports())
except:
return []
ret = []
for order, port, desc, hwid in list:
for preferred in preferred_list:
if fnmatch.fnmatch(desc, preferred) or fnmatch.fnmatch(hwid, preferred):
ret.append(SerialPort(port, description=desc, hwid=hwid))
if len(ret) > 0:
return ret
# now the rest
for order, port, desc, hwid in list:
ret.append(SerialPort(port, description=desc, hwid=hwid))
return ret
def auto_detect_serial_unix(preferred_list=['*']):
'''try to auto-detect serial ports on win32'''
import glob
glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*')
ret = []
# try preferred ones first
for d in glist:
for preferred in preferred_list:
if fnmatch.fnmatch(d, preferred):
ret.append(SerialPort(d))
if len(ret) > 0:
return ret
# now the rest
for d in glist:
ret.append(SerialPort(d))
return ret
def auto_detect_serial(preferred_list=['*']):
'''try to auto-detect serial port'''
# see if
if os.name == 'nt':
return auto_detect_serial_win32(preferred_list=preferred_list)
return auto_detect_serial_unix(preferred_list=preferred_list)
def mode_string_v09(msg):
'''mode string for 0.9 protocol'''
mode = msg.mode
nav_mode = msg.nav_mode
MAV_MODE_UNINIT = 0
MAV_MODE_MANUAL = 2
MAV_MODE_GUIDED = 3
MAV_MODE_AUTO = 4
MAV_MODE_TEST1 = 5
MAV_MODE_TEST2 = 6
MAV_MODE_TEST3 = 7
MAV_NAV_GROUNDED = 0
MAV_NAV_LIFTOFF = 1
MAV_NAV_HOLD = 2
MAV_NAV_WAYPOINT = 3
MAV_NAV_VECTOR = 4
MAV_NAV_RETURNING = 5
MAV_NAV_LANDING = 6
MAV_NAV_LOST = 7
MAV_NAV_LOITER = 8
cmode = (mode, nav_mode)
mapping = {
(MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING",
(MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL",
(MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE",
(MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
(MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE",
(MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA",
(MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO",
(MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL",
(MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER",
(MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF",
(MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING",
(MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER",
(MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
(100, MAV_NAV_VECTOR) : "STABILIZE",
(101, MAV_NAV_VECTOR) : "ACRO",
(102, MAV_NAV_VECTOR) : "ALT_HOLD",
(107, MAV_NAV_VECTOR) : "CIRCLE",
}
if cmode in mapping:
return mapping[cmode]
return "Mode(%s,%s)" % cmode
def mode_string_v10(msg):
'''mode string for 1.0 protocol, from heartbeat'''
if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED:
return "Mode(0x%08x)" % msg.base_mode
mapping = {
0 : 'MANUAL',
1 : 'CIRCLE',
2 : 'STABILIZE',
5 : 'FBWA',
6 : 'FBWB',
7 : 'FBWC',
10 : 'AUTO',
11 : 'RTL',
12 : 'LOITER',
13 : 'TAKEOFF',
14 : 'LAND',
15 : 'GUIDED',
16 : 'INITIALISING'
}
if msg.custom_mode in mapping:
return mapping[msg.custom_mode]
return "Mode(%u)" % msg.custom_mode
class x25crc(object):
'''x25 CRC - based on checksum.h from mavlink library'''
def __init__(self, buf=''):
self.crc = 0xffff
self.accumulate(buf)
def accumulate(self, buf):
'''add in some more bytes'''
bytes = array.array('B')
if isinstance(buf, array.array):
bytes.extend(buf)
else:
bytes.fromstring(buf)
accum = self.crc
for b in bytes:
tmp = b ^ (accum & 0xff)
tmp = (tmp ^ (tmp<<4)) & 0xFF
accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4)
accum = accum & 0xFFFF
self.crc = accum

View File

@ -0,0 +1,135 @@
'''
module for loading/saving waypoints
'''
import mavlink
class MAVWPError(Exception):
'''MAVLink WP error class'''
def __init__(self, msg):
Exception.__init__(self, msg)
self.message = msg
class MAVWPLoader(object):
'''MAVLink waypoint loader'''
def __init__(self, target_system=0, target_component=0):
self.wpoints = []
self.target_system = target_system
self.target_component = target_component
def count(self):
'''return number of waypoints'''
return len(self.wpoints)
def wp(self, i):
'''return a waypoint'''
return self.wpoints[i]
def add(self, w):
'''add a waypoint'''
w.seq = self.count()
self.wpoints.append(w)
def remove(self, w):
'''remove a waypoint'''
self.wpoints.remove(w)
def clear(self):
'''clear waypoint list'''
self.wpoints = []
def _read_waypoint_v100(self, line):
'''read a version 100 waypoint'''
cmdmap = {
2 : mavlink.MAV_CMD_NAV_TAKEOFF,
3 : mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
4 : mavlink.MAV_CMD_NAV_LAND,
24: mavlink.MAV_CMD_NAV_TAKEOFF,
26: mavlink.MAV_CMD_NAV_LAND,
25: mavlink.MAV_CMD_NAV_WAYPOINT ,
27: mavlink.MAV_CMD_NAV_LOITER_UNLIM
}
a = line.split()
if len(a) != 13:
raise MAVWPError("invalid waypoint line with %u values" % len(a))
w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
int(a[0]), # seq
int(a[1]), # frame
int(a[2]), # action
int(a[7]), # current
int(a[12]), # autocontinue
float(a[5]), # param1,
float(a[6]), # param2,
float(a[3]), # param3
float(a[4]), # param4
float(a[9]), # x, latitude
float(a[8]), # y, longitude
float(a[10]) # z
)
if not w.command in cmdmap:
raise MAVWPError("Unknown v100 waypoint action %u" % w.command)
w.command = cmdmap[w.command]
return w
def _read_waypoint_v110(self, line):
'''read a version 110 waypoint'''
a = line.split()
if len(a) != 12:
raise MAVWPError("invalid waypoint line with %u values" % len(a))
w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
int(a[0]), # seq
int(a[2]), # frame
int(a[3]), # command
int(a[1]), # current
int(a[11]), # autocontinue
float(a[4]), # param1,
float(a[5]), # param2,
float(a[6]), # param3
float(a[7]), # param4
float(a[8]), # x (latitude)
float(a[9]), # y (longitude)
float(a[10]) # z (altitude)
)
return w
def load(self, filename):
'''load waypoints from a file.
returns number of waypoints loaded'''
f = open(filename, mode='r')
version_line = f.readline().strip()
if version_line == "QGC WPL 100":
readfn = self._read_waypoint_v100
elif version_line == "QGC WPL 110":
readfn = self._read_waypoint_v110
else:
f.close()
raise MAVWPError("Unsupported waypoint format '%s'" % version_line)
self.clear()
for line in f:
if line.startswith('#'):
continue
line = line.strip()
if not line:
continue
w = readfn(line)
if w is not None:
self.add(w)
f.close()
return len(self.wpoints)
def save(self, filename):
'''save waypoints to a file'''
f = open(filename, mode='w')
f.write("QGC WPL 110\n")
for w in self.wpoints:
f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % (
w.seq, w.current, w.frame, w.command,
w.param1, w.param2, w.param3, w.param4,
w.x, w.y, w.z, w.autocontinue))
f.close()

View File

@ -0,0 +1,62 @@
import euclid, math, util
class Aircraft(object):
'''a basic aircraft class'''
def __init__(self):
self.home_latitude = 0
self.home_longitude = 0
self.home_altitude = 0
self.ground_level = 0
self.frame_height = 0.0
self.latitude = self.home_latitude
self.longitude = self.home_longitude
self.altitude = self.home_altitude
self.pitch = 0.0 # degrees
self.roll = 0.0 # degrees
self.yaw = 0.0 # degrees
self.pitch_rate = 0.0 # degrees/s
self.roll_rate = 0.0 # degrees/s
self.yaw_rate = 0.0 # degrees/s
self.velocity = euclid.Vector3(0, 0, 0) # m/s, North, East, Up
self.position = euclid.Vector3(0, 0, 0) # m North, East, Up
self.accel = euclid.Vector3(0, 0, 0) # m/s/s North, East, Up
self.mass = 0.0
self.update_frequency = 50 # in Hz
self.gravity = 9.8 # m/s/s
self.accelerometer = euclid.Vector3(0, 0, -self.gravity)
def normalise(self):
'''normalise roll, pitch and yaw
roll between -180 and 180
pitch between -180 and 180
yaw between 0 and 360
'''
def norm(angle, min, max):
while angle > max:
angle -= 360
while angle < min:
angle += 360
return angle
self.roll = norm(self.roll, -180, 180)
self.pitch = norm(self.pitch, -180, 180)
self.yaw = norm(self.yaw, 0, 360)
def update_position(self):
'''update lat/lon/alt from position'''
radius_of_earth = 6378100.0 # in meters
dlat = math.degrees(math.atan(self.position.x/radius_of_earth))
dlon = math.degrees(math.atan(self.position.y/radius_of_earth))
self.altitude = self.home_altitude + self.position.z
self.latitude = self.home_latitude + dlat
self.longitude = self.home_longitude + dlon
# work out what the accelerometer would see
self.accelerometer = util.RPY_to_XYZ(self.roll, self.pitch, self.yaw, 1) * -self.gravity
self.accelerometer -= self.accel

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,209 @@
#!/usr/bin/env python
# parse and construct FlightGear NET FDM packets
# Andrew Tridgell, November 2011
# released under GNU GPL version 2 or later
import struct, math
class fgFDMError(Exception):
'''fgFDM error class'''
def __init__(self, msg):
Exception.__init__(self, msg)
self.message = 'fgFDMError: ' + msg
class fgFDMVariable(object):
'''represent a single fgFDM variable'''
def __init__(self, index, arraylength, units):
self.index = index
self.arraylength = arraylength
self.units = units
class fgFDMVariableList(object):
'''represent a list of fgFDM variable'''
def __init__(self):
self.vars = {}
self._nextidx = 0
def add(self, varname, arraylength=1, units=None):
self.vars[varname] = fgFDMVariable(self._nextidx, arraylength, units=units)
self._nextidx += arraylength
class fgFDM(object):
'''a flightgear native FDM parser/generator'''
def __init__(self):
'''init a fgFDM object'''
self.FG_NET_FDM_VERSION = 24
self.pack_string = '>I 4x 3d 6f 11f 3f 2f I 4I 4f 4f 4f 4f 4f 4f 4f 4f 4f I 4f I 3I 3f 3f 3f I i f 10f'
self.values = [0]*98
self.FG_MAX_ENGINES = 4
self.FG_MAX_WHEELS = 3
self.FG_MAX_TANKS = 4
# supported unit mappings
self.unitmap = {
('radians', 'degrees') : math.degrees(1),
('rps', 'dps') : math.degrees(1),
('feet', 'meters') : 0.3048,
('fps', 'mps') : 0.3048,
('knots', 'mps') : 0.514444444,
('knots', 'fps') : 0.514444444/0.3048,
('fpss', 'mpss') : 0.3048,
('seconds', 'minutes') : 60,
('seconds', 'hours') : 3600,
}
# build a mapping between variable name and index in the values array
# note that the order of this initialisation is critical - it must
# match the wire structure
self.mapping = fgFDMVariableList()
self.mapping.add('version')
# position
self.mapping.add('longitude', units='radians') # geodetic (radians)
self.mapping.add('latitude', units='radians') # geodetic (radians)
self.mapping.add('altitude', units='meters') # above sea level (meters)
self.mapping.add('agl', units='meters') # above ground level (meters)
# attitude
self.mapping.add('phi', units='radians') # roll (radians)
self.mapping.add('theta', units='radians') # pitch (radians)
self.mapping.add('psi', units='radians') # yaw or true heading (radians)
self.mapping.add('alpha', units='radians') # angle of attack (radians)
self.mapping.add('beta', units='radians') # side slip angle (radians)
# Velocities
self.mapping.add('phidot', units='rps') # roll rate (radians/sec)
self.mapping.add('thetadot', units='rps') # pitch rate (radians/sec)
self.mapping.add('psidot', units='rps') # yaw rate (radians/sec)
self.mapping.add('vcas', units='fps') # calibrated airspeed
self.mapping.add('climb_rate', units='fps') # feet per second
self.mapping.add('v_north', units='fps') # north velocity in local/body frame, fps
self.mapping.add('v_east', units='fps') # east velocity in local/body frame, fps
self.mapping.add('v_down', units='fps') # down/vertical velocity in local/body frame, fps
self.mapping.add('v_wind_body_north', units='fps') # north velocity in local/body frame
self.mapping.add('v_wind_body_east', units='fps') # east velocity in local/body frame
self.mapping.add('v_wind_body_down', units='fps') # down/vertical velocity in local/body
# Accelerations
self.mapping.add('A_X_pilot', units='fpss') # X accel in body frame ft/sec^2
self.mapping.add('A_Y_pilot', units='fpss') # Y accel in body frame ft/sec^2
self.mapping.add('A_Z_pilot', units='fpss') # Z accel in body frame ft/sec^2
# Stall
self.mapping.add('stall_warning') # 0.0 - 1.0 indicating the amount of stall
self.mapping.add('slip_deg', units='degrees') # slip ball deflection
# Engine status
self.mapping.add('num_engines') # Number of valid engines
self.mapping.add('eng_state', self.FG_MAX_ENGINES) # Engine state (off, cranking, running)
self.mapping.add('rpm', self.FG_MAX_ENGINES) # Engine RPM rev/min
self.mapping.add('fuel_flow', self.FG_MAX_ENGINES) # Fuel flow gallons/hr
self.mapping.add('fuel_px', self.FG_MAX_ENGINES) # Fuel pressure psi
self.mapping.add('egt', self.FG_MAX_ENGINES) # Exhuast gas temp deg F
self.mapping.add('cht', self.FG_MAX_ENGINES) # Cylinder head temp deg F
self.mapping.add('mp_osi', self.FG_MAX_ENGINES) # Manifold pressure
self.mapping.add('tit', self.FG_MAX_ENGINES) # Turbine Inlet Temperature
self.mapping.add('oil_temp', self.FG_MAX_ENGINES) # Oil temp deg F
self.mapping.add('oil_px', self.FG_MAX_ENGINES) # Oil pressure psi
# Consumables
self.mapping.add('num_tanks') # Max number of fuel tanks
self.mapping.add('fuel_quantity', self.FG_MAX_TANKS)
# Gear status
self.mapping.add('num_wheels')
self.mapping.add('wow', self.FG_MAX_WHEELS)
self.mapping.add('gear_pos', self.FG_MAX_WHEELS)
self.mapping.add('gear_steer', self.FG_MAX_WHEELS)
self.mapping.add('gear_compression', self.FG_MAX_WHEELS)
# Environment
self.mapping.add('cur_time', units='seconds') # current unix time
self.mapping.add('warp', units='seconds') # offset in seconds to unix time
self.mapping.add('visibility', units='meters') # visibility in meters (for env. effects)
# Control surface positions (normalized values)
self.mapping.add('elevator')
self.mapping.add('elevator_trim_tab')
self.mapping.add('left_flap')
self.mapping.add('right_flap')
self.mapping.add('left_aileron')
self.mapping.add('right_aileron')
self.mapping.add('rudder')
self.mapping.add('nose_wheel')
self.mapping.add('speedbrake')
self.mapping.add('spoilers')
self.set('version', self.FG_NET_FDM_VERSION)
self._packet_size = struct.calcsize(self.pack_string)
if len(self.values) != self.mapping._nextidx:
raise fgFDMError('Invalid variable list in initialisation')
def packet_size(self):
'''return expected size of FG FDM packets'''
return self._packet_size
def convert(self, value, fromunits, tounits):
'''convert a value from one set of units to another'''
if fromunits == tounits:
return value
if (fromunits,tounits) in self.unitmap:
return value * self.unitmap[(fromunits,tounits)]
if (tounits,fromunits) in self.unitmap:
return value / self.unitmap[(tounits,fromunits)]
raise fgFDMError("unknown unit mapping (%s,%s)" % (fromunits, tounits))
def units(self, varname):
'''return the default units of a variable'''
if not varname in self.mapping.vars:
raise fgFDMError('Unknown variable %s' % varname)
return self.mapping.vars[varname].units
def variables(self):
'''return a list of available variables'''
return sorted(self.mapping.vars.keys(),
key = lambda v : self.mapping.vars[v].index)
def get(self, varname, idx=0, units=None):
'''get a variable value'''
if not varname in self.mapping.vars:
raise fgFDMError('Unknown variable %s' % varname)
if idx >= self.mapping.vars[varname].arraylength:
raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % (
varname, idx, self.mapping.vars[varname].arraylength))
value = self.values[self.mapping.vars[varname].index + idx]
if units:
value = self.convert(value, self.mapping.vars[varname].units, units)
return value
def set(self, varname, value, idx=0, units=None):
'''set a variable value'''
if not varname in self.mapping.vars:
raise fgFDMError('Unknown variable %s' % varname)
if idx >= self.mapping.vars[varname].arraylength:
raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % (
varname, idx, self.mapping.vars[varname].arraylength))
if units:
value = self.convert(value, units, self.mapping.vars[varname].units)
self.values[self.mapping.vars[varname].index + idx] = value
def parse(self, buf):
'''parse a FD FDM buffer'''
try:
t = struct.unpack(self.pack_string, buf)
except struct.error, msg:
raise fgFDMError('unable to parse - %s' % msg)
self.values = list(t)
def pack(self):
'''pack a FD FDM buffer from current values'''
for i in range(len(self.values)):
if math.isnan(self.values[i]):
self.values[i] = 0
return struct.pack(self.pack_string, *self.values)

View File

@ -0,0 +1,75 @@
#!/usr/bin/env python
import socket, struct, time, math
import fgFDM
class udp_socket(object):
'''a UDP socket'''
def __init__(self, device, blocking=True, input=True):
a = device.split(':')
if len(a) != 2:
print("UDP ports must be specified as host:port")
sys.exit(1)
self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
if input:
self.port.bind((a[0], int(a[1])))
self.destination_addr = None
else:
self.destination_addr = (a[0], int(a[1]))
if not blocking:
self.port.setblocking(0)
self.last_address = None
def recv(self,n=1000):
try:
data, self.last_address = self.port.recvfrom(n)
except socket.error as e:
if e.errno in [ 11, 35 ]:
return ""
raise
return data
def write(self, buf):
try:
if self.destination_addr:
self.port.sendto(buf, self.destination_addr)
else:
self.port.sendto(buf, self.last_addr)
except socket.error:
pass
def ft2m(x):
return x * 0.3048
def m2ft(x):
return x / 0.3048
def kt2mps(x):
return x * 0.514444444
def mps2kt(x):
return x / 0.514444444
udp = udp_socket("127.0.0.1:5123")
fgout = udp_socket("127.0.0.1:5124", input=False)
tlast = time.time()
count = 0
fg = fgFDM.fgFDM()
while True:
buf = udp.recv(1000)
fg.parse(buf)
fgout.write(fg.pack())
count += 1
if time.time() - tlast > 1.0:
print("%u FPS len=%u" % (count, len(buf)))
count = 0
tlast = time.time()
print(fg.get('latitude', units='degrees'),
fg.get('longitude', units='degrees'),
fg.get('altitude', units='meters'),
fg.get('vcas', units='mps'))

View File

@ -0,0 +1,88 @@
#!/usr/bin/env python
from aircraft import Aircraft
import euclid, util, time
class QuadCopter(Aircraft):
'''a QuadCopter'''
def __init__(self):
Aircraft.__init__(self)
self.motor_speed = [ 0.0, 0.0, 0.0, 0.0 ]
self.mass = 1.0 # Kg
self.hover_throttle = 0.37
self.terminal_velocity = 30.0
self.frame_height = 0.1
# scaling from total motor power to Newtons. Allows the copter
# to hover against gravity when each motor is at hover_throttle
self.thrust_scale = (self.mass * self.gravity) / (4.0 * self.hover_throttle)
self.last_time = time.time()
def update(self, servos):
for i in range(0, 4):
if servos[i] <= 0.0:
self.motor_speed[i] = 0
else:
self.motor_speed[i] = servos[i]
m = self.motor_speed
# how much time has passed?
t = time.time()
delta_time = t - self.last_time
self.last_time = t
# rotational acceleration, in degrees/s/s
roll_accel = (m[1] - m[0]) * 5000.0
pitch_accel = (m[2] - m[3]) * 5000.0
yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.0
# update rotational rates
self.roll_rate += roll_accel * delta_time
self.pitch_rate += pitch_accel * delta_time
self.yaw_rate += yaw_accel * delta_time
# update rotation
self.roll += self.roll_rate * delta_time
self.pitch += self.pitch_rate * delta_time
self.yaw += self.yaw_rate * delta_time
# air resistance
air_resistance = - self.velocity * (self.gravity/self.terminal_velocity)
# normalise rotations
self.normalise()
thrust = (m[0] + m[1] + m[2] + m[3]) * self.thrust_scale # Newtons
accel = thrust / self.mass
accel3D = util.RPY_to_XYZ(self.roll, self.pitch, self.yaw, accel)
accel3D += euclid.Vector3(0, 0, -self.gravity)
accel3D += air_resistance
# new velocity vector
self.velocity += accel3D * delta_time
self.accel = accel3D
# new position vector
old_position = self.position.copy()
self.position += self.velocity * delta_time
# constrain height to the ground
if self.position.z + self.home_altitude < self.ground_level + self.frame_height:
if old_position.z + self.home_altitude > self.ground_level + self.frame_height:
print("Hit ground at %f m/s" % (-self.velocity.z))
self.velocity = euclid.Vector3(0, 0, 0)
self.roll_rate = 0
self.pitch_rate = 0
self.yaw_rate = 0
self.roll = 0
self.pitch = 0
self.accel = euclid.Vector3(0, 0, 0)
self.position = euclid.Vector3(self.position.x, self.position.y,
self.ground_level + self.frame_height - self.home_altitude)
# update lat/lon/altitude
self.update_position()

178
Tools/autotest/pysim/sim_quad.py Executable file
View File

@ -0,0 +1,178 @@
#!/usr/bin/env python
from quadcopter import QuadCopter
import euclid, util, time, os, sys, math
import socket, struct
import select, fgFDM, errno
# find the mavlink.py module
for d in [ 'pymavlink',
os.path.join(os.path.dirname(os.path.realpath(__file__)), '../pymavlink') ]:
if os.path.exists(d):
sys.path.insert(0, d)
import mavlink
def sim_send(m, a):
'''send flight information to mavproxy and flightgear'''
global fdm
fdm.set('latitude', a.latitude, units='degrees')
fdm.set('longitude', a.longitude, units='degrees')
fdm.set('altitude', a.altitude, units='meters')
fdm.set('phi', a.roll, units='degrees')
fdm.set('theta', a.pitch, units='degrees')
fdm.set('psi', a.yaw, units='degrees')
fdm.set('phidot', a.roll_rate, units='dps')
fdm.set('thetadot', a.pitch_rate, units='dps')
fdm.set('psidot', a.yaw_rate, units='dps')
fdm.set('vcas', math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y), units='mps')
fdm.set('v_north', a.velocity.x, units='mps')
fdm.set('v_east', a.velocity.y, units='mps')
fdm.set('num_engines', 4)
for i in range(4):
fdm.set('rpm', 1000*m[i], idx=i)
try:
fg_out.send(fdm.pack())
except socket.error as e:
if not e.errno in [ errno.ECONNREFUSED ]:
raise
buf = struct.pack('<16dI',
a.latitude, a.longitude, a.altitude, a.yaw,
a.velocity.x, a.velocity.y,
a.accelerometer.x, a.accelerometer.y, a.accelerometer.z,
a.roll_rate, a.pitch_rate, a.yaw_rate,
a.roll, a.pitch, a.yaw,
math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y),
0x4c56414e)
try:
sim_out.send(buf)
except socket.error as e:
if not e.errno in [ errno.ECONNREFUSED ]:
raise
def sim_recv(m, a):
'''receive control information from SITL'''
try:
buf = sim_in.recv(22)
except socket.error as e:
if not e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
raise
return
if len(buf) != 22:
return
pwm = list(struct.unpack('<11H', buf))
for i in range(4):
m[i] = (pwm[i]-1000)/1000.0
def interpret_address(addrstr):
'''interpret a IP:port string'''
a = addrstr.split(':')
a[1] = int(a[1])
return tuple(a)
##################
# main program
from optparse import OptionParser
parser = OptionParser("sim_quad.py [options]")
parser.add_option("--fgout", dest="fgout", help="flightgear output (IP:port)", default="127.0.0.1:5503")
parser.add_option("--simin", dest="simin", help="SIM input (IP:port)", default="127.0.0.1:5502")
parser.add_option("--simout", dest="simout", help="SIM output (IP:port)", default="127.0.0.1:5501")
parser.add_option("--home", dest="home", type='string', default=None, help="home lat,lng,alt,hdg (required)")
parser.add_option("--rate", dest="rate", type='int', help="SIM update rate", default=1000)
(opts, args) = parser.parse_args()
for m in [ 'home' ]:
if not opts.__dict__[m]:
print("Missing required option '%s'" % m)
parser.print_help()
sys.exit(1)
parent_pid = os.getppid()
# UDP socket addresses
fg_out_address = interpret_address(opts.fgout)
sim_out_address = interpret_address(opts.simout)
sim_in_address = interpret_address(opts.simin)
# setup output to flightgear
fg_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
fg_out.connect(fg_out_address)
fg_out.setblocking(0)
# setup input from SITL
sim_in = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sim_in.bind(sim_in_address)
sim_in.setblocking(0)
# setup output to SITL
sim_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sim_out.connect(sim_out_address)
sim_out.setblocking(0)
# FG FDM object
fdm = fgFDM.fgFDM()
# create the quadcopter model
a = QuadCopter()
# motors initially off
m = [0, 0, 0, 0]
lastt = time.time()
frame_count = 0
# parse home
v = opts.home.split(',')
if len(v) != 4:
print("home should be lat,lng,alt,hdg")
sys.exit(1)
a.home_latitude = float(v[0])
a.home_longitude = float(v[1])
a.home_altitude = float(v[2])
a.latitude = a.home_latitude
a.longitude = a.home_longitude
a.altitude = a.home_altitude
a.yaw = float(v[3])
a.ground_level = a.home_altitude
a.position.z = 0
print("Starting at lat=%f lon=%f alt=%.1f heading=%.1f" % (
a.home_latitude,
a.home_longitude,
a.home_altitude,
a.yaw))
frame_time = 1.0/opts.rate
sleep_overhead = 0
while True:
frame_start = time.time()
sim_recv(m, a)
m2 = m[:]
a.update(m2)
sim_send(m, a)
frame_count += 1
t = time.time()
if t - lastt > 1.0:
print("%.2f fps zspeed=%.2f zaccel=%.2f h=%.1f a=%.1f yaw=%.1f yawrate=%.1f" % (
frame_count/(t-lastt),
a.velocity.z, a.accel.z, a.position.z, a.altitude,
a.yaw, a.yaw_rate))
lastt = t
frame_count = 0
frame_end = time.time()
if frame_end - frame_start < frame_time:
dt = frame_time - (frame_end - frame_start)
dt -= sleep_overhead
if dt > 0:
time.sleep(dt)
sleep_overhead = 0.99*sleep_overhead + 0.01*(time.time() - frame_end)

View File

@ -1,12 +1,109 @@
# utility code for autotest
import euclid, math
import os, pexpect, sys, time
from subprocess import call, check_call,Popen, PIPE
def RPY_to_XYZ(roll, pitch, yaw, length):
'''convert roll, pitch and yaw in degrees to
Vector3 in X, Y and Z
inputs:
roll, pitch and yaw are in degrees
yaw == 0 when pointing North
roll == zero when horizontal. +ve roll means tilting to the right
pitch == zero when horizontal, +ve pitch means nose is pointing upwards
length is in an arbitrary linear unit.
When RPY is (0, 0, 0) then length represents distance upwards
outputs:
Vector3:
X is in units along latitude. +ve X means going North
Y is in units along longitude +ve Y means going East
Z is altitude in units (+ve is up)
test suite:
>>> RPY_to_XYZ(0, 0, 0, 1)
Vector3(0.00, 0.00, 1.00)
>>> RPY_to_XYZ(0, 0, 0, 2)
Vector3(0.00, 0.00, 2.00)
>>> RPY_to_XYZ(90, 0, 0, 1)
Vector3(0.00, 1.00, 0.00)
>>> RPY_to_XYZ(-90, 0, 0, 1)
Vector3(0.00, -1.00, 0.00)
>>> RPY_to_XYZ(0, 90, 0, 1)
Vector3(-1.00, 0.00, 0.00)
>>> RPY_to_XYZ(0, -90, 0, 1)
Vector3(1.00, 0.00, 0.00)
>>> RPY_to_XYZ(90, 0, 180, 1)
Vector3(-0.00, -1.00, 0.00)
>>> RPY_to_XYZ(-90, 0, 180, 1)
Vector3(0.00, 1.00, 0.00)
>>> RPY_to_XYZ(0, 90, 180, 1)
Vector3(1.00, -0.00, 0.00)
>>> RPY_to_XYZ(0, -90, 180, 1)
Vector3(-1.00, 0.00, 0.00)
>>> RPY_to_XYZ(90, 0, 90, 1)
Vector3(-1.00, 0.00, 0.00)
>>> RPY_to_XYZ(-90, 0, 90, 1)
Vector3(1.00, -0.00, 0.00)
>>> RPY_to_XYZ(90, 0, 270, 1)
Vector3(1.00, -0.00, 0.00)
>>> RPY_to_XYZ(-90, 0, 270, 1)
Vector3(-1.00, 0.00, 0.00)
>>> RPY_to_XYZ(0, 90, 90, 1)
Vector3(-0.00, -1.00, 0.00)
>>> RPY_to_XYZ(0, -90, 90, 1)
Vector3(0.00, 1.00, 0.00)
>>> RPY_to_XYZ(0, 90, 270, 1)
Vector3(0.00, 1.00, 0.00)
>>> RPY_to_XYZ(0, -90, 270, 1)
Vector3(-0.00, -1.00, 0.00)
'''
v = euclid.Vector3(0, 0, length)
v = euclid.Quaternion.new_rotate_euler(-math.radians(pitch), 0, -math.radians(roll)) * v
v = euclid.Quaternion.new_rotate_euler(0, math.radians(yaw), 0) * v
return v
def m2ft(x):
'''meters to feet'''
return float(x) / 0.3048
def ft2m(x):
'''feet to meters'''
return float(x) * 0.3048
def kt2mps(x):
return x * 0.514444444
def mps2kt(x):
return x / 0.514444444
def topdir():
'''return top of git tree where autotest is running from'''
d = os.path.dirname(os.path.realpath(__file__))
assert(os.path.basename(d)=='pysim')
d = os.path.dirname(d)
assert(os.path.basename(d)=='autotest')
d = os.path.dirname(d)
assert(os.path.basename(d)=='Tools')
@ -74,14 +171,10 @@ def pexpect_close(p):
'''close a pexpect child'''
global close_list
xvfb_server_num = getattr(p, 'xvfb_server_num', None)
if xvfb_server_num is not None:
kill_xvfb(xvfb_server_num)
try:
p.close()
except Exception:
pass
time.sleep(1)
try:
p.close(force=True)
except Exception:
@ -95,6 +188,13 @@ def pexpect_close_all():
for p in close_list[:]:
pexpect_close(p)
def pexpect_drain(p):
'''drain any pending input'''
try:
p.read_nonblocking(1000, timeout=0)
except pexpect.TIMEOUT:
pass
def start_SIL(atype, valgrind=False, wipe=False, CLI=False, height=None):
'''launch a SIL instance'''
cmd=""
@ -108,6 +208,7 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False, height=None):
if height is not None:
cmd += ' -H %u' % height
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
ret.delaybeforesend = 0
pexpect_autoclose(ret)
ret.expect('Waiting for connection')
return ret
@ -127,6 +228,7 @@ def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:
if options is not None:
cmd += ' ' + options
ret = pexpect.spawn(cmd, logfile=logfile, timeout=60)
ret.delaybeforesend = 0
pexpect_autoclose(ret)
return ret
@ -179,12 +281,15 @@ def lock_file(fname):
return None
return f
def kill_xvfb(server_num):
'''Xvfb is tricky to kill!'''
def check_parent(parent_pid=os.getppid()):
'''check our parent process is still alive'''
try:
import signal
pid = int(open('/tmp/.X%s-lock' % server_num).read().strip())
print("Killing Xvfb process %u" % pid)
os.kill(pid, signal.SIGINT)
except Exception, msg:
print("failed to kill Xvfb process - %s" % msg)
os.kill(parent_pid, 0)
except Exception:
print("Parent had finished - exiting")
sys.exit(1)
if __name__ == "__main__":
import doctest
doctest.testmod()

View File

@ -268,6 +268,7 @@ showsources:
$(SKETCHELF): $(SKETCHOBJS) $(LIBOBJS) $(CORELIB)
$(RULEHDR)
$(v)$(LD) $(LDFLAGS) -o $@ $^ $(LIBS)
@echo Built $@
#
# Build sketch objects

View File

@ -128,6 +128,7 @@ static void tcp_start_connection(unsigned int serial_port, bool wait_for_connect
fprintf(stderr, "accept() error - %s", strerror(errno));
exit(1);
}
setsockopt(s->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
setsockopt(s->fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
s->connected = true;
if (!desktop_state.slider) {
@ -174,6 +175,7 @@ static void check_connection(struct tcp_state *s)
int one = 1;
s->connected = true;
setsockopt(s->fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
setsockopt(s->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
printf("New connection on serial port %u\n", s->serial_port);
if (!desktop_state.slider) {
set_nonblocking(s->fd);

View File

@ -2,6 +2,7 @@
#define _DESKTOP_H
#include <unistd.h>
#include <sys/time.h>
struct desktop_info {
bool slider; // slider switch state, True means CLI mode
@ -21,7 +22,10 @@ ssize_t sitl_gps_read(int fd, void *buf, size_t count);
void sitl_update_compass(float heading, float roll, float pitch, float yaw);
void sitl_update_gps(float latitude, float longitude, float altitude,
float speedN, float speedE, bool have_lock);
void sitl_update_adc(float roll, float pitch, float yaw, float airspeed);
void sitl_update_adc(float roll, float pitch, float yaw,
float rollRate, float pitchRate, float yawRate,
float xAccel, float yAccel, float zAccel,
float airspeed);
void sitl_setup_adc(void);
void sitl_update_barometer(float altitude);

View File

@ -31,32 +31,43 @@
#include "desktop.h"
#include "util.h"
#define FGIN_PORT 5501
#define FGOUT_PORT 5502
/*
the sitl_fdm packet is received by the SITL build from the flight
simulator. This is used to feed the internal sensor emulation
*/
struct sitl_fdm {
// little-endian packet format
double latitude, longitude; // degrees
double altitude; // MSL
double heading; // degrees
double speedN, speedE; // m/s
double xAccel, yAccel, zAccel; // m/s/s in body frame
double rollRate, pitchRate, yawRate; // degrees/s/s in earth frame
double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
double airspeed; // m/s
uint32_t magic; // 0x4c56414e
};
#define SIMIN_PORT 5501
#define RCOUT_PORT 5502
static int sitl_fd;
struct sockaddr_in fgout_addr;
struct sockaddr_in rcout_addr;
static pid_t parent_pid;
struct ADC_UDR2 UDR2;
struct RC_ICR4 ICR4;
extern AP_TimerProcess timer_scheduler;
extern Arduino_Mega_ISR_Registry isr_registry;
static volatile struct {
double latitude, longitude; // degrees
double altitude; // MSL
double heading; // degrees
double speedN, speedE; // m/s
double roll, pitch, yaw; // degrees
double airspeed; // m/s
uint32_t update_count;
} sim_state;
static struct sitl_fdm sim_state;
static uint32_t update_count;
/*
setup a FGear listening UDP port, using protocol from MAVLink.xml
setup a SITL FDM listening UDP port
*/
static void setup_fgear(void)
static void setup_fdm(void)
{
int one=1, ret;
struct sockaddr_in sockaddr;
@ -66,7 +77,7 @@ static void setup_fgear(void)
#ifdef HAVE_SOCK_SIN_LEN
sockaddr.sin_len = sizeof(sockaddr);
#endif
sockaddr.sin_port = htons(FGIN_PORT);
sockaddr.sin_port = htons(SIMIN_PORT);
sockaddr.sin_family = AF_INET;
sitl_fd = socket(AF_INET, SOCK_DGRAM, 0);
@ -89,25 +100,16 @@ static void setup_fgear(void)
}
/*
check for a fgear packet
check for a SITL FDM packet
*/
static void sitl_fgear_input(void)
static void sitl_fdm_input(void)
{
ssize_t size;
struct fg_mavlink {
double latitude, longitude, altitude, heading,
speedN, speedE,
xAccel, yAccel, zAccel,
rollRate, pitchRate, yawRate,
rollDeg, pitchDeg, yawDeg,
airspeed;
uint32_t magic;
};
struct pwm_packet {
uint16_t pwm[8];
};
union {
struct fg_mavlink fg_pkt;
struct sitl_fdm fg_pkt;
struct pwm_packet pwm_pkt;
} d;
@ -117,11 +119,8 @@ static void sitl_fgear_input(void)
static uint32_t last_report;
static uint32_t count;
/* sigh, its big-endian */
swap_doubles(&d.fg_pkt.latitude, 16);
d.fg_pkt.magic = ntohl(d.fg_pkt.magic);
if (d.fg_pkt.magic != 0x4c56414d) {
printf("Bad fgear packet - magic=0x%08x\n", d.fg_pkt.magic);
if (d.fg_pkt.magic != 0x4c56414e) {
printf("Bad FDM packet - magic=0x%08x\n", d.fg_pkt.magic);
return;
}
@ -132,17 +131,8 @@ static void sitl_fgear_input(void)
return;
}
sim_state.latitude = d.fg_pkt.latitude;
sim_state.longitude = d.fg_pkt.longitude;
sim_state.altitude = ft2m(d.fg_pkt.altitude);
sim_state.speedN = ft2m(d.fg_pkt.speedN);
sim_state.speedE = ft2m(d.fg_pkt.speedE);
sim_state.roll = d.fg_pkt.rollDeg;
sim_state.pitch = d.fg_pkt.pitchDeg;
sim_state.yaw = d.fg_pkt.yawDeg;
sim_state.heading = d.fg_pkt.heading;
sim_state.airspeed = kt2mps(d.fg_pkt.airspeed);
sim_state.update_count++;
sim_state = d.fg_pkt;
update_count++;
count++;
if (millis() - last_report > 1000) {
@ -168,47 +158,13 @@ static void sitl_fgear_input(void)
}
/*
send RC outputs to simulator for a quadcopter
*/
static void sitl_quadcopter_output(uint16_t pwm[8])
{
struct fg_output {
float throttle[4];
uint16_t pwm[8];
} pkt;
for (uint8_t i=0; i<8; i++) {
pkt.pwm[i] = htonl(pwm[i]);
}
for (uint8_t i=0; i<4; i++) {
pkt.throttle[i] = swap_float((pwm[i]-1000) / 1000.0);
}
sendto(sitl_fd, &pkt, sizeof(pkt), MSG_DONTWAIT, (const sockaddr *)&fgout_addr, sizeof(fgout_addr));
}
/*
send RC outputs to simulator for a plane
*/
static void sitl_plane_output(uint16_t pwm[8])
{
double servo[4];
servo[0] = (((int)pwm[0]) - 1500)/500.0;
servo[1] = (((int)pwm[1]) - 1500)/500.0;
servo[2] = (((int)pwm[3]) - 1500)/500.0;
servo[3] = (pwm[2] - 1000) / 1000.0;
swap_doubles(servo, 4);
sendto(sitl_fd, &servo, sizeof(servo), MSG_DONTWAIT, (const sockaddr *)&fgout_addr, sizeof(fgout_addr));
}
/*
send RC outputs to simulator for a quadcopter
*/
static void sitl_simulator_output(void)
{
static uint32_t last_update;
uint16_t pwm[8];
uint16_t pwm[11];
/* this maps the registers used for PWM outputs. The RC
* driver updates these whenever it wants the channel output
* to change */
@ -218,14 +174,12 @@ static void sitl_simulator_output(void)
uint8_t i;
if (last_update == 0) {
if (desktop_state.quadcopter) {
for (i=0; i<8; i++) {
(*reg[i]) = 1000*2;
}
} else {
for (i=0; i<11; i++) {
(*reg[i]) = 1000*2;
}
if (!desktop_state.quadcopter) {
(*reg[0]) = (*reg[1]) = (*reg[3]) = 1500*2;
(*reg[2]) = (*reg[4]) = (*reg[6]) = 1000*2;
(*reg[5]) = (*reg[7]) = 1800*2;
(*reg[7]) = 1800*2;
}
}
@ -235,17 +189,11 @@ static void sitl_simulator_output(void)
}
last_update = millis();
for (i=0; i<8; i++) {
for (i=0; i<11; i++) {
// the registers are 2x the PWM value
pwm[i] = (*reg[i])/2;
}
if (desktop_state.quadcopter) {
sitl_quadcopter_output(pwm);
} else {
sitl_plane_output(pwm);
}
sendto(sitl_fd, (void*)pwm, sizeof(pwm), MSG_DONTWAIT, (const sockaddr *)&rcout_addr, sizeof(rcout_addr));
}
/*
@ -261,7 +209,7 @@ static void timer_handler(int signum)
}
/* check for packet from flight sim */
sitl_fgear_input();
sitl_fdm_input();
// trigger all timers
timer_scheduler.run();
@ -274,22 +222,25 @@ static void timer_handler(int signum)
// send RC output to flight sim
sitl_simulator_output();
if (sim_state.update_count == 0) {
if (update_count == 0) {
sitl_update_gps(0, 0, 0, 0, 0, false);
return;
}
if (sim_state.update_count == last_update_count) {
if (update_count == last_update_count) {
return;
}
last_update_count = sim_state.update_count;
last_update_count = update_count;
sitl_update_gps(sim_state.latitude, sim_state.longitude,
sim_state.altitude,
sim_state.speedN, sim_state.speedE, true);
sitl_update_adc(sim_state.roll, sim_state.pitch, sim_state.heading, sim_state.airspeed);
sitl_update_adc(sim_state.rollDeg, sim_state.pitchDeg, sim_state.yawDeg,
sim_state.rollRate, sim_state.pitchRate, sim_state.yawRate,
sim_state.xAccel, sim_state.yAccel, sim_state.zAccel,
sim_state.airspeed);
sitl_update_barometer(sim_state.altitude);
sitl_update_compass(sim_state.heading, sim_state.roll, sim_state.pitch, sim_state.heading);
sitl_update_compass(sim_state.heading, sim_state.rollDeg, sim_state.pitchDeg, sim_state.heading);
}
@ -322,18 +273,18 @@ void sitl_setup(void)
{
parent_pid = getppid();
fgout_addr.sin_family = AF_INET;
fgout_addr.sin_port = htons(FGOUT_PORT);
inet_pton(AF_INET, "127.0.0.1", &fgout_addr.sin_addr);
rcout_addr.sin_family = AF_INET;
rcout_addr.sin_port = htons(RCOUT_PORT);
inet_pton(AF_INET, "127.0.0.1", &rcout_addr.sin_addr);
setup_timer();
setup_fgear();
setup_fdm();
sitl_setup_adc();
printf("Starting SITL input\n");
// setup some initial values
sitl_update_barometer(desktop_state.initial_height);
sitl_update_adc(0, 0, 0, 0);
sitl_update_adc(0, 0, 0, 0, 0, 0, 0, 0, -9.8, 0);
sitl_update_compass(0, 0, 0, 0);
sitl_update_gps(0, 0, 0, 0, 0, false);
}

View File

@ -41,64 +41,41 @@ static uint16_t airspeed_sensor(float airspeed)
inputs are in degrees
*/
void sitl_update_adc(float roll, float pitch, float yaw, float airspeed)
void sitl_update_adc(float roll, float pitch, float yaw,
float rollRate, float pitchRate, float yawRate,
float xAccel, float yAccel, float zAccel,
float airspeed)
{
static const uint8_t sensor_map[6] = { 1, 2, 0, 4, 5, 6 };
static const float _sensor_signs[6] = { 1, -1, -1, 1, -1, -1 };
const float accel_offset = 2041;
const float gyro_offset = 1658;
#define ToRad(x) (x*0.01745329252) // *pi/180
const float _gyro_gain_x = 0.4;
const float _gyro_gain_y = 0.41;
const float _gyro_gain_z = 0.41;
const float _gyro_gain_x = ToRad(0.4);
const float _gyro_gain_y = ToRad(0.41);
const float _gyro_gain_z = ToRad(0.41);
const float _accel_scale = 9.80665 / 423.8;
float adc[7];
float xAccel, yAccel, zAccel, scale;
float rollRate, pitchRate, yawRate;
static uint32_t last_update;
static float last_roll, last_pitch, last_yaw;
unsigned long delta_t;
float phi, theta, phiDot, thetaDot, psiDot;
float p, q, r;
// 200Hz max
if (micros() - last_update < 5000) {
return;
}
/* convert the angular velocities from earth frame to
body frame. Thanks to James Goppert for the formula
*/
phi = ToRad(roll);
theta = ToRad(pitch);
phiDot = ToRad(rollRate);
thetaDot = ToRad(pitchRate);
psiDot = ToRad(yawRate);
/* map roll/pitch/yaw to values the accelerometer would see */
xAccel = sin(ToRad(pitch)) * cos(ToRad(roll));
yAccel = -sin(ToRad(roll)) * cos(ToRad(pitch));
zAccel = -cos(ToRad(roll)) * cos(ToRad(pitch));
scale = 9.81 / sqrt((xAccel*xAccel)+(yAccel*yAccel)+(zAccel*zAccel));
xAccel *= scale;
yAccel *= scale;
zAccel *= scale;
/* map roll/pitch/yaw to values the gyro would see */
if (last_update == 0) {
rollRate = 0;
pitchRate = 0;
yawRate = 0;
delta_t = micros();
} else {
delta_t = micros() - last_update;
float rollChange, pitchChange, yawChange;
rollChange = normalise180(roll - last_roll);
pitchChange = normalise180(pitch - last_pitch);
yawChange = normalise180(yaw - last_yaw);
rollRate = 1.0e6 * rollChange / delta_t;
pitchRate = 1.0e6 * pitchChange / delta_t;
yawRate = 1.0e6 * yawChange / delta_t;
}
last_update += delta_t;
last_roll = roll;
last_pitch = pitch;
last_yaw = yaw;
p = phiDot - psiDot*sin(theta);
q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
/* work out the ADC channel values */
adc[0] = (rollRate / (_gyro_gain_x * _sensor_signs[0])) + gyro_offset;
adc[1] = (pitchRate / (_gyro_gain_y * _sensor_signs[1])) + gyro_offset;
adc[2] = (yawRate / (_gyro_gain_z * _sensor_signs[2])) + gyro_offset;
adc[0] = (p / (_gyro_gain_x * _sensor_signs[0])) + gyro_offset;
adc[1] = (q / (_gyro_gain_y * _sensor_signs[1])) + gyro_offset;
adc[2] = (r / (_gyro_gain_z * _sensor_signs[2])) + gyro_offset;
adc[3] = (xAccel / (_accel_scale * _sensor_signs[3])) + accel_offset;
adc[4] = (yAccel / (_accel_scale * _sensor_signs[4])) + accel_offset;
@ -123,14 +100,22 @@ void sitl_update_adc(float roll, float pitch, float yaw, float airspeed)
#endif
#if 0
static uint32_t last_report;
uint32_t tnow = millis();
extern AP_DCM dcm;
Vector3f omega = dcm.get_gyro();
printf("dt=%5u adc[2]=%6.1f roll=%6.1f / %6.1f yaw=%6.1f / %6.1f yawRate=%6.3f / %6.3f\n",
(unsigned)delta_t,
adc[2],
roll, dcm.roll_sensor/100.0, yaw, dcm.yaw_sensor/100.0, yawRate, ToDeg(omega.z));
#endif
// report roll/pitch discrepancies
if (tnow - last_report > 5000 ||
(tnow - last_report > 1000 &&
(fabs(roll - dcm.roll_sensor/100.0) > 5.0 ||
fabs(pitch - dcm.pitch_sensor/100.0) > 5.0))) {
last_report = tnow;
printf("roll=%5.1f / %5.1f pitch=%5.1f / %5.1f rr=%5.2f / %5.2f pr=%5.2f / %5.2f\n",
roll, dcm.roll_sensor/100.0,
pitch, dcm.pitch_sensor/100.0,
rollRate, ToDeg(omega.x),
pitchRate, ToDeg(omega.y));
}
}

View File

@ -16,64 +16,6 @@
#include "desktop.h"
/*
swap one double
*/
double swap_double(double d)
{
union {
double d;
uint8_t b[8];
} in, out;
int i;
in.d = d;
for (i=0; i<8; i++) {
out.b[7-i] = in.b[i];
}
return out.d;
}
/*
swap an array of doubles
*/
void swap_doubles(double *d, unsigned count)
{
while (count--) {
*d = swap_double(*d);
d++;
}
}
/*
swap one float
*/
float swap_float(float f)
{
union {
float f;
uint8_t b[4];
} in, out;
int i;
in.f = f;
for (i=0; i<4; i++) {
out.b[3-i] = in.b[i];
}
return out.f;
}
/*
swap an array of floats
*/
void swap_floats(float *f, unsigned count)
{
while (count--) {
*f = swap_float(*f);
f++;
}
}
void set_nonblocking(int fd)
{
unsigned v = fcntl(fd, F_GETFL, 0);

View File

@ -3,10 +3,6 @@
#define kt2mps(x) ((x) * 0.514444444)
#define sqr(x) ((x)*(x))
double swap_double(double d);
void swap_doubles(double *d, unsigned count);
float swap_float(float f);
void swap_floats(float *f, unsigned count);
void set_nonblocking(int fd);
double normalise(double v, double min, double max);
double normalise180(double v);