This commit is contained in:
Jason Short 2011-10-17 23:51:59 -07:00
commit f8a07f8acc
38 changed files with 680 additions and 149067 deletions

View File

@ -808,12 +808,20 @@ static void update_current_flight_mode(void)
break;
case FLY_BY_WIRE_B:
// fake Navigation output using sticks
// Substitute stick inputs for Navigation control output
// We use g.pitch_limit_min because its magnitude is
// normally greater than g.pitch_limit_max
nav_roll = g.channel_roll.norm_input() * g.roll_limit;
altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min;
if ((current_loc.alt>=home.alt+g.FBWB_min_altitude) || (g.FBWB_min_altitude == -1)) {
altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min;
} else {
if (g.channel_pitch.norm_input()<0)
altitude_error =( (home.alt + g.FBWB_min_altitude) - current_loc.alt) + g.channel_pitch.norm_input() * g.pitch_limit_min ;
else altitude_error =( (home.alt + g.FBWB_min_altitude) - current_loc.alt) ;
}
if (g.airspeed_enabled == true)
{
airspeed_fbwB = ((int)(g.flybywire_airspeed_max -

View File

@ -83,6 +83,7 @@ public:
//
k_param_flybywire_airspeed_min = 120,
k_param_flybywire_airspeed_max,
k_param_FBWB_min_altitude, // -1=disabled, minimum value for altitude in cm (default 30m)
//
// 130: Sensor parameters
@ -262,6 +263,7 @@ public:
//
AP_Int8 flybywire_airspeed_min;
AP_Int8 flybywire_airspeed_max;
AP_Int16 FBWB_min_altitude;
// Throttle
//
@ -411,6 +413,7 @@ public:
airspeed_cruise (AIRSPEED_CRUISE_CM, k_param_airspeed_cruise, PSTR("TRIM_ARSPD_CM")),
pitch_trim (0, k_param_pitch_trim, PSTR("TRIM_PITCH_CD")),
RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
FBWB_min_altitude (ALT_HOLD_FBW_CM, k_param_FBWB_min_altitude, PSTR("ALT_HOLD_FBWCM")),
ground_temperature (0, k_param_ground_temperature, PSTR("GND_TEMP")),
ground_pressure (0, k_param_ground_pressure, PSTR("GND_ABS_PRESS")),
compass_enabled (MAGNETOMETER, k_param_compass_enabled, PSTR("MAG_ENABLE")),

View File

@ -366,6 +366,14 @@
#ifndef AIRSPEED_FBW_MAX
# define AIRSPEED_FBW_MAX 22
#endif
#ifndef ALT_HOLD_FBW
# define ALT_HOLD_FBW 0
#endif
#define ALT_HOLD_FBW_CM ALT_HOLD_FBW*100
/* The following parmaeters have no corresponding control implementation
#ifndef THROTTLE_ALT_P
# define THROTTLE_ALT_P 0.32

File diff suppressed because it is too large Load Diff

View File

@ -668,7 +668,7 @@
0000071a t update_nav_wp()
000007ec t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
000009b4 W Parameters::Parameters()
000009b8 W Parameters::Parameters()
00000a1f b g
00000ffc T loop
0000100a T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -668,7 +668,7 @@
0000071a t update_nav_wp()
000007e8 t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
000009b4 W Parameters::Parameters()
000009b8 W Parameters::Parameters()
00000a1f b g
00000ffc T loop
0000100a T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined

View File

@ -683,7 +683,7 @@
0000071a t update_nav_wp()
000007ec t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
000009b4 W Parameters::Parameters()
000009b8 W Parameters::Parameters()
00000a1f b g
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000158a T loop
00001598 T loop

View File

@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined

View File

@ -683,7 +683,7 @@
0000071a t update_nav_wp()
000007e8 t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
000009b4 W Parameters::Parameters()
000009b8 W Parameters::Parameters()
00000a1f b g
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000158a T loop
00001598 T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005ee t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
00000638 t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000019f6 T loop
00001a00 T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005ec t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
00000636 t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000019f6 T loop
00001a00 T loop

View File

@ -5,7 +5,7 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
/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:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
@ -20,51 +20,42 @@ autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static'
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
autogenerated:247: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:248: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:250: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:251: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:252: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:336: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:354: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:355: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:356: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:361: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -214,6 +216,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -223,6 +226,8 @@
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
@ -275,6 +280,7 @@
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 V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -372,7 +378,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -412,7 +417,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -481,6 +485,7 @@
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -511,8 +516,6 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors()
@ -555,7 +558,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
@ -566,6 +568,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
@ -601,11 +604,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
00000588 t __static_initialization_and_destruction_0(int, int)
000005d4 t init_ardupilot()
000006f0 t update_nav_wp()
00000824 b g
00000598 t __static_initialization_and_destruction_0(int, int)
0000061e t init_ardupilot()
0000071a t update_nav_wp()
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
0000136a T loop
00000884 W Parameters::Parameters()
00001372 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -5,7 +5,7 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
/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:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
@ -20,51 +20,42 @@ autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static'
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
autogenerated:247: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:248: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:250: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:251: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:252: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:336: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:354: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:355: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:356: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:361: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -214,6 +216,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -223,6 +226,8 @@
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
@ -275,6 +280,7 @@
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 V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -372,7 +378,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -412,7 +417,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -481,6 +485,7 @@
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -511,8 +516,6 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors()
@ -555,7 +558,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
@ -566,6 +568,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
@ -601,11 +604,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
00000588 t __static_initialization_and_destruction_0(int, int)
000005d2 t init_ardupilot()
000006f0 t update_nav_wp()
00000824 b g
00000598 t __static_initialization_and_destruction_0(int, int)
0000061c t init_ardupilot()
0000071a t update_nav_wp()
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
0000136a T loop
00000884 W Parameters::Parameters()
00001372 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005f2 t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
0000063c t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018f0 T loop
000018fa T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005f0 t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
0000063a t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018f0 T loop
000018fa T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -567,7 +570,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -580,6 +582,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005f2 t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
0000063c t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000182c T loop
00001836 T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -567,7 +570,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -580,6 +582,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005f0 t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
0000063a t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000182c T loop
00001836 T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005ee t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
00000638 t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001904 T loop
0000190e T loop

View File

@ -5,47 +5,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
autogenerated:119: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:181: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:183: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:210: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:231: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:232: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:233: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' 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:213: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:245: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:246: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:249: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:248: warning: 'long int 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:263: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:264: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:271: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:272: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:286: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:293: warning: 'void fake_out_gps()' declared 'static' but never defined
autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(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

View File

@ -41,6 +41,8 @@
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 event_delay
@ -217,6 +219,7 @@
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 report_batt_monitor()::__c
00000008 r report_batt_monitor()::__c
@ -226,6 +229,8 @@
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
@ -276,6 +281,7 @@
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 test_baro(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
@ -374,7 +380,6 @@
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
@ -418,7 +423,6 @@
00000023 r print_gyro_offsets()::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
@ -486,6 +490,7 @@
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t update_GPS_light()
@ -518,8 +523,6 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
@ -566,7 +569,6 @@
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
@ -579,6 +581,7 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
@ -616,11 +619,11 @@
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
000005ec t init_ardupilot()
000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g
00000636 t init_ardupilot()
0000071a t update_nav_wp()
000007c8 t __static_initialization_and_destruction_0(int, int)
00000842 b g
00000870 t process_next_command()
000008f4 W Parameters::Parameters()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001904 T loop
0000190e T loop

View File

@ -51,46 +51,46 @@
<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>
<name>ArduCopter V2.0.48 Beta Quad</name>
<name>ArduCopter V2.0.49 Beta Quad</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>110</format_version>
<format_version>111</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>
<name>ArduCopter V2.0.48 Beta Tri</name>
<name>ArduCopter V2.0.49 Beta Tri</name>
<desc>
#define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>110</format_version>
<format_version>111</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>
<name>ArduCopter V2.0.48 Beta Hexa</name>
<name>ArduCopter V2.0.49 Beta Hexa</name>
<desc>
#define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>110</format_version>
<format_version>111</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>
<name>ArduCopter V2.0.48 Beta Y6</name>
<name>ArduCopter V2.0.49 Beta Y6</name>
<desc>
#define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>110</format_version>
<format_version>111</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
@ -141,7 +141,7 @@
<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>
<name>ArduCopter V2.0.48 Beta Quad Hil</name>
<name>ArduCopter V2.0.49 Beta Quad Hil</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME
@ -151,7 +151,7 @@
</desc>
<format_version>110</format_version>
<format_version>111</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>

View File

@ -1,26 +1 @@
From https://code.google.com/p/ardupilot-mega
6a8104d..b4f49d1 APM_Camera -> origin/APM_Camera
d5ab678..7f6c49b master -> origin/master
Updating d5ab678..7f6c49b
Fast-forward
ArduCopter/APM_Config.h | 19 ++++++
ArduCopter/ArduCopter.pde | 48 +++++++++++++--
ArduCopter/Camera.pde | 11 ++-
ArduCopter/Parameters.h | 15 ++++-
ArduCopter/UserCode.pde | 15 +++++
ArduCopter/UserVariables.h | 13 ++++
ArduCopter/config.h | 14 ++++-
ArduCopter/control_modes.pde | 19 ++++---
ArduCopter/heli.pde | 49 ++++++++++------
ArduCopter/navigation.pde | 26 ++++++--
ArduCopter/radio.pde | 8 ---
ArduCopter/read_commands.pde | 112 ------------------------------------
ArduCopter/setup.pde | 6 +-
ArduCopter/system.pde | 11 +---
ArduCopter/test.pde | 2 +-
libraries/Desktop/Desktop.mk | 18 +++---
libraries/Desktop/Makefile.desktop | 5 +-
17 files changed, 198 insertions(+), 193 deletions(-)
create mode 100644 ArduCopter/UserCode.pde
create mode 100644 ArduCopter/UserVariables.h
delete mode 100644 ArduCopter/read_commands.pde
Already up-to-date.

View File

@ -168,6 +168,8 @@ namespace ArdupilotMega.GCSViews
comPort.ReadBufferSize = 1024 * 1024;
comPort.PortName = MainV2.comportname;
comPort.Open();
System.Threading.Thread t11 = new System.Threading.Thread(delegate()

View File

@ -75,7 +75,8 @@ namespace ArdupilotMega
comPort.DtrEnable = true;
//comPort.Open();
}
catch (Exception) {
catch (Exception)
{
MessageBox.Show("Error opening comport");
}
@ -99,7 +100,7 @@ namespace ArdupilotMega
comPort_DataReceived((object)null, (SerialDataReceivedEventArgs)null);
}
}
catch (Exception ex) { Console.WriteLine("crash in comport reader "+ex.ToString()); } // cant exit unless told to
catch (Exception ex) { Console.WriteLine("crash in comport reader " + ex.ToString()); } // cant exit unless told to
}
Console.WriteLine("Comport thread close");
});
@ -158,7 +159,8 @@ namespace ArdupilotMega
if (!line.Contains("\n"))
line = line + "\n";
}
catch {
catch
{
line = comPort.ReadExisting();
//byte[] data = readline(comPort);
//line = Encoding.ASCII.GetString(data, 0, data.Length);
@ -172,7 +174,7 @@ namespace ArdupilotMega
{
case serialstatus.Connecting:
if (line.Contains("reset to FLY") || line.Contains("interactive setup"))
if (line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI:"))
{
comPort.Write("logs\r");
}
@ -199,6 +201,8 @@ namespace ArdupilotMega
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
TXT_seriallog.AppendText("Createing KML for " + logfile);
while (tr.Peek() != -1)
{
processLine(tr.ReadLine());
@ -206,12 +210,16 @@ namespace ArdupilotMega
tr.Close();
try
{
writeKML(logfile + ".kml");
}
catch { } // usualy invalid lat long error
status = serialstatus.Done;
break;
case serialstatus.Createfile:
receivedbytes = 0;
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath)+ Path.DirectorySeparatorChar +@"logs");
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
logfile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " " + currentlog + ".log";
sw = new StreamWriter(logfile);
status = serialstatus.Waiting;
@ -286,17 +294,20 @@ namespace ArdupilotMega
{
try
{
Application.DoEvents();
line = line.Replace(", ", ",");
line = line.Replace(": ", ":");
string[] items = line.Split(',',':');
string[] items = line.Split(',', ':');
if (items[0].Contains("CMD")) {
if (items[0].Contains("CMD"))
{
if (flightdata.Count == 0)
{
if (int.Parse(items[2]) <= (int)MAVLink.MAV_CMD.LAST) // wps
{
PointLatLngAlt temp = new PointLatLngAlt(double.Parse(items[5],new System.Globalization.CultureInfo("en-US")) / 10000000, double.Parse(items[6],new System.Globalization.CultureInfo("en-US")) / 10000000, double.Parse(items[4],new System.Globalization.CultureInfo("en-US")) / 100, items[1].ToString());
PointLatLngAlt temp = new PointLatLngAlt(double.Parse(items[5], new System.Globalization.CultureInfo("en-US")) / 10000000, double.Parse(items[6], new System.Globalization.CultureInfo("en-US")) / 10000000, double.Parse(items[4], new System.Globalization.CultureInfo("en-US")) / 100, items[1].ToString());
cmd.Add(temp);
}
}
@ -319,7 +330,7 @@ namespace ArdupilotMega
alt = double.Parse(items[7], new System.Globalization.CultureInfo("en-US"));
position[positionindex].Add(new Point3D(double.Parse(items[5],new System.Globalization.CultureInfo("en-US")), double.Parse(items[4],new System.Globalization.CultureInfo("en-US")), alt));
position[positionindex].Add(new Point3D(double.Parse(items[5], new System.Globalization.CultureInfo("en-US")), double.Parse(items[4], new System.Globalization.CultureInfo("en-US")), alt));
oldlastpos = lastpos;
lastpos = (position[positionindex][position[positionindex].Count - 1]);
lastline = line;
@ -443,8 +454,8 @@ namespace ArdupilotMega
stylecode = colours[g % (colours.Length - 1)].ToArgb();
Style style2 = new Style();
Color color = Color.FromArgb(0xff, (stylecode >> 16) & 0xff,(stylecode >> 8) & 0xff,(stylecode >> 0) & 0xff);
Console.WriteLine("colour " + color.ToArgb().ToString("X") + " "+ color.ToKnownColor().ToString());
Color color = Color.FromArgb(0xff, (stylecode >> 16) & 0xff, (stylecode >> 8) & 0xff, (stylecode >> 0) & 0xff);
Console.WriteLine("colour " + color.ToArgb().ToString("X") + " " + color.ToKnownColor().ToString());
style2.Add(new LineStyle(color, 4));
@ -529,6 +540,9 @@ namespace ArdupilotMega
}
catch { }
try
{
pmplane.Point = new KmlPoint((float)model.Location.longitude, (float)model.Location.latitude, (float)model.Location.altitude);
pmplane.Point.AltitudeMode = altmode;
@ -540,6 +554,8 @@ namespace ArdupilotMega
pmplane.Model = model;
planes.Add(pmplane);
}
catch { } // bad lat long value
lastmodel = mod.model;
@ -552,7 +568,7 @@ namespace ArdupilotMega
// create kmz - aka zip file
FileStream fs = File.Open(filename.Replace(".log.kml",".kmz"),FileMode.Create);
FileStream fs = File.Open(filename.Replace(".log.kml", ".kmz"), FileMode.Create);
ZipOutputStream zipStream = new ZipOutputStream(fs);
zipStream.SetLevel(9); //0-9, 9 being the highest level of compression
zipStream.UseZip64 = UseZip64.Off; // older zipfile
@ -632,7 +648,7 @@ namespace ArdupilotMega
}
}
private void downloadthread(int startlognum,int endlognum)
private void downloadthread(int startlognum, int endlognum)
{
for (int a = startlognum; a <= endlognum; a++)
{
@ -643,7 +659,8 @@ namespace ArdupilotMega
comPort.Write(a.ToString() + "\r");
status = serialstatus.Createfile;
while (status != serialstatus.Done) {
while (status != serialstatus.Done)
{
System.Threading.Thread.Sleep(100);
}
@ -660,7 +677,7 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(500);
comPort.Write("dump ");
System.Threading.Thread.Sleep(100);
comPort.Write(a.ToString()+"\r");
comPort.Write(a.ToString() + "\r");
status = serialstatus.Createfile;
while (status != serialstatus.Done)
@ -687,6 +704,7 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(500);
comPort.Write("erase\r");
System.Threading.Thread.Sleep(100);
TXT_seriallog.AppendText("!!Allow 30 seconds for erase\n");
status = serialstatus.Done;
}
@ -699,7 +717,7 @@ namespace ArdupilotMega
openFileDialog1.Multiselect = true;
try
{
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"+ Path.DirectorySeparatorChar ;
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
}
catch { } // incase dir doesnt exist
@ -780,7 +798,7 @@ namespace ArdupilotMega
{
foreach (string logfile in openFileDialog1.FileNames)
{
TXT_seriallog.AppendText("\n\nProcessing " + logfile+"\n");
TXT_seriallog.AppendText("\n\nProcessing " + logfile + "\n");
this.Refresh();
try

View File

@ -321,6 +321,13 @@ namespace ArdupilotMega
RichTextBox txtr = (RichTextBox)ctl;
txtr.BorderStyle = BorderStyle.None;
}
else if (((Type)ctl.GetType()) == typeof(CheckedListBox))
{
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
ctl.ForeColor = Color.White;
CheckedListBox txtr = (CheckedListBox)ctl;
txtr.BorderStyle = BorderStyle.None;
}
else if (((Type)ctl.GetType()) == typeof(TabPage))
{
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28); //Color.FromArgb(0x43, 0x44, 0x45);
@ -682,7 +689,7 @@ namespace ArdupilotMega
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
comportname = CMB_serialport.Text;
if (comportname == "UDP")
if (comportname == "UDP" || comportname == "TCP")
CMB_baudrate.Enabled = false;
else
CMB_baudrate.Enabled = true;

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.0.83")]
[assembly: AssemblyFileVersion("1.0.84")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -11,7 +11,7 @@
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>xG04b9X6TXBWirLuQOgI+3TR8H0=</dsig:DigestValue>
<dsig:DigestValue>sVd4w+f3LroCsyok5UsAi4Bq9eI=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>

View File

@ -40,29 +40,14 @@
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <sys/ioctl.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
int list_s; /* listening socket */
int conn_s; /* connection socket */
short int port = 5760; /* port number */
struct sockaddr_in servaddr, cli_addr; /* socket address structure */
char buffer[256]; /* character buffer */
socklen_t clilen;
int myread(void)
{
return read(conn_s,buffer,1);
}
int mywrite(uint8_t c)
{
return write(conn_s,(char *) &c,1);
}
#define LISTEN_BASE_PORT 5760
#define BUFFER_SIZE 128
#if defined(UDR3)
@ -75,6 +60,122 @@ int mywrite(uint8_t c)
# define FS_MAX_PORTS 1
#endif
static struct tcp_state {
bool connected; // true if a client has connected
int listen_fd; // socket we are listening on
int fd; // data socket
int serial_port;
} tcp_state[FS_MAX_PORTS];
/*
start a TCP connection for a given serial port. If
wait_for_connection is true then block until a client connects
*/
static void tcp_start_connection(unsigned int serial_port, bool wait_for_connection)
{
struct tcp_state *s = &tcp_state[serial_port];
int one=1;
struct sockaddr_in sockaddr;
int ret;
s->serial_port = serial_port;
/* Create the listening socket */
s->listen_fd = socket(AF_INET, SOCK_STREAM, 0);
if (s->listen_fd == -1) {
fprintf(stderr, "ECHOSERV: Error creating listening socket - %s\n", strerror(errno));
exit(1);
}
memset(&sockaddr,0,sizeof(sockaddr));
#ifdef HAVE_SOCK_SIN_LEN
sockaddr.sin_len = sizeof(sockaddr);
#endif
sockaddr.sin_port = htons(LISTEN_BASE_PORT+serial_port);
sockaddr.sin_family = AF_INET;
s->listen_fd = socket(AF_INET, SOCK_STREAM, 0);
if (s->listen_fd == -1) {
fprintf(stderr, "socket failed - %s\n", strerror(errno));
exit(1);
}
/* we want to be able to re-use ports quickly */
setsockopt(s->listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
ret = bind(s->listen_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
if (ret == -1) {
fprintf(stderr, "bind failed on port %u - %s\n",
LISTEN_BASE_PORT+serial_port,
strerror(errno));
exit(1);
}
ret = listen(s->listen_fd, 5);
if (ret == -1) {
fprintf(stderr, "listen failed - %s\n", strerror(errno));
exit(1);
}
printf("Serial port %u on TCP port %u\n", serial_port, LISTEN_BASE_PORT+serial_port);
fflush(stdout);
if (wait_for_connection) {
printf("Waiting for connection ....\n");
s->fd = accept(s->listen_fd, NULL, NULL);
if (s->fd == -1) {
fprintf(stderr, "accept() error - %s", strerror(errno));
exit(1);
}
s->connected = true;
}
}
/*
use select() to see if something is pending
*/
static bool select_check(int fd)
{
fd_set fds;
struct timeval tv;
FD_ZERO(&fds);
FD_SET(fd, &fds);
// zero time means immediate return from select()
tv.tv_sec = 0;
tv.tv_usec = 0;
if (select(fd+1, &fds, NULL, NULL, &tv) == 1) {
return true;
}
return false;
}
/*
see if a new connection is coming in
*/
static void check_connection(struct tcp_state *s)
{
if (s->connected) {
// we only want 1 connection at a time
return;
}
if (select_check(s->listen_fd)) {
s->fd = accept(s->listen_fd, NULL, NULL);
if (s->fd != -1) {
s->connected = true;
printf("New connection on serial port %u\n", s->serial_port);
}
}
}
FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS];
FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS];
@ -99,59 +200,7 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati
void FastSerial::begin(long baud)
{
if (_u2x == 0) {
unsigned v;
v = fcntl(0, F_GETFL, 0);
fcntl(0, F_SETFL, v | O_NONBLOCK);
v = fcntl(1, F_GETFL, 0);
fcntl(1, F_SETFL, v | O_NONBLOCK);
/* Create the listening socket */
if ( (list_s = socket(AF_INET, SOCK_STREAM, 0)) < 0 ) {
fprintf(stderr, "ECHOSERV: Error creating listening socket.\n");
exit(EXIT_FAILURE);
}
int val = 1;
setsockopt(list_s, SOL_SOCKET, SO_REUSEADDR, &val, sizeof val);
/* Set all bytes in socket address structure to
zero, and fill in the relevant data members */
memset(&servaddr, 0, sizeof(servaddr));
servaddr.sin_family = AF_INET;
servaddr.sin_addr.s_addr = INADDR_ANY;
servaddr.sin_port = htons(port + _u2x);
/* Bind our socket addresss to the
listening socket, and call listen() */
if ( bind(list_s, (struct sockaddr *) &servaddr, sizeof(servaddr)) < 0 ) {
fprintf(stderr, "ECHOSERV: Error calling bind()\n");
exit(EXIT_FAILURE);
}
if ( listen(list_s, 5) < 0 ) {
fprintf(stderr, "ECHOSERV: Error calling listen()\n");
exit(EXIT_FAILURE);
}
clilen = sizeof(cli_addr);
fprintf(stdout, "Listerning on port %i\n",port + _u2x);
fflush(stdout);
if ( (conn_s = accept(list_s, NULL, NULL) ) < 0 ) {
fprintf(stderr, "ECHOSERV: Error calling accept()\n");
exit(EXIT_FAILURE);
}
fcntl(conn_s, F_SETFL, O_NONBLOCK);
}
tcp_start_connection(_u2x, _u2x == 0?true:false);
}
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
@ -165,49 +214,65 @@ void FastSerial::end()
int FastSerial::available(void)
{
if (_u2x != 0) return 0;
struct tcp_state *s = &tcp_state[_u2x];
check_connection(s);
if (!s->connected) {
return 0;
}
if (select_check(s->fd)) {
#ifdef FIONREAD
// use FIONREAD to get exact value if possible
int num_ready;
fd_set socks;
struct timeval t;
FD_ZERO(&socks);
FD_SET(conn_s, &socks);
t.tv_sec = 0;
t.tv_usec = 500;
if (int ans = select(conn_s + 1, &socks, NULL, NULL,&t))
{
//FD_ZERO(&socks);
//FD_SET(conn_s, &socks);
//if (FD_ISSET(conn_s, &socks)) {
return 1;
// }
if (ioctl(s->fd, FIONREAD, &num_ready) == 0) {
if (num_ready > BUFFER_SIZE) {
return BUFFER_SIZE;
}
if (num_ready == 0) {
// EOF is reached
fprintf(stdout, "Closed connection on serial port %u\n", s->serial_port);
close(s->fd);
s->connected = false;
return 0;
}
return num_ready;
}
#endif
return 1; // best we can do is say 1 byte available
}
return 0;
}
int FastSerial::txspace(void)
{
return 128;
// always claim there is space available
return BUFFER_SIZE;
}
int FastSerial::read(void)
{
if (_u2x != 0) {
struct tcp_state *s = &tcp_state[_u2x];
char c;
if (available() <= 0) {
return -1;
}
char c;
int n = myread();
if (n == 0) {
if ( (conn_s = accept(list_s, NULL, NULL) ) < 0 ) {
fprintf(stderr, "ECHOSERV: Error calling accept()\n");
exit(EXIT_FAILURE);
int n = recv(s->fd, &c, 1, MSG_DONTWAIT | MSG_NOSIGNAL);
if (n <= 0) {
// the socket has reached EOF
close(s->fd);
s->connected = false;
fprintf(stdout, "Closed connection on serial port %u\n", s->serial_port);
fflush(stdout);
return -1;
}
fcntl(conn_s, F_SETFL, O_NONBLOCK);
if (n == 1) {
return (int)c;
}
return (int)buffer[0];
return -1;
}
int FastSerial::peek(void)
@ -221,14 +286,12 @@ void FastSerial::flush(void)
void FastSerial::write(uint8_t c)
{
if (_u2x != 0) {
struct tcp_state *s = &tcp_state[_u2x];
check_connection(s);
if (!s->connected) {
return;
}
mywrite(c);
if (c >= '\n' && c <= 128) {
fwrite(&c, 1, 1, stdout);
fflush(stdout);
}
send(s->fd, &c, 1, MSG_DONTWAIT | MSG_NOSIGNAL);
}
// Buffer management ///////////////////////////////////////////////////////////