This commit is contained in:
James Goppert 2011-11-24 14:28:25 -05:00
commit 29b7eb12a7
102 changed files with 6330 additions and 2755 deletions

View File

@ -41,9 +41,6 @@
#define ACCEL_ALT_HOLD 0 // disabled by default, work in progress
// See the config.h and defines.h files for how to set this up!
//
// lets use Manual throttle during Loiter
//#define LOITER_THR THROTTLE_MANUAL
# define RTL_YAW YAW_HOLD

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V2.0.50 Beta"
#define THISFIRMWARE "ArduCopter V2.0.51"
/*
ArduCopter Version 2.0 Beta
Authors: Jason Short
@ -260,7 +260,12 @@ static byte control_mode = STABILIZE;
static byte old_control_mode = STABILIZE;
static byte oldSwitchPosition; // for remembering the control mode switch
static int16_t motor_out[8];
static bool do_simple = false;
static bool do_simple = false;
static int16_t rc_override[8] = {0,0,0,0,0,0,0,0};
static bool rc_override_active = false;
static uint32_t rc_override_fs_timer = 0;
// Heli
// ----
@ -480,6 +485,7 @@ static int32_t perf_mon_timer;
//static float imu_health; // Metric based on accel gain deweighting
static int16_t gps_fix_count;
static byte gps_watchdog;
static int pmTest1;
// System Timers
// --------------
@ -1051,7 +1057,7 @@ void update_throttle_mode(void)
case THROTTLE_MANUAL:
if (g.rc_3.control_in > 0){
#if FRAME_CONFIG == HELI_FRAME
g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.rc_3.control_in));
g.rc_3.servo_out = heli_get_angle_boost(g.rc_3.control_in);
#else
angle_boost = get_angle_boost(g.rc_3.control_in);
g.rc_3.servo_out = g.rc_3.control_in + angle_boost;
@ -1071,34 +1077,39 @@ void update_throttle_mode(void)
// fall through
case THROTTLE_AUTO:
// 10hz, don't run up i term
if(invalid_throttle && motor_auto_armed == true){
// how far off are we
altitude_error = get_altitude_error();
// get the AP throttle
nav_throttle = get_nav_throttle(altitude_error);//, 250); //150 = target speed of 1.5m/s
//Serial.printf("in:%d, cr:%d, NT:%d, I:%1.4f\n", g.rc_3.control_in,altitude_error, nav_throttle, g.pi_throttle.get_integrator());
// clear the new data flag
invalid_throttle = false;
}
// calculate angle boost
angle_boost = get_angle_boost(g.throttle_cruise);
// manual command up or down?
if(manual_boost != 0){
//remove alt_hold_velocity when implemented
#if FRAME_CONFIG == HELI_FRAME
g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.throttle_cruise + nav_throttle + manual_boost + get_z_damping()));
g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + manual_boost + get_z_damping());
#else
g.rc_3.servo_out = g.throttle_cruise + angle_boost + manual_boost + get_z_damping();
#endif
// reset next_WP.alt
next_WP.alt = max(current_loc.alt, 100);
}else{
// 10hz, don't run up i term
if(invalid_throttle && motor_auto_armed == true){
// how far off are we
altitude_error = get_altitude_error();
// get the AP throttle
nav_throttle = get_nav_throttle(altitude_error);
// clear the new data flag
invalid_throttle = false;
}
#if FRAME_CONFIG == HELI_FRAME
//g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + nav_throttle + get_z_damping());
g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.throttle_cruise + nav_throttle + get_z_damping()));
g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + nav_throttle + get_z_damping());
#else
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost + get_z_damping();
#endif
@ -1244,14 +1255,23 @@ static void update_altitude()
#else
// This is real life
// calc the vertical accel rate
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
old_baro_alt = temp_baro_alt;
// read in Actual Baro Altitude
baro_alt = (baro_alt + read_barometer()) >> 1;
// calc the vertical accel rate
#if CLIMB_RATE_BARO == 0
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 2; // invert and scale
temp_baro_alt = (float)temp_baro_alt * .1 + (float)old_baro_alt * .9;
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
old_baro_alt = temp_baro_alt;
#else
baro_rate = (baro_alt - old_baro_alt) * 10;
old_baro_alt = baro_alt;
#endif
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
#endif
@ -1386,7 +1406,7 @@ static void tuning(){
break;
case CH6_THROTTLE_KP:
g.rc_6.set_range(0,1000);
g.rc_6.set_range(0,1000); // 0 to 1
g.pi_throttle.kP(tuning_value);
break;
@ -1424,6 +1444,11 @@ static void tuning(){
g.heli_ext_gyro_gain = tuning_value * 1000;
break;
#endif
case CH6_THR_HOLD_KP:
g.rc_6.set_range(0,1000); // 0 to 1
g.pi_alt_hold.kP(tuning_value);
break;
}
}
@ -1466,8 +1491,8 @@ static void update_nav_wp()
if (circle_angle > 6.28318531)
circle_angle -= 6.28318531;
target_WP.lng = next_WP.lng + (g.loiter_radius * cos(1.57 - circle_angle) * scaleLongUp);
target_WP.lat = next_WP.lat + (g.loiter_radius * sin(1.57 - circle_angle));
target_WP.lng = next_WP.lng + (g.loiter_radius * 100 * cos(1.57 - circle_angle) * scaleLongUp);
target_WP.lat = next_WP.lat + (g.loiter_radius * 100 * sin(1.57 - circle_angle));
// calc the lat and long error to the target
calc_location_error(&target_WP);

View File

@ -133,7 +133,6 @@ static void reset_hold_I(void)
{
g.pi_loiter_lat.reset_I();
g.pi_loiter_lon.reset_I();
g.pi_crosstrack.reset_I();
}
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.

File diff suppressed because it is too large Load Diff

View File

@ -980,7 +980,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// set frame of waypoint
uint8_t frame;
if (tell_command.options & WP_OPTION_ALT_RELATIVE) {
if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) {
frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; // reference frame
} else {
frame = MAV_FRAME_GLOBAL; // reference frame
@ -1294,7 +1294,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
guided_WP = tell_command;
// add home alt if needed
if (guided_WP.options & WP_OPTION_ALT_RELATIVE){
if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT){
guided_WP.alt += home.alt;
}
@ -1322,7 +1322,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
if(packet.seq != 0)
set_command_with_index(tell_command, packet.seq);
set_cmd_with_index(tell_command, packet.seq);
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
@ -1367,6 +1367,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// find the requested parameter
vp = AP_Var::find(key);
if ((NULL != vp) && // exists
!isnan(packet.param_value) && // not nan
!isinf(packet.param_value)) { // not inf
@ -1382,19 +1383,27 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// handle variables with standard type IDs
if (var_type == AP_Var::k_typeid_float) {
((AP_Float *)vp)->set_and_save(packet.param_value);
Log_Write_Data(1, (float)((AP_Float *)vp)->get());
} else if (var_type == AP_Var::k_typeid_float16) {
((AP_Float16 *)vp)->set_and_save(packet.param_value);
Log_Write_Data(2, (float)((AP_Float *)vp)->get());
} else if (var_type == AP_Var::k_typeid_int32) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
Log_Write_Data(3, (int32_t)((AP_Float *)vp)->get());
} else if (var_type == AP_Var::k_typeid_int16) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
Log_Write_Data(4, (int32_t)((AP_Float *)vp)->get());
} else if (var_type == AP_Var::k_typeid_int8) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
Log_Write_Data(5, (int32_t)((AP_Float *)vp)->get());
} else {
// we don't support mavlink set on this parameter
break;
@ -1410,6 +1419,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
vp->cast_to_float(),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
}
break;

View File

@ -20,8 +20,8 @@ static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
// This is the help function
// PSTR is an AVR macro to read strings from flash memory
// printf_P is a version of print_f that reads from flash memory
static int8_t help_log(uint8_t argc, const Menu::arg *argv)
{
//static int8_t help_log(uint8_t argc, const Menu::arg *argv)
/*{
Serial.printf_P(PSTR("\n"
"Commands:\n"
" dump <n>"
@ -30,7 +30,7 @@ static int8_t help_log(uint8_t argc, const Menu::arg *argv)
" disable <name> | all\n"
"\n"));
return 0;
}
}*/
// Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM.
@ -40,8 +40,7 @@ const struct Menu::command log_menu_commands[] PROGMEM = {
{"dump", dump_log},
{"erase", erase_logs},
{"enable", select_logs},
{"disable", select_logs},
{"help", help_log}
{"disable", select_logs}
};
// A Macro to create the Menu
@ -698,15 +697,16 @@ static void Log_Write_Control_Tuning()
DataFlash.WriteInt(angle_boost); //8
DataFlash.WriteInt(manual_boost); //9
DataFlash.WriteInt(climb_rate); //10
//#if HIL_MODE == HIL_MODE_ATTITUDE
// DataFlash.WriteInt(0); //10
//#else
// DataFlash.WriteInt((int)(barometer.RawPress - barometer._offset_press));//10
//#endif
DataFlash.WriteInt(g.rc_3.servo_out); //11
DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); //12
DataFlash.WriteInt(g.pi_throttle.get_integrator()); //13
#if HIL_MODE == HIL_MODE_ATTITUDE
DataFlash.WriteInt(0); //11
#else
DataFlash.WriteInt((int)(barometer.RawPress - barometer._offset_press));//11
#endif
DataFlash.WriteInt(g.rc_3.servo_out); //12
DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); //13
DataFlash.WriteInt(g.pi_throttle.get_integrator()); //14
DataFlash.WriteByte(END_BYTE);
}
@ -718,7 +718,7 @@ static void Log_Read_Control_Tuning()
Serial.printf_P(PSTR("CTUN, "));
for(int8_t i = 1; i < 13; i++ ){
for(int8_t i = 1; i < 14; i++ ){
temp = DataFlash.ReadInt();
Serial.printf("%d, ", temp);
}
@ -901,6 +901,29 @@ static void Log_Read_Startup()
Serial.printf_P(PSTR("START UP\n"));
}
static void Log_Write_Data(int8_t _type, float _data)
{
Log_Write_Data(_type, (int32_t)(_data * 1000));
}
static void Log_Write_Data(int8_t _type, int32_t _data)
{
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_DATA_MSG);
DataFlash.WriteByte(_type);
DataFlash.WriteLong(_data);
DataFlash.WriteByte(END_BYTE);
}
// Read a mode packet
static void Log_Read_Data()
{
int8_t temp1 = DataFlash.ReadByte();
int32_t temp2 = DataFlash.ReadLong();
Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp2);
}
// Read the DataFlash log memory : Packet Parser
static void Log_Read(int start_page, int end_page)
@ -981,6 +1004,10 @@ static void Log_Read(int start_page, int end_page)
case LOG_GPS_MSG:
Log_Read_GPS();
break;
case LOG_DATA_MSG:
Log_Read_Data();
break;
}
break;
}
@ -1000,6 +1027,8 @@ static void Log_Write_Raw() {}
static void Log_Write_GPS() {}
static void Log_Write_Current() {}
static void Log_Write_Attitude() {}
static void Log_Write_Data(int8_t _type, float _data){}
static void Log_Write_Data(int8_t _type, int32_t _data){}
#ifdef OPTFLOW_ENABLED
static void Log_Write_Optflow() {}
#endif

View File

@ -17,7 +17,7 @@ public:
// The increment will prevent old parameters from being used incorrectly
// by newer code.
//
static const uint16_t k_format_version = 112;
static const uint16_t k_format_version = 113;
// The parameter software_type is set up solely for ground station use
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
@ -55,7 +55,8 @@ public:
// Misc
//
k_param_log_bitmask,
k_param_log_bitmask = 20,
k_param_log_last_filenumber,
#if FRAME_CONFIG == HELI_FRAME
//
@ -107,8 +108,8 @@ public:
//
// 160: Navigation parameters
//
k_param_crosstrack_entry_angle = 160,
k_param_RTL_altitude,
k_param_RTL_altitude = 160,
k_param_crosstrack_gain,
//
// 180: Radio settings
@ -171,7 +172,6 @@ public:
k_param_pi_nav_lon,
k_param_pi_alt_hold,
k_param_pi_throttle,
k_param_pi_crosstrack,
k_param_pi_acro_roll,
k_param_pi_acro_pitch,
@ -189,9 +189,14 @@ public:
AP_Int8 serial3_baud;
// Crosstrack navigation
//
AP_Int16 crosstrack_entry_angle;
AP_Int16 RTL_altitude;
AP_Int8 sonar_enabled;
AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current
AP_Int16 pack_capacity; // Battery pack capacity less reserve
AP_Int8 compass_enabled;
AP_Int8 optflow_enabled;
AP_Float input_voltage;
AP_Float low_voltage;
// Waypoints
//
@ -202,6 +207,7 @@ public:
AP_Int8 waypoint_radius;
AP_Int16 loiter_radius;
AP_Int16 waypoint_speed_max;
AP_Float crosstrack_gain;
// Throttle
//
@ -222,30 +228,16 @@ public:
AP_Int8 flight_mode6;
AP_Int8 simple_modes;
// Radio settings
//
//AP_Var_group pwm_roll;
//AP_Var_group pwm_pitch;
//AP_Var_group pwm_throttle;
//AP_Var_group pwm_yaw;
// Misc
//
AP_Int16 log_bitmask;
AP_Int16 RTL_altitude;
AP_Int16 log_last_filenumber;
AP_Int8 sonar_enabled;
AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current
AP_Int16 pack_capacity; // Battery pack capacity less reserve
AP_Int8 compass_enabled;
AP_Int8 esc_calibrate;
AP_Int8 radio_tuning;
AP_Int8 frame_orientation;
AP_Float top_bottom_ratio;
AP_Int8 optflow_enabled;
AP_Float input_voltage;
AP_Float low_voltage;
#if FRAME_CONFIG == HELI_FRAME
// Heli
@ -272,6 +264,7 @@ public:
RC_Channel rc_8;
RC_Channel rc_camera_pitch;
RC_Channel rc_camera_roll;
AP_Float camera_pitch_gain;
AP_Float camera_roll_gain;
@ -292,7 +285,6 @@ public:
APM_PI pi_alt_hold;
APM_PI pi_throttle;
APM_PI pi_crosstrack;
APM_PI pi_acro_roll;
APM_PI pi_acro_pitch;
@ -310,9 +302,7 @@ public:
sysid_my_gcs (255, k_param_sysid_my_gcs, PSTR("SYSID_MYGCS")),
serial3_baud (SERIAL3_BAUD/1000, k_param_serial3_baud, PSTR("SERIAL3_BAUD")),
//crosstrack_gain (XTRACK_GAIN * 100, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
crosstrack_entry_angle (XTRACK_ENTRY_ANGLE * 100, k_param_crosstrack_entry_angle, PSTR("XTRK_ANGLE_CD")),
RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
sonar_enabled (DISABLED, k_param_sonar, PSTR("SONAR_ENABLE")),
battery_monitoring (DISABLED, k_param_battery_monitoring, PSTR("BATT_MONITOR")),
pack_capacity (HIGH_DISCHARGE, k_param_pack_capacity, PSTR("BATT_CAPACITY")),
@ -326,8 +316,9 @@ public:
command_index (0, k_param_command_index, PSTR("WP_INDEX")),
command_nav_index (0, k_param_command_nav_index, PSTR("WP_MUST_INDEX")),
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
crosstrack_gain (CROSSTRACK_GAIN, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
throttle_min (0, k_param_throttle_min, PSTR("THR_MIN")),
throttle_max (1000, k_param_throttle_max, PSTR("THR_MAX")),
@ -345,7 +336,7 @@ public:
simple_modes (0, k_param_simple_modes, PSTR("SIMPLE")),
log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")),
RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
log_last_filenumber (0, k_param_log_last_filenumber, PSTR("LOG_LASTFILE")),
esc_calibrate (0, k_param_esc_calibrate, PSTR("ESC")),
radio_tuning (0, k_param_radio_tuning, PSTR("TUNE")),
frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")),
@ -408,7 +399,6 @@ public:
pi_alt_hold (k_param_pi_alt_hold, PSTR("THR_ALT_"), THR_HOLD_P, THR_HOLD_I, THR_HOLD_IMAX),
pi_throttle (k_param_pi_throttle, PSTR("THR_RATE_"), THROTTLE_P, THROTTLE_I, THROTTLE_IMAX),
pi_crosstrack (k_param_pi_crosstrack, PSTR("XTRACK_"), XTRACK_P, XTRACK_I, XTRACK_IMAX),
pi_acro_roll (k_param_pi_acro_roll, PSTR("ACRO_RLL_"), ACRO_ROLL_P, ACRO_ROLL_I, ACRO_ROLL_IMAX * 100),
pi_acro_pitch (k_param_pi_acro_pitch, PSTR("ACRO_PIT_"), ACRO_PITCH_P, ACRO_PITCH_I, ACRO_PITCH_IMAX * 100),

View File

@ -50,7 +50,7 @@ static struct Location get_cmd_with_index(int i)
}
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
//if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & WP_OPTION_ALT_RELATIVE){
//if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & MASK_OPTIONS_RELATIVE_ALT){
//temp.alt += home.alt;
//}
@ -65,8 +65,9 @@ static struct Location get_cmd_with_index(int i)
// Setters
// -------
static void set_command_with_index(struct Location temp, int i)
static void set_cmd_with_index(struct Location temp, int i)
{
i = constrain(i, 0, g.command_total.get());
//Serial.printf("set_command: %d with id: %d\n", i, temp.id);
@ -203,7 +204,7 @@ static void init_home()
// Save Home to EEPROM
// -------------------
// no need to save this to EPROM
set_command_with_index(home, 0);
set_cmd_with_index(home, 0);
print_wp(&home, 0);
// Save prev loc this makes the calcs look better before commands are loaded

View File

@ -222,7 +222,7 @@ static void do_takeoff()
Location temp = current_loc;
// command_nav_queue.alt is a relative altitude!!!
if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) {
if (command_nav_queue.options & MASK_OPTIONS_RELATIVE_ALT) {
temp.alt = command_nav_queue.alt + home.alt;
//Serial.printf("rel alt: %ld",temp.alt);
} else {
@ -242,7 +242,7 @@ static void do_nav_wp()
wp_control = WP_MODE;
// command_nav_queue.alt is a relative altitude!!!
if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) {
if (command_nav_queue.options & MASK_OPTIONS_RELATIVE_ALT) {
command_nav_queue.alt += home.alt;
}
set_next_WP(&command_nav_queue);
@ -258,7 +258,7 @@ static void do_nav_wp()
loiter_time_max = command_nav_queue.p1 * 1000;
// if we don't require an altitude minimum, we save this flag as passed (1)
if((next_WP.options & WP_OPTION_ALT_REQUIRED) == 0){
if((next_WP.options & MASK_OPTIONS_RELATIVE_ALT) == 0){
// we don't need to worry about it
wp_verify_byte |= NAV_ALTITUDE;
}
@ -383,7 +383,7 @@ static bool verify_land()
static bool verify_nav_wp()
{
// Altitude checking
if(next_WP.options & WP_OPTION_ALT_REQUIRED){
if(next_WP.options & MASK_OPTIONS_RELATIVE_ALT){
// we desire a certain minimum altitude
if (current_loc.alt > next_WP.alt){
// we have reached that altitude

View File

@ -71,7 +71,7 @@
//
#ifndef CH7_OPTION
# define CH7_OPTION CH7_SET_HOVER
# define CH7_OPTION CH7_SAVE_WP
#endif
@ -343,7 +343,7 @@
// RTL Mode
#ifndef RTL_YAW
# define RTL_YAW YAW_AUTO
# define RTL_YAW YAW_HOLD
#endif
#ifndef RTL_RP
@ -519,7 +519,7 @@
// RATE control
#ifndef THROTTLE_P
# define THROTTLE_P 1.0 //
# define THROTTLE_P 0.5 //
#endif
#ifndef THROTTLE_I
# define THROTTLE_I 0.0 //
@ -532,24 +532,10 @@
//////////////////////////////////////////////////////////////////////////////
// Crosstrack compensation
//
#ifndef XTRACK_ENTRY_ANGLE
# define XTRACK_ENTRY_ANGLE 30 // deg
#ifndef CROSSTRACK_GAIN
# define CROSSTRACK_GAIN 4
#endif
#ifndef XTRACK_P
# define XTRACK_P 2 // trying a lower val
#endif
#ifndef XTRACK_I
# define XTRACK_I 0.00 //with 4m error, 12.5s windup
#endif
#ifndef XTRACK_D
# define XTRACK_D 0.00 // upped with filter
#endif
#ifndef XTRACK_IMAX
# define XTRACK_IMAX 10
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////

View File

@ -107,7 +107,7 @@ static void read_trim_switch()
current_loc.id = MAV_CMD_NAV_WAYPOINT;
// save command
set_command_with_index(current_loc, CH7_wp_index);
set_cmd_with_index(current_loc, CH7_wp_index);
// save the index
g.command_total.set_and_save(CH7_wp_index + 1);

View File

@ -120,6 +120,8 @@
#define POSITION 8 // AUTO control
#define NUM_MODES 9
#define INITIALISING 9 // in startup routines
#define SIMPLE_1 1
#define SIMPLE_2 2
#define SIMPLE_3 4
@ -138,7 +140,7 @@
#define CH6_RATE_KP 4
#define CH6_RATE_KI 5
#define CH6_YAW_RATE_KP 6
// Altitude
// Altitude rate controller
#define CH6_THROTTLE_KP 7
// Extras
#define CH6_TOP_BOTTOM_RATIO 8
@ -149,6 +151,9 @@
#define CH6_LOITER_P 12
#define CH6_HELI_EXTERNAL_GYRO 13
// altitude controller
#define CH6_THR_HOLD_KP 14
// nav byte mask
// -------------
#define NAV_LOCATION 1
@ -166,14 +171,14 @@
#define CIRCLE_MODE 3
// Waypoint options
#define WP_OPTION_ALT_RELATIVE 1
#define WP_OPTION_ALT_CHANGE 2
#define WP_OPTION_YAW 4
#define WP_OPTION_ALT_REQUIRED 8
#define WP_OPTION_RELATIVE 16
#define MASK_OPTIONS_RELATIVE_ALT 1
#define WP_OPTION_ALT_CHANGE 2
#define WP_OPTION_YAW 4
#define WP_OPTION_ALT_REQUIRED 8
#define WP_OPTION_RELATIVE 16
//#define WP_OPTION_ 32
//#define WP_OPTION_ 64
#define WP_OPTION_NEXT_CMD 128
#define WP_OPTION_NEXT_CMD 128
//repeating events
#define NO_REPEAT 0
@ -236,6 +241,7 @@ enum gcs_severity {
#define LOG_STARTUP_MSG 0x0A
#define LOG_MOTORS_MSG 0x0B
#define LOG_OPTFLOW_MSG 0x0C
#define LOG_DATA_MSG 0x0D
#define LOG_INDEX_MSG 0xF0
#define MAX_NUM_LOGS 50
@ -332,6 +338,8 @@ enum gcs_severity {
#define B_LED_PIN 36
#define C_LED_PIN 35
// RADIANS
#define RADX100 0.000174533
// EEPROM addresses
#define EEPROM_MAX_ADDR 4096

View File

@ -5,8 +5,8 @@
#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz
#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz
static float heli_throttle_scaler = 0;
static bool heli_swash_initialised = false;
static int heli_throttle_mid = 0; // throttle mid point in pwm form (i.e. 0 ~ 1000)
// heli_servo_averaging:
// 0 or 1 = no averaging, 250hz
@ -19,8 +19,6 @@ static bool heli_swash_initialised = false;
static void heli_init_swash()
{
int i;
int tilt_max[CH_3+1];
int total_tilt_max = 0;
// swash servo initialisation
g.heli_servo_1.set_range(0,1000);
@ -38,23 +36,38 @@ static void heli_init_swash()
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
// collective min / max
total_tilt_max = 0;
for( i=CH_1; i<=CH_3; i++ ) {
tilt_max[i] = max(abs(heli_rollFactor[i]*g.heli_roll_max), abs(heli_pitchFactor[i]*g.heli_pitch_max))/100;
total_tilt_max = max(total_tilt_max,tilt_max[i]);
// ensure g.heli_coll values are reasonable
if( g.heli_coll_min >= g.heli_coll_max ) {
g.heli_coll_min = 1000;
g.heli_coll_max = 2000;
}
// servo min/max values - or should I use set_range?
g.heli_servo_1.radio_min = g.heli_coll_min - tilt_max[CH_1];
g.heli_servo_1.radio_max = g.heli_coll_max + tilt_max[CH_1];
g.heli_servo_2.radio_min = g.heli_coll_min - tilt_max[CH_2];
g.heli_servo_2.radio_max = g.heli_coll_max + tilt_max[CH_2];
g.heli_servo_3.radio_min = g.heli_coll_min - tilt_max[CH_3];
g.heli_servo_3.radio_max = g.heli_coll_max + tilt_max[CH_3];
// scaler for changing channel 3 radio input into collective range
heli_throttle_scaler = ((float)(g.heli_coll_max - g.heli_coll_min))/1000;
g.heli_coll_mid = constrain(g.heli_coll_mid, g.heli_coll_min, g.heli_coll_max);
// servo min/max values
if( g.heli_servo_1.get_reverse() ) {
g.heli_servo_1.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_1.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_1.radio_trim-1500);
}else{
g.heli_servo_1.radio_min = g.heli_coll_min + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_1.radio_max = g.heli_coll_max + (g.heli_servo_1.radio_trim-1500);
}
if( g.heli_servo_2.get_reverse() ) {
g.heli_servo_2.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_2.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_2.radio_trim-1500);
}else{
g.heli_servo_2.radio_min = g.heli_coll_min + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_2.radio_max = g.heli_coll_max + (g.heli_servo_2.radio_trim-1500);
}
if( g.heli_servo_3.get_reverse() ) {
g.heli_servo_3.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_3.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_3.radio_trim-1500);
}else{
g.heli_servo_3.radio_min = g.heli_coll_min + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_3.radio_max = g.heli_coll_max + (g.heli_servo_3.radio_trim-1500);
}
// calculate throttle mid point
heli_throttle_mid = (g.heli_coll_mid-g.heli_coll_min)*(1000.0/(g.heli_coll_max-g.heli_coll_min));
// reset the servo averaging
for( i=0; i<=3; i++ )
@ -72,7 +85,7 @@ static void heli_init_swash()
static void heli_move_servos_to_mid()
{
heli_move_swash(0,0,1500,0);
heli_move_swash(0,0,500,0);
}
//
@ -80,7 +93,7 @@ static void heli_move_servos_to_mid()
// - expected ranges:
// roll : -4500 ~ 4500
// pitch: -4500 ~ 4500
// collective: 1000 ~ 2000
// collective: 0 ~ 1000
// yaw: -4500 ~ 4500
//
static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
@ -92,6 +105,29 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
// we must be in set-up mode so mark swash as uninitialised
heli_swash_initialised = false;
// free up servo ranges
if( g.heli_servo_1.get_reverse() ) {
g.heli_servo_1.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_1.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_1.radio_trim-1500);
}else{
g.heli_servo_1.radio_min = g.rc_3.radio_min + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_1.radio_max = g.rc_3.radio_max + (g.heli_servo_1.radio_trim-1500);
}
if( g.heli_servo_2.get_reverse() ) {
g.heli_servo_2.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_2.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_2.radio_trim-1500);
}else{
g.heli_servo_2.radio_min = g.rc_3.radio_min + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_2.radio_max = g.rc_3.radio_max + (g.heli_servo_2.radio_trim-1500);
}
if( g.heli_servo_3.get_reverse() ) {
g.heli_servo_3.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_3.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_3.radio_trim-1500);
}else{
g.heli_servo_3.radio_min = g.rc_3.radio_min + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_3.radio_max = g.rc_3.radio_max + (g.heli_servo_3.radio_trim-1500);
}
}else{ // regular flight mode
// check if we need to reinitialise the swash
@ -102,7 +138,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
// ensure values are acceptable:
roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max);
coll_out = constrain(coll_out, 0, 1000);
// rudder feed forward based on collective
#if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator
@ -113,9 +149,9 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
}
// swashplate servos
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out + (g.heli_servo_1.radio_trim-1500);
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_4.servo_out = yaw_out + yaw_offset;
// use servo_out to calculate pwm_out and radio_out
@ -130,7 +166,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
heli_servo_out[2] += g.heli_servo_3.radio_out;
heli_servo_out[3] += g.heli_servo_4.radio_out;
heli_servo_out_count++;
// is it time to move the servos?
if( heli_servo_out_count >= g.heli_servo_averaging ) {
@ -171,8 +207,8 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR5 = 8000; // 250 hz output CH 1, 2, 9
ICR1 = 8000; // 250 hz output CH 3, 4, 10
ICR3 = 40000; // 50 hz output CH 7, 8, 11
#endif
}
@ -194,7 +230,7 @@ static void output_motors_armed()
g.rc_3.calc_pwm();
g.rc_4.calc_pwm();
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out );
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.servo_out, g.rc_4.servo_out );
}
// for helis - armed or disarmed we allow servos to move
@ -212,25 +248,16 @@ static void output_motor_test()
{
}
// heli_get_scaled_throttle - user's throttle scaled to collective range
// input is expected to be in the range of 0~1000 (ie. pwm)
// also does equivalent of angle_boost
static int heli_get_scaled_throttle(int throttle)
{
float scaled_throttle = (g.heli_coll_min - 1000) + throttle * heli_throttle_scaler;
return scaled_throttle;
}
// heli_angle_boost - takes servo_out position
// adds a boost depending on roll/pitch values
// heli_angle_boost - adds a boost depending on roll/pitch values
// equivalent of quad's angle_boost function
// pwm_out value should be 0 ~ 1000
static int heli_get_angle_boost(int pwm_out)
// throttle value should be 0 ~ 1000
static int heli_get_angle_boost(int throttle)
{
float angle_boost_factor = cos_pitch_x * cos_roll_x;
angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0);
int throttle_above_center = max(1000 + pwm_out - g.heli_coll_mid,0);
return pwm_out + throttle_above_center*angle_boost_factor;
int throttle_above_mid = max(throttle - heli_throttle_mid,0);
return throttle + throttle_above_mid*angle_boost_factor;
}
#endif // HELI_FRAME

View File

@ -67,7 +67,8 @@ static void calc_loiter(int x_error, int y_error)
int y_target_speed = g.pi_loiter_lat.get_pi(y_error, dTnav);
// find the rates:
float temp = radians((float)g_gps->ground_course/100.0);
//float temp = radians((float)g_gps->ground_course/100.0);
float temp = g_gps->ground_course * RADX100;
#ifdef OPTFLOW_ENABLED
// calc the cos of the error to tell how fast we are moving towards the target in cm
@ -172,7 +173,8 @@ static void calc_nav_rate(int max_speed)
}
// XXX target_angle should be the original desired target angle!
float temp = radians((target_bearing - g_gps->ground_course)/100.0);
//float temp = radians((target_bearing - g_gps->ground_course)/100.0);
float temp = (target_bearing - g_gps->ground_course) * RADX100;
// push us towards the original track
update_crosstrack();
@ -209,8 +211,11 @@ static void update_crosstrack(void)
// Crosstrack Error
// ----------------
if (cross_track_test() < 5000) { // If we are too far off or too close we don't do track following
crosstrack_error = sin(radians((target_bearing - original_target_bearing) / 100)) * wp_distance; // Meters we are off track line
crosstrack_error = constrain(crosstrack_error * 4, -1200, 1200);
float temp = (target_bearing - original_target_bearing) * RADX100;
//radians((target_bearing - original_target_bearing) / 100)
crosstrack_error = sin(temp) * wp_distance; // Meters we are off track line
crosstrack_error = constrain(crosstrack_error * g.crosstrack_gain, -1200, 1200);
}
}
@ -225,7 +230,9 @@ static int32_t cross_track_test()
// nav_roll, nav_pitch
static void calc_nav_pitch_roll()
{
float temp = radians((float)(9000 - (dcm.yaw_sensor - original_target_bearing))/100.0);
float temp = (9000l - (dcm.yaw_sensor - original_target_bearing)) * RADX100;
//t: 1.5465, t1: -10.9451, t2: 1.5359, t3: 1.5465
float _cos_yaw_x = cos(temp);
float _sin_yaw_y = sin(temp);

View File

@ -54,11 +54,6 @@ static void init_rc_in()
static void init_rc_out()
{
#if ARM_AT_STARTUP == 1
motor_armed = 1;
#endif
APM_RC.Init(); // APM Radio initialization
init_motors_out();
@ -74,24 +69,44 @@ static void init_rc_out()
APM_RC.OutputCh(CH_5, 1500);
APM_RC.OutputCh(CH_6, 1500);
// don't fuss if we are calibrating
if(g.esc_calibrate == 1)
return;
if(g.rc_3.radio_min <= 1200){
output_min();
}
for(byte i = 0; i < 5; i++){
delay(20);
read_radio();
}
// sanity check
// sanity check - prevent unconfigured radios from outputting
if(g.rc_3.radio_min >= 1300){
g.rc_3.radio_min = g.rc_3.radio_in;
output_min();
}
// we are full throttle
if(g.rc_3.control_in == 800){
if(g.esc_calibrate == 0){
// we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(1);
// send miinimum throttle out to ESC
output_min();
// block until we restart
while(1){
//Serial.println("esc");
delay(200);
dancing_light();
}
}else{
//Serial.println("esc init");
// clear esc flag
g.esc_calibrate.set_and_save(0);
// block until we restart
init_esc();
}
}else{
// did we abort the calibration?
if(g.esc_calibrate == 1)
g.esc_calibrate.set_and_save(0);
// send miinimum throttle out to ESC
output_min();
}
}
void output_min()

View File

@ -16,7 +16,6 @@ static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
static int8_t setup_tune (uint8_t argc, const Menu::arg *argv);
//static int8_t setup_mag_offset (uint8_t argc, const Menu::arg *argv);
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
static int8_t setup_esc (uint8_t argc, const Menu::arg *argv);
#ifdef OPTFLOW_ENABLED
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
#endif
@ -36,7 +35,6 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
{"radio", setup_radio},
{"frame", setup_frame},
{"motors", setup_motors},
{"esc", setup_esc},
{"level", setup_accel},
{"modes", setup_flightmodes},
{"battery", setup_batt_monitor},
@ -72,9 +70,9 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
if(g.rc_1.radio_min >= 1300){
delay(1000);
Serial.printf_P(PSTR("\n!Warning, your radio is not configured!"));
Serial.printf_P(PSTR("\n!Warning, radio not configured!"));
delay(1000);
Serial.printf_P(PSTR("\n Type 'radio' to configure now.\n\n"));
Serial.printf_P(PSTR("\n Type 'radio' now.\n\n"));
}
// Run the setup menu. When the menu exits, we will return to the main menu.
@ -122,7 +120,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
{
int c;
Serial.printf_P(PSTR("\n'Y' + Enter to factory reset, any other key to abort:\n"));
Serial.printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n"));
do {
c = Serial.read();
@ -192,7 +190,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
g.rc_8.radio_trim = 1500;
Serial.printf_P(PSTR("\nMove all controls to each extreme. Hit Enter to save: "));
Serial.printf_P(PSTR("\nMove all controls to extremes. Enter to save: "));
while(1){
delay(20);
@ -230,29 +228,6 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
return(0);
}
static int8_t
setup_esc(uint8_t argc, const Menu::arg *argv)
{
Serial.printf_P(PSTR("\nESC Calibration:\n"
"-1 Unplug USB and battery\n"
"-2 Move CLI/FLY switch to FLY mode\n"
"-3 Move throttle to max, connect battery\n"
"-4 After two long beeps, throttle to 0, then test\n\n"
" Press Enter to cancel.\n"));
g.esc_calibrate.set_and_save(1);
while(1){
delay(20);
if(Serial.available() > 0){
g.esc_calibrate.set_and_save(0);
return(0);
}
}
}
static int8_t
setup_motors(uint8_t argc, const Menu::arg *argv)
{
@ -288,7 +263,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv)
} else if (!strcmp_P(argv[1].str, PSTR("v"))) {
g.frame_orientation.set_and_save(V_FRAME);
}else{
Serial.printf_P(PSTR("\nOptions:[x,+,v]\n"));
Serial.printf_P(PSTR("\nOp:[x,+,v]\n"));
report_frame();
return 0;
}
@ -304,7 +279,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
byte _oldSwitchPosition = 0;
byte mode = 0;
Serial.printf_P(PSTR("\nMove mode switch to edit, aileron: select modes, rudder: Simple on/off\n"));
Serial.printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n"));
print_hit_enter();
while(1){
@ -406,7 +381,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
g.compass_enabled.set_and_save(false);
}else{
Serial.printf_P(PSTR("\nOptions:[on,off]\n"));
Serial.printf_P(PSTR("\nOp:[on,off]\n"));
report_compass();
return 0;
}
@ -426,7 +401,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
g.battery_monitoring.set_and_save(argv[1].i);
} else {
Serial.printf_P(PSTR("\nOptions: off, 1-4"));
Serial.printf_P(PSTR("\nOp: off, 1-4"));
}
report_batt_monitor();
@ -443,7 +418,7 @@ setup_sonar(uint8_t argc, const Menu::arg *argv)
g.sonar_enabled.set_and_save(false);
}else{
Serial.printf_P(PSTR("\nOptions:[on, off]\n"));
Serial.printf_P(PSTR("\nOp:[on, off]\n"));
report_sonar();
return 0;
}
@ -494,7 +469,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
// read radio although we don't use it yet
read_radio();
// allow swash plate to move
output_motors_armed();
@ -691,7 +666,7 @@ setup_gyro(uint8_t argc, const Menu::arg *argv)
g.heli_ext_gyro_gain.save();
}else{
Serial.printf_P(PSTR("\nOptions:[on, off] gain\n"));
Serial.printf_P(PSTR("\nOp:[on, off] gain\n"));
}
report_gyro();
@ -783,7 +758,7 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
g.optflow_enabled = false;
}else{
Serial.printf_P(PSTR("\nOptions:[on, off]\n"));
Serial.printf_P(PSTR("\nOp:[on, off]\n"));
report_optflow();
return 0;
}
@ -801,12 +776,12 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
static void report_batt_monitor()
{
Serial.printf_P(PSTR("\nBatt Mointor\n"));
Serial.printf_P(PSTR("\nBatt Mon:\n"));
print_divider();
if(g.battery_monitoring == 0) print_enabled(false);
if(g.battery_monitoring == 1) Serial.printf_P(PSTR("3 cells"));
if(g.battery_monitoring == 2) Serial.printf_P(PSTR("4 cells"));
if(g.battery_monitoring == 3) Serial.printf_P(PSTR("batt volts"));
if(g.battery_monitoring == 1) Serial.printf_P(PSTR("3c"));
if(g.battery_monitoring == 2) Serial.printf_P(PSTR("4c"));
if(g.battery_monitoring == 3) Serial.printf_P(PSTR("volts"));
if(g.battery_monitoring == 4) Serial.printf_P(PSTR("volts and cur"));
print_blanks(2);
}
@ -897,7 +872,7 @@ static void report_compass()
Vector3f offsets = compass.get_offsets();
// mag offsets
Serial.printf_P(PSTR("Mag offsets: %4.4f, %4.4f, %4.4f"),
Serial.printf_P(PSTR("Mag off: %4.4f, %4.4f, %4.4f"),
offsets.x,
offsets.y,
offsets.z);
@ -964,7 +939,7 @@ static void report_heli()
static void report_gyro()
{
Serial.printf_P(PSTR("External Gyro:\n"));
Serial.printf_P(PSTR("Gyro:\n"));
print_divider();
print_enabled( g.heli_ext_gyro_enabled );
@ -1018,7 +993,7 @@ print_switch(byte p, byte m, bool b)
static void
print_done()
{
Serial.printf_P(PSTR("\nSaved Settings\n\n"));
Serial.printf_P(PSTR("\nSaved\n"));
}
@ -1038,7 +1013,7 @@ static void zero_eeprom(void)
static void
print_accel_offsets(void)
{
Serial.printf_P(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\n"),
Serial.printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\n"),
(float)imu.ax(),
(float)imu.ay(),
(float)imu.az());
@ -1047,7 +1022,7 @@ print_accel_offsets(void)
static void
print_gyro_offsets(void)
{
Serial.printf_P(PSTR("Gyro offsets: %4.2f, %4.2f, %4.2f\n"),
Serial.printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"),
(float)imu.gx(),
(float)imu.gy(),
(float)imu.gz());
@ -1122,7 +1097,6 @@ static void print_enabled(boolean b)
static void
init_esc()
{
g.esc_calibrate.set_and_save(0);
while(1){
read_radio();
delay(100);
@ -1147,7 +1121,7 @@ static void print_wp(struct Location *cmd, byte index)
float t1 = (float)cmd->lat / t7;
float t2 = (float)cmd->lng / t7;
Serial.printf_P(PSTR("scommand #: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"),
Serial.printf_P(PSTR("cmd#: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"),
(int)index,
(int)cmd->id,
(int)cmd->options,
@ -1167,7 +1141,7 @@ static void report_gps()
static void report_version()
{
Serial.printf_P(PSTR("FW Version %d\n"),(int)g.format_version.get());
Serial.printf_P(PSTR("FW Ver: %d\n"),(int)g.format_version.get());
print_divider();
print_blanks(2);
}

View File

@ -184,6 +184,7 @@ static void init_ardupilot()
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
init_camera();
#if HIL_MODE != HIL_MODE_ATTITUDE
@ -217,12 +218,10 @@ static void init_ardupilot()
#ifdef USERHOOK_INIT
USERHOOK_INIT
#endif
// Logging:
// --------
// DataFlash log initialization
#if LOGGING_ENABLED == ENABLED
#if LOGGING_ENABLED == ENABLED
DataFlash.Init();
#endif
#endif
#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
// If the switch is in 'menu' mode, run the main menu.
@ -237,20 +236,16 @@ static void init_ardupilot()
run_cli();
}
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
Serial.printf_P(PSTR("\nPress ENTER 3 times for CLI\n\n"));
#endif // CLI_ENABLED
if(g.esc_calibrate == 1){
init_esc();
}
// Logging:
// --------
#if LOGGING_ENABLED == ENABLED
if(g.log_bitmask != 0){
// TODO - Here we will check on the length of the last log
// We don't want to create a bunch of little logs due to powering on and off
start_new_log();
}
#endif
GPS_enabled = false;
@ -311,6 +306,10 @@ static void init_ardupilot()
startup_ground();
Log_Write_Startup();
Log_Write_Data(10, g.pi_stabilize_roll.kP());
Log_Write_Data(11, g.pi_stabilize_pitch.kP());
Log_Write_Data(12, g.pi_rate_roll.kP());
Log_Write_Data(13, g.pi_rate_pitch.kP());
SendDebug("\nReady to FLY ");
}
@ -359,6 +358,13 @@ static void set_mode(byte mode)
return;
}
// if we don't have GPS lock
if(home_is_set == false){
// our max mode should be
if (mode > ALT_HOLD)
mode = STABILIZE;
}
old_control_mode = control_mode;
control_mode = mode;

View File

@ -4,13 +4,13 @@
// These are function definitions so the Menu can be constructed before the functions
// are defined below. Order matters to the compiler.
static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
//static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
//static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv);
//static int8_t test_stabilize(uint8_t argc, const Menu::arg *argv);
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
//static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
//static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
@ -21,7 +21,7 @@ static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
//static int8_t test_reverse(uint8_t argc, const Menu::arg *argv);
static int8_t test_tuning(uint8_t argc, const Menu::arg *argv);
static int8_t test_current(uint8_t argc, const Menu::arg *argv);
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
//static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
static int8_t test_baro(uint8_t argc, const Menu::arg *argv);
//static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
@ -54,22 +54,22 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
// User enters the string in the console to call the functions on the right.
// See class Menu in AP_Coommon for implementation details
const struct Menu::command test_menu_commands[] PROGMEM = {
{"pwm", test_radio_pwm},
// {"pwm", test_radio_pwm},
{"radio", test_radio},
// {"failsafe", test_failsafe},
// {"stabilize", test_stabilize},
{"gps", test_gps},
#if HIL_MODE != HIL_MODE_ATTITUDE
{"adc", test_adc},
// {"adc", test_adc},
#endif
{"imu", test_imu},
//{"dcm", test_dcm},
//{"omega", test_omega},
{"battery", test_battery},
{"tune", test_tuning},
{"tri", test_tri},
//{"tri", test_tri},
{"current", test_current},
{"relay", test_relay},
// {"relay", test_relay},
{"wp", test_wp},
//{"nav", test_nav},
#if HIL_MODE != HIL_MODE_ATTITUDE
@ -82,7 +82,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
#endif
//{"xbee", test_xbee},
{"eedump", test_eedump},
{"rawgps", test_rawgps},
// {"rawgps", test_rawgps},
// {"mission", test_mission},
//{"reverse", test_reverse},
//{"wp", test_wp_nav},
@ -114,8 +114,8 @@ test_eedump(uint8_t argc, const Menu::arg *argv)
return(0);
}
static int8_t
test_radio_pwm(uint8_t argc, const Menu::arg *argv)
/*static int8_t
//test_radio_pwm(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -144,10 +144,10 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
return (0);
}
}
}
}*/
static int8_t
test_tri(uint8_t argc, const Menu::arg *argv)
/*static int8_t
//test_tri(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -171,11 +171,11 @@ test_tri(uint8_t argc, const Menu::arg *argv)
return (0);
}
}
}
}*/
/*
static int8_t
test_nav(uint8_t argc, const Menu::arg *argv)
//test_nav(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -248,7 +248,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
/*
static int8_t
test_failsafe(uint8_t argc, const Menu::arg *argv)
//test_failsafe(uint8_t argc, const Menu::arg *argv)
{
#if THROTTLE_FAILSAFE
@ -303,7 +303,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
*/
/*static int8_t
test_stabilize(uint8_t argc, const Menu::arg *argv)
//test_stabilize(uint8_t argc, const Menu::arg *argv)
{
static byte ts_num;
@ -390,9 +390,10 @@ test_stabilize(uint8_t argc, const Menu::arg *argv)
}
}
*/
#if HIL_MODE != HIL_MODE_ATTITUDE
/*#if HIL_MODE != HIL_MODE_ATTITUDE
static int8_t
test_adc(uint8_t argc, const Menu::arg *argv)
//test_adc(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
Serial.printf_P(PSTR("ADC\n"));
@ -410,6 +411,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
}
}
#endif
*/
static int8_t
test_imu(uint8_t argc, const Menu::arg *argv)
@ -709,8 +711,9 @@ test_current(uint8_t argc, const Menu::arg *argv)
}
}
/*
static int8_t
test_relay(uint8_t argc, const Menu::arg *argv)
//test_relay(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -731,7 +734,7 @@ test_relay(uint8_t argc, const Menu::arg *argv)
}
}
}
*/
static int8_t
test_wp(uint8_t argc, const Menu::arg *argv)
{
@ -754,7 +757,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
return (0);
}
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) {
//static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) {
/*
print_hit_enter();
delay(1000);
@ -774,10 +777,10 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) {
}
}
*/
}
//}
/*static int8_t
test_xbee(uint8_t argc, const Menu::arg *argv)
//test_xbee(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -823,7 +826,7 @@ test_baro(uint8_t argc, const Menu::arg *argv)
/*
static int8_t
test_mag(uint8_t argc, const Menu::arg *argv)
//test_mag(uint8_t argc, const Menu::arg *argv)
{
if(g.compass_enabled) {
//Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);
@ -854,7 +857,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
*/
/*
static int8_t
test_reverse(uint8_t argc, const Menu::arg *argv)
//test_reverse(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
@ -952,7 +955,7 @@ test_optflow(uint8_t argc, const Menu::arg *argv)
/*
static int8_t
test_mission(uint8_t argc, const Menu::arg *argv)
//test_mission(uint8_t argc, const Menu::arg *argv)
{
//write out a basic mission to the EEPROM
@ -967,38 +970,38 @@ test_mission(uint8_t argc, const Menu::arg *argv)
// clear home
{Location t = {0, 0, 0, 0, 0, 0};
set_command_with_index(t,0);}
set_cmd_with_index(t,0);}
// CMD opt pitch alt/cm
{Location t = {MAV_CMD_NAV_TAKEOFF, WP_OPTION_RELATIVE, 0, 100, 0, 0};
set_command_with_index(t,1);}
set_cmd_with_index(t,1);}
if (!strcmp_P(argv[1].str, PSTR("wp"))) {
// CMD opt
{Location t = {MAV_CMD_NAV_WAYPOINT, WP_OPTION_RELATIVE, 15, 0, 0, 0};
set_command_with_index(t,2);}
set_cmd_with_index(t,2);}
// CMD opt
{Location t = {MAV_CMD_NAV_RETURN_TO_LAUNCH, WP_OPTION_YAW, 0, 0, 0, 0};
set_command_with_index(t,3);}
set_cmd_with_index(t,3);}
// CMD opt
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
set_command_with_index(t,4);}
set_cmd_with_index(t,4);}
} else {
//2250 = 25 meteres
// CMD opt p1 //alt //NS //WE
{Location t = {MAV_CMD_NAV_LOITER_TIME, 0, 10, 0, 0, 0}; // 19
set_command_with_index(t,2);}
set_cmd_with_index(t,2);}
// CMD opt dir angle/deg deg/s relative
{Location t = {MAV_CMD_CONDITION_YAW, 0, 1, 360, 60, 1};
set_command_with_index(t,3);}
set_cmd_with_index(t,3);}
// CMD opt
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
set_command_with_index(t,4);}
set_cmd_with_index(t,4);}
}
@ -1017,7 +1020,7 @@ static void print_hit_enter()
}
/*
static void fake_out_gps()
//static void fake_out_gps()
{
static float rads;
g_gps->new_data = true;
@ -1040,7 +1043,7 @@ static void fake_out_gps()
*/
/*
static void print_motor_out(){
//static void print_motor_out(){
Serial.printf("out: R: %d, L: %d F: %d B: %d\n",
(motor_out[CH_1] - g.rc_3.radio_min),
(motor_out[CH_2] - g.rc_3.radio_min),

View File

@ -36,4 +36,3 @@
#define AIRSPEED_CRUISE 25
#define THROTTLE_FAILSAFE ENABLED
*/
#define GPS_PROTOCOL GPS_NONE

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduPlane V2.251"
#define THISFIRMWARE "ArduPlane V2.26"
/*
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short
Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi

View File

@ -409,7 +409,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
(float)airspeed / 100.0,
(float)g_gps->ground_speed / 100.0,
(dcm.yaw_sensor / 100) % 360,
(int)g.channel_throttle.servo_out,
(uint16_t)(100 * g.channel_throttle.norm_output()),
current_loc.alt / 100.0,
0);
}

View File

@ -5,9 +5,9 @@
// Code to Write and Read packets from DataFlash log memory
// Code to interact with the user to dump or erase logs
#define HEAD_BYTE1 0xA3 // Decimal 163
#define HEAD_BYTE2 0x95 // Decimal 149
#define END_BYTE 0xBA // Decimal 186
#define HEAD_BYTE1 0xA3 // Decimal 163
#define HEAD_BYTE2 0x95 // Decimal 149
#define END_BYTE 0xBA // Decimal 186
// These are function definitions so the Menu can be constructed before the functions
@ -19,17 +19,17 @@ static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
// This is the help function
// PSTR is an AVR macro to read strings from flash memory
// printf_P is a version of print_f that reads from flash memory
static int8_t help_log(uint8_t argc, const Menu::arg *argv)
{
//static int8_t help_log(uint8_t argc, const Menu::arg *argv)
/*{
Serial.printf_P(PSTR("\n"
"Commands:\n"
" dump <n> dump log <n>\n"
" erase erase all logs\n"
" enable <name>|all enable logging <name> or everything\n"
" disable <name>|all disable logging <name> or everything\n"
" dump <n>"
" erase (all logs)\n"
" enable <name> | all\n"
" disable <name> | all\n"
"\n"));
return 0;
}
}*/
// Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM.
@ -39,8 +39,7 @@ static const struct Menu::command log_menu_commands[] PROGMEM = {
{"dump", dump_log},
{"erase", erase_logs},
{"enable", select_logs},
{"disable", select_logs},
{"help", help_log}
{"disable", select_logs}
};
// A Macro to create the Menu
@ -53,11 +52,12 @@ print_log_menu(void)
{
int log_start;
int log_end;
int temp;
int temp;
uint16_t num_logs = get_num_logs();
//Serial.print("num logs: "); Serial.println(num_logs, DEC);
Serial.printf_P(PSTR("logs enabled: "));
if (0 == g.log_bitmask) {
Serial.printf_P(PSTR("none"));
}else{
@ -78,18 +78,18 @@ print_log_menu(void)
PLOG(CUR);
#undef PLOG
}
Serial.println();
if (num_logs == 0) {
Serial.printf_P(PSTR("\nNo logs available for download\n"));
Serial.printf_P(PSTR("\nNo logs\n\n"));
}else{
Serial.printf_P(PSTR("\n%d logs\n"), num_logs);
Serial.printf_P(PSTR("\n%d logs available for download\n"), num_logs);
for(int i=num_logs;i>=1;i--) {
temp = g.log_last_filenumber-i+1;
get_log_boundaries(temp, log_start, log_end);
Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"),
temp, log_start, log_end);
Serial.printf_P(PSTR("Log %d, start %d, end %d\n"), temp, log_start, log_end);
}
Serial.println();
}
@ -109,17 +109,18 @@ dump_log(uint8_t argc, const Menu::arg *argv)
last_log_num = g.log_last_filenumber;
if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
Serial.printf_P(PSTR("bad log number\n"));
Log_Read(0, 4095);
return(-1);
}
get_log_boundaries(dump_log, dump_log_start, dump_log_end);
Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"),
Serial.printf_P(PSTR("Dumping Log %d, start pg %d, end pg %d\n"),
dump_log,
dump_log_start,
dump_log_end);
Log_Read(dump_log_start, dump_log_end);
Serial.printf_P(PSTR("Log read complete\n"));
Serial.printf_P(PSTR("Done\n"));
return 0;
}
@ -137,7 +138,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
}
g.log_last_filenumber.set_and_save(0);
Serial.printf_P(PSTR("\nLog erased.\n"));
return 0;
}
@ -189,7 +190,7 @@ static int8_t
process_logs(uint8_t argc, const Menu::arg *argv)
{
log_menu.run();
return 0;
return 0;
}
@ -202,31 +203,32 @@ static byte get_num_logs(void)
uint16_t first;
if(g.log_last_filenumber < 1) return 0;
DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) return 0;
if(DataFlash.GetFileNumber() == 0XFFFF) return 0;
lastpage = find_last();
DataFlash.StartRead(lastpage);
last = DataFlash.GetFileNumber();
DataFlash.StartRead(lastpage + 2);
first = DataFlash.GetFileNumber();
if(first == 0xFFFF) {
if(first > last) {
DataFlash.StartRead(1);
first = DataFlash.GetFileNumber();
}
if(last == first)
if(last == first)
{
return 1;
} else {
return (last - first + 1);
}
}
// This function starts a new log file in the DataFlash
static void start_new_log()
{
uint16_t last_page;
uint16_t last_page;
if(g.log_last_filenumber < 1) {
last_page = 0;
@ -246,7 +248,7 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
if(num == 1)
{
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
if(DataFlash.GetFileNumber() == 0xFFFF)
{
start_page = 1;
end_page = find_last_log_page((uint16_t)log_num);
@ -254,7 +256,7 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
end_page = find_last_log_page((uint16_t)log_num);
start_page = end_page + 1;
}
} else {
end_page = find_last_log_page((uint16_t)log_num);
if(log_num==1)
@ -268,13 +270,13 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
}
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
}
// This function finds the last page of the last file
// It also cleans up in the situation where a file was initiated, but no pages written
static int find_last(void)
{
int16_t num;
do
do
{
num = find_last_log_page(g.log_last_filenumber);
if (num == -1) g.log_last_filenumber.set_and_save(g.log_last_filenumber - 1);
@ -285,123 +287,118 @@ static int find_last(void)
// This function finds the last page of a particular log file
static int find_last_log_page(uint16_t log_number)
{
int16_t bottom_page;
int16_t top_page;
int16_t bottom_page_file;
int16_t bottom_page_filepage;
int16_t top_page_file;
int16_t top_page_filepage;
int16_t look_page;
int16_t look_page_file;
int16_t look_page_filepage;
int16_t check;
bool XLflag = false;
uint16_t bottom_page;
uint16_t bottom_page_file;
uint16_t bottom_page_filepage;
uint16_t top_page;
uint16_t top_page_file;
uint16_t top_page_filepage;
uint16_t look_page;
uint16_t look_page_file;
uint16_t look_page_filepage;
bottom_page = 1;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
// First see if the logs are empty
DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) {
// First see if the logs are empty. If so we will exit right away.
if(bottom_page_file == 0XFFFF) {
return 0;
}
// Next, see if logs wrap the top of the dataflash
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
{
// This case is that we have not wrapped the top of the dataflash
top_page = DF_LAST_PAGE;
bottom_page = 1;
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
if(DataFlash.GetFileNumber() > log_number)
top_page = look_page;
else
bottom_page = look_page;
}
return bottom_page;
} else {
// The else case is that the logs do wrap the top of the dataflash
bottom_page = 1;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
top_page_filepage = DataFlash.GetFilePage();
// Check is we have exactly filled the dataflash but not wrapped. If so we can exit quickly.
if(top_page_file == log_number && bottom_page_file != log_number) {
return top_page_file;
}
// Check if the top is 1 file higher than we want. If so we can exit quickly.
if(top_page_file == log_number+1) {
return top_page - top_page_filepage;
}
// Check if the file has partially overwritten itself
if(top_page_filepage >= DF_LAST_PAGE) {
XLflag = true;
} else {
top_page = top_page - top_page_filepage;
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
}
if(top_page_file == log_number) {
bottom_page = top_page;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(top_page);
top_page_filepage = DataFlash.GetFilePage();
if(XLflag) bottom_page = 1;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
top_page_filepage = DataFlash.GetFilePage();
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
if(DataFlash.GetFilePage() < top_page_filepage)
{
top_page = look_page;
top_page_filepage = DataFlash.GetFilePage();
} else {
bottom_page = look_page;
}
while((top_page - bottom_page) > 1) {
look_page = ((long)top_page + (long)bottom_page) / 2L;
DataFlash.StartRead(look_page);
look_page_file = DataFlash.GetFileNumber();
look_page_filepage = DataFlash.GetFilePage();
// We have a lot of different logic cases dependant on if the log space is overwritten
// and where log breaks might occur relative to binary search points.
// Someone could make work up a logic table and simplify this perhaps, or perhaps
// it is easier to interpret as is.
if (look_page_file == 0xFFFF) {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
} else if (look_page_file == log_number && bottom_page_file == log_number && top_page_file == log_number) {
// This case is typical if a single file fills the log and partially overwrites itself
if (bottom_page_filepage < top_page_filepage) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
}
return bottom_page;
}
// Step down through the files to find the one we want
bottom_page = top_page;
bottom_page_filepage = top_page_filepage;
do
{
top_page = bottom_page;
bottom_page = bottom_page - bottom_page_filepage;
if(bottom_page < 1) bottom_page = 1;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
} while (bottom_page_file != log_number && bottom_page != 1);
// Deal with stepping down too far due to overwriting a file
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
if(DataFlash.GetFileNumber() < log_number)
top_page = look_page;
else
} else if (look_page_file == log_number && look_page_file ==bottom_page_file) {
if (bottom_page_filepage < look_page_filepage) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
}
} else if (look_page_file == log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else if(look_page_file < log_number && bottom_page_file > look_page_file && bottom_page_file <= log_number) {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
} else if(look_page_file < log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else if(look_page_file > log_number && top_page_file < look_page_file && top_page_file >= log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
}
// The -1 return is for the case where a very short power up increments the log
// number counter but no log file is actually created. This happens if power is
// removed before the first page is written to flash.
if(bottom_page ==1 && DataFlash.GetFileNumber() != log_number) return -1;
return bottom_page;
// End while
}
if (bottom_page_file == log_number && top_page_file == log_number) {
if( bottom_page_filepage < top_page_filepage)
return top_page;
else
return bottom_page;
} else if (bottom_page_file == log_number) {
return bottom_page;
} else if (top_page_file == log_number) {
return top_page;
} else {
return -1;
}
}
// Write an attitude packet. Total length : 10 bytes
@ -724,14 +721,14 @@ static void Log_Read_Raw()
static void Log_Read(int start_page, int end_page)
{
int packet_count = 0;
#ifdef AIRFRAME_NAME
Serial.printf_P(PSTR((AIRFRAME_NAME)
#endif
Serial.printf_P(PSTR("\n" THISFIRMWARE
"\nFree RAM: %u\n"),
memcheck_available_memory());
if(start_page > end_page)
{
packet_count = Log_Read_Process(start_page, DF_LAST_PAGE);
@ -739,7 +736,7 @@ static void Log_Read(int start_page, int end_page)
} else {
packet_count = Log_Read_Process(start_page, end_page);
}
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
}
@ -754,6 +751,7 @@ static int Log_Read_Process(int start_page, int end_page)
DataFlash.StartRead(start_page);
while (page < end_page && page != -1){
data = DataFlash.ReadByte();
switch(log_step) // This is a state machine to read the packets
{
case 0:

View File

@ -286,20 +286,6 @@ static void startup_ground(void)
// ---------------------------
trim_radio(); // This was commented out as a HACK. Why? I don't find a problem.
#if HIL_MODE != HIL_MODE_ATTITUDE
if (g.airspeed_enabled == true)
{
// initialize airspeed sensor
// --------------------------
zero_airspeed();
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> zero airspeed calibrated"));
}
else
{
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> NO airspeed"));
}
#endif
// Save the settings for in-air restart
// ------------------------------------
//save_EEPROM_groundstart();
@ -439,6 +425,15 @@ static void startup_IMU_ground(void)
//-----------------------------
init_barometer();
if (g.airspeed_enabled == true) {
// initialize airspeed sensor
// --------------------------
zero_airspeed();
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> zero airspeed calibrated"));
} else {
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> NO airspeed"));
}
#endif // HIL_MODE_ATTITUDE
digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready

View File

@ -1,5 +1,5 @@
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ARDUCODER Version v0.9.85
// ArduPPM Version v0.9.87
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards
// By:John Arne Birkeland - 2011
@ -33,6 +33,8 @@
// 0.9.83 : Implemented PPM passtrough failsafe
// 0.9.84 : Corrected pin and port names in Encoder-PPM.c according to #define for Mega32U2 compatibility
// 0.9.85 : Added brownout reset detection flag
// 0.9.86 : Added a #define to disable Radio Passthrough mode (hardware failsafe for Arduplane)
// 0.9.87 : #define correction for radio passthrough (was screwed up).
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// PREPROCESSOR DIRECTIVES
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
@ -41,10 +43,11 @@
#include <util/delay.h>
#define ERROR_THRESHOLD 1 // Number of servo input errors before alerting
#define ERROR_THRESHOLD 2 // Number of servo input errors before alerting
#define ERROR_DETECTION_WINDOW 3000 * LOOP_TIMER_10MS // Detection window for error detection (default to 30s)
#define ERROR_CONDITION_DELAY 500 * LOOP_TIMER_10MS // Servo error condition LED delay (LED blinking duration)
#define PASSTHROUGH_MODE_ENABLED // Comment this line to remove CH8 radio passthrough mode support (hardware failsafe for Arduplane)
#define PASSTHROUGH_CHANNEL 8 * 2 // Channel for passthrough mode selection
#define PASSTHROUGH_CHANNEL_OFF_US ONE_US * 1600 - PPM_PRE_PULSE // Passthrough off threshold
#define PASSTHROUGH_CHANNEL_ON_US ONE_US * 1800 - PPM_PRE_PULSE // Passthrough on threshold
@ -87,8 +90,6 @@ int main(void)
// LOCAL VARIABLES
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
bool init = true; // We are inside init sequence
int8_t mux_check = 0;
uint16_t mux_ppm = 500;
bool mux_passthrough = false; // Mux passthrough mode status Flag : passthrough is off
uint16_t led_acceleration; // Led acceleration based on throttle stick position
bool servo_error_condition = false; // Servo signal error condition
@ -96,8 +97,14 @@ int main(void)
static uint16_t servo_error_detection_timer=0; // Servo error detection timer
static uint16_t servo_error_condition_timer=0; // Servo error condition timer
static uint16_t blink_led_timer = 0; // Blink led timer
#ifdef PASSTHROUGH_MODE_ENABLED
static uint8_t mux_timer = 0; // Mux timer
static uint8_t mux_counter = 0; // Mux counter
static int8_t mux_check = 0;
static uint16_t mux_ppm = 500;
#endif
static uint16_t led_code_timer = 0; // Blink Code Timer
static uint8_t led_code_symbol = 0; // Blink Code current symbol
@ -308,6 +315,7 @@ int main(void)
PWM_LOOP: // SERVO_PWM_MODE
while( 1 )
{
#ifdef PASSTHROUGH_MODE_ENABLED
// ------------------------------------------------------------------------------
// Radio passthrough control (mux chip A/B control)
// ------------------------------------------------------------------------------
@ -355,7 +363,7 @@ int main(void)
}
#endif
// ------------------------------------------------------------------------------
// Status LED control

View File

@ -35,7 +35,7 @@
*/
#include "Arduino-usbserial.h"
#include "..\..\..\Libraries\ppm_encoder.h"
#include "../../../Libraries/PPM_Encoder.h"
/** Circular buffer to hold data from the host before it is sent to the device via the serial port. */

View File

@ -243,18 +243,33 @@ const uint16_t failsafe_ppm[ PPM_ARRAY_MAX ] =
#define USB_PORT PORTC
#define USB_PIN PC2
// true if we have received a USB device connect event
static bool usb_connected;
// USB connected event
void EVENT_USB_Device_Connect(void)
{
// Toggle USB pin high if USB is connected
USB_PORT |= (1 << USB_PIN);
usb_connected = true;
// this unsets the pin connected to PA1 on the 2560
// when the bit is clear, USB is connected
PORTD &= ~1;
}
// USB dosconnect event
// USB disconnect event
void EVENT_USB_Device_Disconnect(void)
{
// toggle USB pin low if USB is disconnected
USB_PORT &= ~(1 << USB_PIN);
usb_connected = false;
// this sets the pin connected to PA1 on the 2560
// when the bit is clear, USB is connected
PORTD |= 1;
}
// AVR parameters for ArduPilot MEGA v1.4 PPM Encoder (ATmega328P)
@ -676,6 +691,17 @@ void ppm_encoder_init( void )
// Activate pullups on all input pins
SERVO_PORT |= 0xFF;
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
// on 32U2 set PD0 to be an output, and clear the bit. This tells
// the 2560 that USB is connected. The USB connection event fires
// later to set the right value
DDRD |= 1;
if (usb_connected) {
PORTD &= ~1;
} else {
PORTD |= 1;
}
#endif
// SERVO/PPM INPUT - PIN CHANGE INTERRUPT
// ------------------------------------------------------------------------------

View File

@ -56,7 +56,7 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(500);
//HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
if (!MainV2.MAC)
if (!MainV2.MONO)
{
ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
@ -66,7 +66,7 @@ namespace ArdupilotMega
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
{
return "2560-2";
//return "2560-2";
}
}
}

View File

@ -10,7 +10,7 @@
<AppDesignerFolder>Properties</AppDesignerFolder>
<RootNamespace>ArdupilotMega</RootNamespace>
<AssemblyName>ArdupilotMegaPlanner</AssemblyName>
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
<TargetFrameworkVersion>v4.0</TargetFrameworkVersion>
<TargetFrameworkProfile>
</TargetFrameworkProfile>
<FileAlignment>512</FileAlignment>
@ -57,7 +57,7 @@
<DebugType>full</DebugType>
<Optimize>true</Optimize>
<OutputPath>bin\Release\</OutputPath>
<DefineConstants>TRACE;MAVLINK10cra</DefineConstants>
<DefineConstants>TRACE;DEBUG;MAVLINK10cra</DefineConstants>
<ErrorReport>prompt</ErrorReport>
<WarningLevel>4</WarningLevel>
<AllowUnsafeBlocks>false</AllowUnsafeBlocks>
@ -92,7 +92,7 @@
</PropertyGroup>
<PropertyGroup />
<PropertyGroup>
<AssemblyOriginatorKeyFile>mykey.pfx</AssemblyOriginatorKeyFile>
<AssemblyOriginatorKeyFile>mykey.snk</AssemblyOriginatorKeyFile>
</PropertyGroup>
<PropertyGroup />
<PropertyGroup />
@ -134,6 +134,17 @@
<Reference Include="ICSharpCode.SharpZipLib">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\SrcSamples\bin\ICSharpCode.SharpZipLib.dll</HintPath>
</Reference>
<Reference Include="IronPython, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.dll</HintPath>
<Private>True</Private>
<EmbedInteropTypes>False</EmbedInteropTypes>
</Reference>
<Reference Include="IronPython.Modules, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.Modules.dll</HintPath>
<Private>True</Private>
</Reference>
<Reference Include="KMLib">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
</Reference>
@ -147,6 +158,16 @@
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.DirectInput.dll</HintPath>
<Private>False</Private>
</Reference>
<Reference Include="Microsoft.Dynamic, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Dynamic.dll</HintPath>
<Private>True</Private>
</Reference>
<Reference Include="Microsoft.Scripting, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Scripting.dll</HintPath>
<Private>True</Private>
</Reference>
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\Desktop\DIYDrones\opentk\trunk\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
@ -203,6 +224,7 @@
<Compile Include="HIL\QuadCopter.cs" />
<Compile Include="HIL\Quaternion.cs" />
<Compile Include="HIL\Vector3d.cs" />
<Compile Include="hires.cs" />
<Compile Include="MavlinkLog.cs">
<SubType>Form</SubType>
</Compile>
@ -329,6 +351,7 @@
</Compile>
<Compile Include="Program.cs" />
<Compile Include="Properties\AssemblyInfo.cs" />
<Compile Include="Script.cs" />
<Compile Include="SerialOutput.cs">
<SubType>Form</SubType>
</Compile>
@ -523,7 +546,7 @@
</None>
<None Include="MAC\Info.plist" />
<None Include="MAC\run.sh" />
<None Include="mykey.pfx" />
<None Include="mykey.snk" />
<None Include="Properties\app.manifest" />
<None Include="Properties\DataSources\CurrentState.datasource" />
<None Include="block_plane_0.dae">
@ -621,7 +644,6 @@
</BootstrapperPackage>
</ItemGroup>
<ItemGroup />
<ItemGroup />
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
<PropertyGroup>
<PostBuildEvent>rem macos.bat</PostBuildEvent>

View File

@ -10,4 +10,7 @@
<InstallUrlHistory />
<UpdateUrlHistory />
</PropertyGroup>
<PropertyGroup>
<ReferencePath>C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Release\</ReferencePath>
</PropertyGroup>
</Project>

View File

@ -140,6 +140,9 @@ namespace ArdupilotMega
public class GMapMarkerQuad : GMapMarker
{
const float rad2deg = (float)(180 / Math.PI);
const float deg2rad = (float)(1.0 / rad2deg);
static readonly System.Drawing.Size SizeSt = new System.Drawing.Size(global::ArdupilotMega.Properties.Resources.quad2.Width, global::ArdupilotMega.Properties.Resources.quad2.Height);
float heading = 0;
float cog = -1;
@ -158,8 +161,17 @@ namespace ArdupilotMega
{
Matrix temp = g.Transform;
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
int length = 500;
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
//g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
g.RotateTransform(heading);
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quad2, global::ArdupilotMega.Properties.Resources.quad2.Width / -2, global::ArdupilotMega.Properties.Resources.quad2.Height / -2);
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quad2, global::ArdupilotMega.Properties.Resources.quad2.Width / -2 + 2, global::ArdupilotMega.Properties.Resources.quad2.Height / -2);
g.Transform = temp;
}

View File

@ -57,7 +57,7 @@ namespace System.IO.Ports
get { return client.Available + rbuffer.Length - rbufferread; }
}
public bool IsOpen { get { return client.Client.Connected; } }
public bool IsOpen { get { try { return client.Client.Connected; } catch { return false; } } }
public bool DtrEnable
{
@ -97,6 +97,11 @@ namespace System.IO.Ports
{
if (client == null || !IsOpen)
{
try
{
client.Close();
}
catch { }
throw new Exception("The socket/serialproxy is closed");
}
}
@ -216,11 +221,21 @@ namespace System.IO.Ports
public void Close()
{
if (client.Client.Connected)
try
{
if (client.Client.Connected)
{
client.Client.Close();
client.Close();
}
}
catch { }
try
{
client.Client.Close();
client.Close();
}
catch { }
client = new TcpClient();
}

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,22 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +404,21 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,14 +477,13 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007c t test_baro(unsigned char, Menu::arg const*)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,107 +526,101 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000aa t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
000000be t update_events()
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t Log_Read_Nav_Tuning()
000000d0 t Log_Read_Control_Tuning()
000000d2 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000de t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000160 t test_wp(unsigned char, Menu::arg const*)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017a t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
00000210 t setup_motors(unsigned char, Menu::arg const*)
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000384 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a00 T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000704 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c1e T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,22 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +404,21 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,15 +477,14 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t test_baro(unsigned char, Menu::arg const*)
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,18 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000a8 t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -546,84 +545,82 @@
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000cc t Log_Read_Nav_Tuning()
000000cc t Log_Read_Control_Tuning()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
00000210 t setup_motors(unsigned char, Menu::arg const*)
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000382 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a00 T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000702 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c1e T loop

View File

@ -3,59 +3,54 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
autogenerated: At global scope:
autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:105: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:111: warning: 'void Log_Write_Control_Tuning()' 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
/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
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/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:55: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:56: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:57: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:110: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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
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: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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
autogenerated:249: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:250: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
autogenerated:252: warning: 'int32_t read_barometer()' declared 'static' but never defined
autogenerated:253: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:254: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:365: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'old_sonar_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/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:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -96,7 +91,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,24 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -67,6 +73,8 @@
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
@ -83,6 +91,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,6 +104,7 @@
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b circle_angle
00000004 b current_amps
00000004 b gps_base_alt
00000004 b original_alt
@ -101,7 +113,6 @@
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -190,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -202,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -211,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -218,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -227,7 +240,6 @@
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
@ -257,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -267,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t setup_accel(unsigned char, Menu::arg const*)
0000000c t process_logs(unsigned char, Menu::arg const*)
@ -281,10 +293,13 @@
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -296,6 +311,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -306,12 +323,13 @@
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r arm_motors()::__c
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r init_arm_motors()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -319,6 +337,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -330,29 +349,27 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c
00000011 r arm_motors()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000011 r init_disarm_motors()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -366,79 +383,74 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B adc
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e t init_disarm_motors()
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000030 B imu
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
@ -446,34 +458,30 @@
00000033 b pending_status
00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003a B g_gps_driver
0000003c W RC_Channel::~RC_Channel()
0000003c t read_AHRS()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000052 t report_version()
@ -483,55 +491,55 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 t print_gyro_offsets()
00000064 t print_accel_offsets()
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t init_arm_motors()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*)
00000090 t init_compass()
00000090 r test_menu_commands
00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t arm_motors()
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000aa t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ab B compass
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000be t update_events()
@ -539,76 +547,72 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t Log_Read_Nav_Tuning()
000000d0 t Log_Read_Control_Tuning()
000000d2 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000e0 r test_menu_commands
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000160 t test_wp(unsigned char, Menu::arg const*)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000017a t verify_nav_wp()
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001a8 t print_radio_values()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001cc t start_new_log()
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000220 t test_wp(unsigned char, Menu::arg const*)
00000204 t test_imu(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000330 t tuning()
00000246 t calc_loiter(int, int)
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000384 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
00001372 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
000005a8 t __static_initialization_and_destruction_0(int, int)
00000640 t init_ardupilot()
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001832 T loop

View File

@ -3,59 +3,54 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
autogenerated: At global scope:
autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:105: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:111: warning: 'void Log_Write_Control_Tuning()' 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
/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
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/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:55: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:56: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:57: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:110: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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
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: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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
autogenerated:249: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:250: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
autogenerated:252: warning: 'int32_t read_barometer()' declared 'static' but never defined
autogenerated:253: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:254: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:365: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'old_sonar_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/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:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -96,7 +91,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,24 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -67,6 +73,8 @@
00000002 r comma
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
@ -83,6 +91,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,6 +104,7 @@
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b circle_angle
00000004 b current_amps
00000004 b gps_base_alt
00000004 b original_alt
@ -101,7 +113,6 @@
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -190,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -202,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -211,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -218,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -227,7 +240,6 @@
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
@ -257,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -267,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t setup_accel(unsigned char, Menu::arg const*)
0000000c t process_logs(unsigned char, Menu::arg const*)
@ -281,10 +293,13 @@
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
0000000c r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -296,6 +311,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -306,12 +323,13 @@
0000000e V vtable for AP_VarT<signed char>
0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int>
0000000e r arm_motors()::__c
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r init_arm_motors()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -319,6 +337,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -330,29 +349,27 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
00000010 r planner_menu_commands
00000010 b motor_out
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c
00000011 r arm_motors()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000011 r init_disarm_motors()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -366,79 +383,74 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B adc
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e t init_disarm_motors()
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000030 B imu
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
@ -446,35 +458,31 @@
00000033 b pending_status
00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003a B g_gps_driver
0000003c W RC_Channel::~RC_Channel()
0000003c t read_AHRS()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000052 W AP_IMU_Shim::update()
@ -483,29 +491,31 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm
0000005a t Log_Write_Data(signed char, long)
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*)
0000005e t change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 t print_gyro_offsets()
00000064 t print_accel_offsets()
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t init_arm_motors()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -514,24 +524,22 @@
0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t init_compass()
00000090 t report_tuning()
00000090 r test_menu_commands
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t arm_motors()
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000a8 t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ab B compass
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000be t update_events()
@ -540,75 +548,71 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000cc t Log_Read_Nav_Tuning()
000000cc t Log_Read_Control_Tuning()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000e0 r test_menu_commands
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t verify_nav_wp()
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001a8 t print_radio_values()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021c t test_wp(unsigned char, Menu::arg const*)
00000204 t test_imu(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000330 t tuning()
00000246 t calc_loiter(int, int)
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000382 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
00001372 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
000005a8 t __static_initialization_and_destruction_0(int, int)
0000063e t init_ardupilot()
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001832 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,23 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +405,20 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,14 +477,13 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007c t test_baro(unsigned char, Menu::arg const*)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,19 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000aa t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -547,83 +547,80 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t Log_Read_Nav_Tuning()
000000d0 t Log_Read_Control_Tuning()
000000d2 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000de t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000160 t test_wp(unsigned char, Menu::arg const*)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017a t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001cc t start_new_log()
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000384 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018fa T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000708 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001af8 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,9 +278,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,23 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +405,20 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,15 +477,14 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t test_baro(unsigned char, Menu::arg const*)
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,19 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000a8 t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -548,82 +548,79 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000cc t Log_Read_Nav_Tuning()
000000cc t Log_Read_Control_Tuning()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000382 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018fa T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000706 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001af8 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,10 +278,11 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_frame()::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,23 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +405,20 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,14 +477,13 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007c t test_baro(unsigned char, Menu::arg const*)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,19 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000aa t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -547,83 +547,80 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t Log_Read_Nav_Tuning()
000000d0 t Log_Read_Control_Tuning()
000000d2 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t Log_Read(int, int)
000000de t setup_motors(unsigned char, Menu::arg const*)
000000de t test_adc(unsigned char, Menu::arg const*)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000160 t test_wp(unsigned char, Menu::arg const*)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017a t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000384 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001836 T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000708 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a34 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
0000000a r Log_Read_Startup()::__c
@ -270,10 +278,11 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_frame()::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,23 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +405,20 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,15 +477,14 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t test_baro(unsigned char, Menu::arg const*)
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,19 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000a8 t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -548,82 +548,79 @@
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000cc t Log_Read_Nav_Tuning()
000000cc t Log_Read_Control_Tuning()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000de t setup_motors(unsigned char, Menu::arg const*)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000382 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001836 T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000706 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a34 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_frame()::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
@ -271,9 +279,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,22 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +404,21 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,14 +477,13 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007c t test_baro(unsigned char, Menu::arg const*)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,107 +526,101 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000aa t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
000000be t update_events()
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t Log_Read_Nav_Tuning()
000000d0 t Log_Read_Control_Tuning()
000000d2 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000de t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t setup_motors(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000160 t test_wp(unsigned char, Menu::arg const*)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017a t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000384 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000190e T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000704 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001d42 T loop

View File

@ -3,40 +3,38 @@
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
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: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: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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used
autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined
autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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: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:180: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:187: warning: 'int heli_get_angle_boost(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/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used
autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined
autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined
autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated: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/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o

View File

@ -3,16 +3,17 @@
00000001 b home_is_set
00000001 b motor_armed
00000001 b motor_light
00000001 b CH7_wp_index
00000001 b control_mode
00000001 b gps_watchdog
00000001 b simple_timer
00000001 d yaw_tracking
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
00000001 b mavlink_active
00000001 b prev_nav_index
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
00000001 b command_yaw_dir
00000001 b new_radio_frame
00000001 b roll_pitch_mode
@ -24,13 +25,14 @@
00000001 b old_control_mode
00000001 b slow_loopCounter
00000001 b takeoff_complete
00000001 b command_may_index
00000001 b command_nav_index
00000001 b oldSwitchPosition
00000001 b command_must_index
00000001 b command_cond_index
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b command_yaw_relative
00000001 d jump
00000001 b nav_ok
00000001 b event_id
00000001 b led_mode
00000001 b yaw_mode
@ -45,20 +47,25 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
00000002 b sonar_rate
00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
00000002 b event_repeat
00000002 b loiter_total
00000002 b manual_boost
00000002 b nav_throttle
00000002 b old_baro_alt
00000002 b x_rate_error
00000002 b y_rate_error
00000002 b altitude_rate
00000002 b gps_fix_count
00000002 b old_sonar_alt
00000002 b velocity_land
00000002 b x_actual_speed
00000002 b y_actual_speed
00000002 b loiter_time_max
00000002 b command_yaw_time
00000002 b crosstrack_error
00000002 b event_undo_value
00000002 b command_yaw_speed
00000002 b auto_level_counter
@ -69,6 +76,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
00000002 b baro_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -82,6 +90,9 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r report_batt_monitor()::__c
00000003 r report_batt_monitor()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@ -93,15 +104,14 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
00000004 b simple_cos_x
00000004 b simple_sin_y
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 t test_failsafe(unsigned char, Menu::arg const*)
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
@ -152,7 +162,6 @@
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
00000004 V Parameters::Parameters()::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -171,7 +180,6 @@
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r print_log_menu()::__c
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
00000005 V Parameters::Parameters()::__c
@ -193,6 +201,7 @@
00000006 r Log_Read_Mode()::__c
00000006 r print_log_menu()::__c
00000006 r print_log_menu()::__c
00000006 r report_batt_monitor()::__c
00000006 V Parameters::Parameters()::__c
00000007 b setup_menu
00000007 b planner_menu
@ -205,6 +214,8 @@
00000007 r report_radio()::__c
00000007 r report_sonar()::__c
00000007 r print_enabled(unsigned char)::__c
00000007 r Log_Read_Nav_Tuning()::__c
00000007 r Log_Read_Control_Tuning()::__c
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
00000007 V Parameters::Parameters()::__c
00000007 V Parameters::Parameters()::__c
@ -214,6 +225,7 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 t setup_erase(unsigned char, Menu::arg const*)
00000008 r __menu_name__planner_menu
00000008 r print_done()::__c
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
00000008 r report_frame()::__c
00000008 r report_frame()::__c
@ -221,8 +233,6 @@
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
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c
@ -230,7 +240,6 @@
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
@ -260,7 +269,6 @@
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a T piezo_on()
0000000a T piezo_off()
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_frame()::__c
0000000a r start_new_log()::__c
0000000a r print_log_menu()::__c
@ -271,9 +279,10 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
0000000b r setup_esc(unsigned char, Menu::arg const*)::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega
@ -282,11 +291,13 @@
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 r report_version()::__c
0000000c r report_batt_monitor()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r setup_frame(unsigned char, Menu::arg const*)::__c
0000000d r test_tuning(unsigned char, Menu::arg const*)::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r startup_ground()::__c
@ -298,6 +309,8 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -313,6 +326,7 @@
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r setup_compass(unsigned char, Menu::arg const*)::__c
0000000e r print_log_menu()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
@ -321,6 +335,7 @@
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r print_radio_values()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
@ -332,19 +347,18 @@
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b command_nav_queue
0000000f b command_cond_queue
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f b target_WP
0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c
0000000f r Log_Read_Data()::__c
0000000f r print_log_menu()::__c
0000000f r print_log_menu()::__c
0000000f r report_version()::__c
0000000f r report_batt_monitor()::__c
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 r planner_menu_commands
00000010 b motor_out
@ -354,7 +368,6 @@
00000010 r report_compass()::__c
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r update_commands()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
@ -368,30 +381,22 @@
00000012 W AP_VarT<float>::~AP_VarT()
00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
00000016 r setup_mode(unsigned char, Menu::arg const*)::__c
00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
@ -399,18 +404,21 @@
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r print_gyro_offsets()::__c
0000001c r print_accel_offsets()::__c
0000001d r report_compass()::__c
0000001d r Log_Read_Motors()::__c
0000001d r Log_Read_Attitude()::__c
0000001d r Log_Read_Performance()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 t byte_swap_4
00000021 r setup_mode(unsigned char, Menu::arg const*)::__c
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -419,52 +427,49 @@
00000022 W AP_VarT<signed char>::~AP_VarT()
00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000022 r test_imu(unsigned char, Menu::arg const*)::__c
00000023 r test_baro(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t Log_Write_Data(signed char, float)
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 r Log_Read_Cmd()::__c
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r init_ardupilot()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c
0000002f r setup_factory(unsigned char, Menu::arg const*)::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 r setup_radio(unsigned char, Menu::arg const*)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c
00000038 t init_throttle_cruise()
00000036 r print_wp(Location*, unsigned char)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel()
0000003c B barometer
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 t init_throttle_cruise()
00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 B adc
@ -472,15 +477,14 @@
00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004c t update_auto_yaw()
00000050 b mavlink_queue
00000050 t report_version()
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -489,13 +493,13 @@
00000056 t readSwitch()
00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005a t Log_Write_Data(signed char, long)
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 change_command(unsigned char)
0000005e t update_GPS_light()
0000005e T GCS_MAVLINK::_count_parameters()
00000064 B barometer
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
@ -504,13 +508,12 @@
0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch()
0000007a t report_flight_modes()
0000007a t test_baro(unsigned char, Menu::arg const*)
0000007a t do_RTL()
0000007c t Log_Read_Data()
0000007c t send_gps_status(mavlink_channel_t)
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
@ -523,22 +526,18 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
0000009a t Log_Read_Motors()
0000009b B gcs0
0000009b B gcs3
0000009c B gcs0
0000009c B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 r test_menu_commands
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000a8 t test_sonar(unsigned char, Menu::arg const*)
000000aa t Log_Read_Nav_Tuning()
000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 B compass
@ -546,84 +545,82 @@
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
000000c2 t Log_Read_Motors()
000000c2 t Log_Read_Attitude()
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
000000cc t Log_Read_Nav_Tuning()
000000cc t Log_Read_Control_Tuning()
000000d0 t read_radio()
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
000000d4 t Log_Read(int, int)
000000d4 t print_wp(Location*, unsigned char)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t test_adc(unsigned char, Menu::arg const*)
000000dc t Log_Read(int, int)
000000e0 r setup_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000ee t Log_Read_Performance()
000000f6 t Log_Read_Cmd()
00000100 r test_menu_commands
000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
0000012c t calc_loiter_pitch_roll()
00000118 t arm_motors()
0000011c t get_cmd_with_index(int)
00000130 t report_compass()
00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long)
00000148 t Log_Read_GPS()
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013a t test_baro(unsigned char, Menu::arg const*)
0000014c t get_stabilize_roll(long)
0000014c t get_stabilize_pitch(long)
0000014e t send_servo_out(mavlink_channel_t)
00000156 t update_commands()
00000152 t init_home()
00000156 t Log_Read_GPS()
0000015c t update_trig()
0000015c t setup_motors(unsigned char, Menu::arg const*)
0000015c t test_wp(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000164 t set_cmd_with_index(Location, int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t verify_nav_wp()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001b2 t start_new_log()
000001b8 t send_nav_controller_output(mavlink_channel_t)
000001ce T GCS_MAVLINK::update()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
00000216 t set_mode(unsigned char)
00000210 t test_imu(unsigned char, Menu::arg const*)
0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000246 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
00000330 t tuning()
0000026a t send_gps_raw(mavlink_channel_t)
000002cc t set_mode(unsigned char)
00000362 t tuning()
00000382 t print_log_menu()
0000039a T update_throttle_mode()
00000396 T update_roll_pitch_mode()
000003a0 t read_battery()
00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode()
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()
00000884 W Parameters::Parameters()
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000190e T loop
0000041c T update_yaw_mode()
00000444 T update_throttle_mode()
00000702 t init_ardupilot()
000007d8 t __static_initialization_and_destruction_0(int, int)
00000878 t update_nav_wp()
000008f6 W Parameters::Parameters()
000008fa b g
000009be t update_commands(bool)
000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001d42 T loop

View File

@ -3,10 +3,21 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)':
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check'
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope:
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -219,6 +219,7 @@
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r print_log_menu()::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -283,6 +284,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -343,6 +345,7 @@
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 r __menu_name__main_menu
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
@ -351,7 +354,6 @@
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
@ -420,10 +422,11 @@
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r print_log_menu()::__c
0000001a r Log_Read_Process(int, int)::__c
0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -433,25 +436,25 @@
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read_Process(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e t update_commands()
0000001e r flight_mode_strings
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r print_log_menu()::__c
0000001f r Log_Read(int, int)::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int)
@ -478,12 +481,11 @@
00000026 t print_done()
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
@ -504,8 +506,6 @@
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
@ -516,10 +516,10 @@
00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio()
00000036 t find_last()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -530,11 +530,13 @@
0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char)
0000003c b barometer
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
@ -552,7 +554,6 @@
0000004c t Log_Read_Mode()
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -566,7 +567,6 @@
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000062 t print_switch(unsigned char, unsigned char)
@ -575,7 +575,6 @@
00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
@ -609,6 +608,7 @@
0000009c t print_PID(PID*)
0000009c B gcs0
0000009c B gcs3
0000009e t get_num_logs()
000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd()
@ -619,15 +619,16 @@
000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t Log_Read_Startup()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass
000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c4 t Log_Read(int, int)
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c6 t get_log_boundaries(unsigned char, int&, int&)
000000c7 B dcm
000000ca t send_radio_out(mavlink_channel_t)
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
@ -635,15 +636,15 @@
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d4 t trim_radio()
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f6 t erase_logs(unsigned char, Menu::arg const*)
000000fa t Log_Read_Current()
000000fc t dump_log(unsigned char, Menu::arg const*)
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
@ -658,7 +659,6 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*)
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
@ -674,6 +674,7 @@
00000152 t verify_condition_command()
0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t Log_Read_Process(int, int)
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016c t navigate()
@ -682,12 +683,11 @@
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning()
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
0000017e t send_extended_status1(mavlink_channel_t, unsigned int)
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000192 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019c t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
@ -700,7 +700,6 @@
000001ea t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000208 t calc_throttle()
00000216 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
0000022a t send_gps_raw(mavlink_channel_t)
0000022c t process_next_command()
@ -710,16 +709,17 @@
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
00000268 t find_last_log_page(unsigned int)
000002d4 t handle_process_do_command()
000002e4 t read_radio()
0000031e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
000003e6 t read_battery()
0000044c t print_log_menu()
00000462 t print_log_menu()
000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int)
0000064a t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000694 t init_ardupilot()
00000936 W Parameters::Parameters()
00000938 b g
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001cbe T loop
00001caa T loop

View File

@ -3,10 +3,21 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)':
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check'
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope:
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -219,6 +219,7 @@
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r print_log_menu()::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -283,6 +284,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -343,6 +345,7 @@
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 r __menu_name__main_menu
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
@ -351,7 +354,6 @@
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
@ -420,10 +422,11 @@
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r print_log_menu()::__c
0000001a r Log_Read_Process(int, int)::__c
0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -433,25 +436,25 @@
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read_Process(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e t update_commands()
0000001e r flight_mode_strings
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r print_log_menu()::__c
0000001f r Log_Read(int, int)::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int)
@ -478,12 +481,11 @@
00000026 t print_done()
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
@ -504,8 +506,6 @@
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
@ -516,10 +516,10 @@
00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio()
00000036 t find_last()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -530,11 +530,13 @@
0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char)
0000003c b barometer
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
@ -552,7 +554,6 @@
0000004c t Log_Read_Mode()
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -566,7 +567,6 @@
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char)
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
@ -575,7 +575,6 @@
00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
@ -609,6 +608,7 @@
0000009c t print_PID(PID*)
0000009c B gcs0
0000009c B gcs3
0000009e t get_num_logs()
000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd()
@ -619,31 +619,32 @@
000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b0 t Log_Read_Startup()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass
000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c0 t Log_Read(int, int)
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000c8 t get_log_boundaries(unsigned char, int&, int&)
000000ca t send_radio_out(mavlink_channel_t)
000000ca t control_failsafe(unsigned int)
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d4 t trim_radio()
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t erase_logs(unsigned char, Menu::arg const*)
000000fa t Log_Read_Current()
000000fc t dump_log(unsigned char, Menu::arg const*)
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
@ -657,7 +658,6 @@
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*)
00000120 t test_pressure(unsigned char, Menu::arg const*)
@ -673,6 +673,7 @@
00000152 t report_gains()
00000152 t verify_condition_command()
00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015a t Log_Read_Process(int, int)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*)
@ -682,12 +683,11 @@
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning()
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
0000017e t send_extended_status1(mavlink_channel_t, unsigned int)
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000190 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019a t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
@ -700,7 +700,6 @@
000001ea t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000208 t calc_throttle()
00000210 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t test_wp(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
@ -710,16 +709,17 @@
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
00000268 t find_last_log_page(unsigned int)
000002d4 t handle_process_do_command()
000002e4 t read_radio()
0000031e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
000003e6 t read_battery()
00000436 t print_log_menu()
0000044c t print_log_menu()
000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int)
00000648 t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000692 t init_ardupilot()
00000936 W Parameters::Parameters()
00000938 b g
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001cbe T loop
00001caa T loop

View File

@ -3,10 +3,21 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)':
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check'
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope:
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -219,6 +219,7 @@
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r print_log_menu()::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -283,6 +284,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -343,6 +345,7 @@
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 r __menu_name__main_menu
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
@ -351,7 +354,6 @@
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
@ -420,10 +422,11 @@
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r print_log_menu()::__c
0000001a r Log_Read_Process(int, int)::__c
0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -433,25 +436,25 @@
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read_Process(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e t update_commands()
0000001e r flight_mode_strings
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r print_log_menu()::__c
0000001f r Log_Read(int, int)::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int)
@ -478,12 +481,11 @@
00000026 t print_done()
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
@ -504,8 +506,6 @@
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
@ -516,10 +516,10 @@
00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio()
00000036 t find_last()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -530,11 +530,13 @@
0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char)
0000003c b barometer
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
@ -552,7 +554,6 @@
0000004c t Log_Read_Mode()
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -566,7 +567,6 @@
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000062 t print_switch(unsigned char, unsigned char)
@ -575,7 +575,6 @@
00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
@ -609,6 +608,7 @@
0000009c t print_PID(PID*)
0000009c B gcs0
0000009c B gcs3
0000009e t get_num_logs()
000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd()
@ -619,15 +619,16 @@
000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t Log_Read_Startup()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass
000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c4 t Log_Read(int, int)
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c6 t get_log_boundaries(unsigned char, int&, int&)
000000c7 B dcm
000000ca t send_radio_out(mavlink_channel_t)
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
@ -635,15 +636,15 @@
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d4 t trim_radio()
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f6 t erase_logs(unsigned char, Menu::arg const*)
000000fa t Log_Read_Current()
000000fc t dump_log(unsigned char, Menu::arg const*)
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
@ -658,7 +659,6 @@
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*)
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
@ -674,6 +674,7 @@
00000152 t verify_condition_command()
0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t Log_Read_Process(int, int)
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016c t navigate()
@ -682,12 +683,11 @@
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning()
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
0000017e t send_extended_status1(mavlink_channel_t, unsigned int)
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000192 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019c t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
@ -700,7 +700,6 @@
000001ea t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000208 t calc_throttle()
00000216 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
0000022a t send_gps_raw(mavlink_channel_t)
0000022c t process_next_command()
@ -710,16 +709,17 @@
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
00000268 t find_last_log_page(unsigned int)
000002d4 t handle_process_do_command()
000002e4 t read_radio()
0000031e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
000003e6 t read_battery()
0000044c t print_log_menu()
00000462 t print_log_menu()
000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int)
0000064a t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000694 t init_ardupilot()
00000936 W Parameters::Parameters()
00000938 b g
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001cbe T loop
00001caa T loop

View File

@ -3,10 +3,21 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)':
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage'
/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check'
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope:
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -219,6 +219,7 @@
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r print_log_menu()::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -283,6 +284,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -343,6 +345,7 @@
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 r __menu_name__main_menu
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
@ -351,7 +354,6 @@
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
@ -420,10 +422,11 @@
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r print_log_menu()::__c
0000001a r Log_Read_Process(int, int)::__c
0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -433,25 +436,25 @@
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read_Process(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e t update_commands()
0000001e r flight_mode_strings
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r print_log_menu()::__c
0000001f r Log_Read(int, int)::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int)
@ -478,12 +481,11 @@
00000026 t print_done()
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
@ -504,8 +506,6 @@
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
@ -516,10 +516,10 @@
00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio()
00000036 t find_last()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -530,11 +530,13 @@
0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char)
0000003c b barometer
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 r log_menu_commands
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8
@ -552,7 +554,6 @@
0000004c t Log_Read_Mode()
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
@ -566,7 +567,6 @@
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char)
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
@ -575,7 +575,6 @@
00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
@ -609,6 +608,7 @@
0000009c t print_PID(PID*)
0000009c B gcs0
0000009c B gcs3
0000009e t get_num_logs()
000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd()
@ -619,31 +619,32 @@
000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b0 t Log_Read_Startup()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass
000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c0 t Log_Read(int, int)
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000c8 t get_log_boundaries(unsigned char, int&, int&)
000000ca t send_radio_out(mavlink_channel_t)
000000ca t control_failsafe(unsigned int)
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d4 t trim_radio()
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t erase_logs(unsigned char, Menu::arg const*)
000000fa t Log_Read_Current()
000000fc t dump_log(unsigned char, Menu::arg const*)
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
@ -657,7 +658,6 @@
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*)
00000120 t test_pressure(unsigned char, Menu::arg const*)
@ -673,6 +673,7 @@
00000152 t report_gains()
00000152 t verify_condition_command()
00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015a t Log_Read_Process(int, int)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*)
@ -682,12 +683,11 @@
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning()
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
0000017e t send_extended_status1(mavlink_channel_t, unsigned int)
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000190 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019a t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
@ -700,7 +700,6 @@
000001ea t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000208 t calc_throttle()
00000210 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t test_wp(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
@ -710,16 +709,17 @@
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
00000268 t find_last_log_page(unsigned int)
000002d4 t handle_process_do_command()
000002e4 t read_radio()
0000031e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
000003e6 t read_battery()
00000436 t print_log_menu()
0000044c t print_log_menu()
000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int)
00000648 t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000692 t init_ardupilot()
00000936 W Parameters::Parameters()
00000938 b g
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001cbe T loop
00001caa T loop

View File

@ -13,58 +13,62 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta
autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:842: warning: 'byte get_num_logs()' defined but not used
autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:53: warning: 'int find_last()' declared 'static' but never defined
autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'void Log_Write_Performance()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:846: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:68: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:69: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:70: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:71: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:72: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:73: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:74: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:75: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:76: warning: 'int Log_Read_Process(int, int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:166: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:167: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:168: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:171: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:172: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:173: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:174: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:175: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:176: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:177: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:178: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:179: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:180: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:181: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:182: warning: 'void print_done()' declared 'static' but never defined
autogenerated:183: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:184: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:185: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:186: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:187: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:188: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:189: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:190: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:200: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -199,6 +199,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -290,6 +291,7 @@
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001e t update_commands()
0000001e r startup_ground()::__c
00000020 t gcs_send_message(ap_message)
00000020 t byte_swap_4
@ -309,8 +311,8 @@
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000028 t demo_servos(unsigned char)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -429,9 +431,9 @@
000002d4 t handle_process_do_command()
000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
00000494 t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000936 W Parameters::Parameters()
00000938 b g
0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c82 T loop
00001c76 T loop

View File

@ -13,58 +13,62 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta
autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:842: warning: 'byte get_num_logs()' defined but not used
autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:53: warning: 'int find_last()' declared 'static' but never defined
autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'void Log_Write_Performance()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:846: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:68: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:69: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:70: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:71: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:72: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:73: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:74: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:75: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:76: warning: 'int Log_Read_Process(int, int)' declared 'static' but never defined
autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:166: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:167: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:168: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:171: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:172: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:173: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:174: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:175: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:176: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:177: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:178: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:179: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:180: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:181: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:182: warning: 'void print_done()' declared 'static' but never defined
autogenerated:183: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:184: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:185: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:186: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:187: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:188: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:189: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:190: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:200: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o

View File

@ -199,6 +199,7 @@
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial
@ -290,6 +291,7 @@
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001e t update_commands()
0000001e r startup_ground()::__c
00000020 t gcs_send_message(ap_message)
00000020 t byte_swap_4
@ -309,8 +311,8 @@
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c
00000026 r init_ardupilot()::__c
00000026 r init_ardupilot()::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c
00000028 t demo_servos(unsigned char)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -429,9 +431,9 @@
000002d4 t handle_process_do_command()
000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters()
00000344 W Parameters::~Parameters()
00000492 t init_ardupilot()
00000920 W Parameters::Parameters()
0000092b b g
00000936 W Parameters::Parameters()
00000938 b g
0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c82 T loop
00001c76 T loop

View File

@ -3,14 +3,14 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<name>ArduPlane V2.251 </name>
<name>ArduPlane V2.26 </name>
<desc></desc>
<format_version>12</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<name>ArduPlane V2.251 HIL</name>
<name>ArduPlane V2.26 HIL</name>
<desc>
#define FLIGHT_MODE_CHANNEL 8
#define FLIGHT_MODE_1 AUTO
@ -44,53 +44,53 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<name>ArduPlane V2.251 APM trunk</name>
<name>ArduPlane V2.26 APM trunk</name>
<desc></desc>
<format_version>12</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<name>ArduCopter V2.0.49 Beta Quad</name>
<name>ArduCopter V2.0.50 Beta Quad</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>111</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<name>ArduCopter V2.0.49 Beta Tri</name>
<name>ArduCopter V2.0.50 Beta Tri</name>
<desc>
#define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>111</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<name>ArduCopter V2.0.49 Beta Hexa</name>
<name>ArduCopter V2.0.50 Beta Hexa</name>
<desc>
#define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>111</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<name>ArduCopter V2.0.49 Beta Y6</name>
<name>ArduCopter V2.0.50 Beta Y6</name>
<desc>
#define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME
</desc>
<format_version>111</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
@ -142,7 +142,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.49 Beta Quad Hil</name>
<name>ArduCopter V2.0.50 Beta Quad Hil</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME
@ -152,7 +152,7 @@
</desc>
<format_version>111</format_version>
<format_version>113</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>

View File

@ -1,29 +1 @@
From https://code.google.com/p/ardupilot-mega
66cc8dd..6f4e7ec master -> origin/master
Updating 66cc8dd..6f4e7ec
Fast-forward
ArduCopter/APM_Config.h | 2 +-
ArduCopter/ArduCopter.pde | 18 ++-
ArduCopter/commands.pde | 8 +-
ArduCopter/commands_process.pde | 3 +-
ArduCopter/motors_hexa.pde | 2 +-
ArduCopter/motors_octa.pde | 2 +-
ArduCopter/motors_octa_quad.pde | 2 +-
ArduCopter/motors_y6.pde | 3 +-
ArduPlane/ArduPlane.pde | 2 +-
ArduPlane/Log.pde | 5 +-
ArduPlane/commands_logic.pde | 13 ++-
Tools/ArdupilotMegaPlanner/CurrentState.cs | 1 -
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 27 +++-
.../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 149 +++++++++++++++++---
Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 14 ++-
.../Properties/AssemblyInfo.cs | 2 +-
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2195456 bytes
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
Tools/autotest/arducopter.py | 58 ++++++---
Tools/autotest/common.py | 16 ++-
24 files changed, 251 insertions(+), 78 deletions(-)
Already up-to-date.

View File

@ -730,6 +730,69 @@
<data name="TabAPM2.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_PIT_IMAX.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label27.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_PIT_I.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label29.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_PIT_P.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label33.ToolTip" xml:space="preserve">
<value />
</data>
<data name="groupBox17.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label14.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_RATE_IMAX.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_RATE_I.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label20.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_RATE_P.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label25.ToolTip" xml:space="preserve">
<value />
</data>
<data name="groupBox5.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_RLL_IMAX.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label40.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_RLL_I.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label44.ToolTip" xml:space="preserve">
<value />
</data>
<data name="ACRO_RLL_P.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label48.ToolTip" xml:space="preserve">
<value />
</data>
<data name="groupBox18.ToolTip" xml:space="preserve">
<value />
</data>
<data name="CHK_lockrollpitch.Size" type="System.Drawing.Size, System.Drawing">
<value>122, 17</value>
</data>
@ -805,19 +868,19 @@
<data name="groupBox6.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_HOLD_IMAX.ToolTip" xml:space="preserve">
<data name="THR_ALT_IMAX.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label19.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_HOLD_I.ToolTip" xml:space="preserve">
<data name="THR_ALT_I.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label21.ToolTip" xml:space="preserve">
<value />
</data>
<data name="THR_HOLD_P.ToolTip" xml:space="preserve">
<data name="THR_ALT_P.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label22.ToolTip" xml:space="preserve">
@ -982,6 +1045,15 @@
<data name="TabAC2.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label26.Text" xml:space="preserve">
<value>视频格式</value>
</data>
<data name="label26.ToolTip" xml:space="preserve">
<value />
</data>
<data name="CMB_videoresolutions.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label12.Text" xml:space="preserve">
<value>抬头显示</value>
</data>
@ -1261,6 +1333,9 @@
<data name="ConfigTabs.ToolTip" xml:space="preserve">
<value />
</data>
<data name="label109.ToolTip" xml:space="preserve">
<value />
</data>
<data name="BUT_rerequestparams.Text" xml:space="preserve">
<value>刷新参数</value>
</data>
@ -1273,10 +1348,17 @@
<data name="BUT_load.Text" xml:space="preserve">
<value>加载</value>
</data>
<data name="BUT_compare.Text" xml:space="preserve">
<value>比较参数</value>
</data>
<data name="BUT_compare.ToolTip" xml:space="preserve">
<value />
</data>
<data name="$this.ToolTip" xml:space="preserve">
<value />
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="MAVParam" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\Resources\MAVParam.zh-Hans.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
</data>
</root>

View File

@ -681,7 +681,7 @@ namespace ArdupilotMega.GCSViews
}
}
lbl_status.Text = "Done";
lbl_status.Text = "Write Done... Waiting";
}
else
{
@ -696,6 +696,7 @@ namespace ArdupilotMega.GCSViews
System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time.
lbl_status.Text = "Done";
}
catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
flashing = false;

View File

@ -141,6 +141,8 @@ namespace ArdupilotMega.GCSViews
CMB_setwp.SelectedIndex = 0;
zg1.Visible = true;
CreateChart(zg1);
// config map
@ -693,7 +695,7 @@ namespace ArdupilotMega.GCSViews
{
((Button)sender).Enabled = false;
#if MAVLINK10
comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text));
comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text),0,0,0,0,0,0,0);
#else
comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text));
#endif
@ -734,6 +736,7 @@ namespace ArdupilotMega.GCSViews
ZedGraphTimer.Enabled = true;
ZedGraphTimer.Start();
zg1.Visible = true;
zg1.Refresh();
}
else
{
@ -807,9 +810,9 @@ namespace ArdupilotMega.GCSViews
Locationwp gotohere = new Locationwp();
gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
gotohere.alt = (int)(intalt / MainV2.cs.multiplierdist * 100); // back to m
gotohere.lat = (int)(gotolocation.Lat * 10000000);
gotohere.lng = (int)(gotolocation.Lng * 10000000);
gotohere.alt = (float)(intalt / MainV2.cs.multiplierdist); // back to m
gotohere.lat = (float)(gotolocation.Lat);
gotohere.lng = (float)(gotolocation.Lng);
try
{

View File

@ -123,6 +123,9 @@
<data name="contextMenuStrip1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="contextMenuStrip2.ToolTip" xml:space="preserve">
<value />
</data>
<data name="hud1.ToolTip" xml:space="preserve">
<value />
</data>
@ -4212,18 +4215,15 @@
<data name="tabStatus.ToolTip" xml:space="preserve">
<value />
</data>
<data name="lbl_logpercent.ToolTip" xml:space="preserve">
<value />
</data>
<data name="BUT_log2kml.ToolTip" xml:space="preserve">
<value />
</data>
<data name="tracklog.ToolTip" xml:space="preserve">
<value />
</data>
<data name="BUT_stoptelemlog.Text" xml:space="preserve">
<value>停止记录</value>
</data>
<data name="BUT_stoptelemlog.ToolTip" xml:space="preserve">
<value />
</data>
<data name="BUT_playlog.Text" xml:space="preserve">
<value>播放/暂停</value>
</data>
@ -4236,12 +4236,6 @@
<data name="BUT_loadtelem.ToolTip" xml:space="preserve">
<value />
</data>
<data name="BUT_savetelem.Text" xml:space="preserve">
<value>开始记录</value>
</data>
<data name="BUT_savetelem.ToolTip" xml:space="preserve">
<value />
</data>
<data name="tabTLogs.Text" xml:space="preserve">
<value>遥测记录</value>
</data>
@ -4260,64 +4254,10 @@
<data name="MainH.Panel1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_lat.ToolTip" xml:space="preserve">
<data name="zg1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>474, 7</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>440, 10</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>缩放</value>
</data>
<data name="label1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>90, 10</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_long.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>170, 10</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_alt.ToolTip" xml:space="preserve">
<value />
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>339, 9</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>98, 17</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>自动平移地图</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>250, 9</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>舵机调整</value>
</data>
<data name="panel1.ToolTip" xml:space="preserve">
<data name="splitContainer1.Panel1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="gMapControl1.streamjpg" mimetype="application/x-microsoft.net.object.binary.base64">
@ -4468,10 +4408,70 @@
<data name="gMapControl1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="zg1.ToolTip" xml:space="preserve">
<data name="splitContainer1.Panel2.ToolTip" xml:space="preserve">
<value />
</data>
<data name="panel2.ToolTip" xml:space="preserve">
<data name="splitContainer1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_lat.ToolTip" xml:space="preserve">
<value />
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>474, 7</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>440, 10</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>缩放</value>
</data>
<data name="label1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>90, 10</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_long.ToolTip" xml:space="preserve">
<value />
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>170, 10</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>80, 13</value>
</data>
<data name="TXT_alt.ToolTip" xml:space="preserve">
<value />
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>339, 9</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>98, 17</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>自动平移地图</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>250, 9</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>舵机调整</value>
</data>
<data name="panel1.ToolTip" xml:space="preserve">
<value />
</data>
<data name="tableMap.ToolTip" xml:space="preserve">

View File

@ -120,6 +120,7 @@
this.label11 = new System.Windows.Forms.Label();
this.panelBASE = new System.Windows.Forms.Panel();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_zoomto = new ArdupilotMega.MyButton();
((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit();
this.panel5.SuspendLayout();
this.panel1.SuspendLayout();
@ -508,6 +509,7 @@
this.panelWaypoints.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold);
this.panelWaypoints.CaptionHeight = 21;
this.panelWaypoints.ColorScheme = BSE.Windows.Forms.ColorScheme.Custom;
this.panelWaypoints.Controls.Add(this.BUT_zoomto);
this.panelWaypoints.Controls.Add(this.BUT_Camera);
this.panelWaypoints.Controls.Add(this.BUT_grid);
this.panelWaypoints.Controls.Add(this.BUT_Prefetch);
@ -649,6 +651,7 @@
this.panelMap.ForeColor = System.Drawing.SystemColors.ControlText;
this.panelMap.MinimumSize = new System.Drawing.Size(27, 27);
this.panelMap.Name = "panelMap";
this.panelMap.Resize += new System.EventHandler(this.panelMap_Resize);
//
// lbl_distance
//
@ -831,6 +834,14 @@
resources.ApplyResources(this.panelBASE, "panelBASE");
this.panelBASE.Name = "panelBASE";
//
// BUT_zoomto
//
resources.ApplyResources(this.BUT_zoomto, "BUT_zoomto");
this.BUT_zoomto.Name = "BUT_zoomto";
this.toolTip1.SetToolTip(this.BUT_zoomto, resources.GetString("BUT_zoomto.ToolTip"));
this.BUT_zoomto.UseVisualStyleBackColor = true;
this.BUT_zoomto.Click += new System.EventHandler(this.BUT_zoomto_Click);
//
// FlightPlanner
//
resources.ApplyResources(this, "$this");
@ -942,5 +953,6 @@
private System.Windows.Forms.DataGridViewButtonColumn Delete;
private System.Windows.Forms.DataGridViewImageColumn Up;
private System.Windows.Forms.DataGridViewImageColumn Down;
private MyButton BUT_zoomto;
}
}

View File

@ -642,6 +642,11 @@ namespace ArdupilotMega.GCSViews
updateCMDParams();
// mono
panelMap.Dock = DockStyle.None;
panelMap.Dock = DockStyle.Fill;
panelMap_Resize(null,null);
writeKML();
}
@ -672,7 +677,12 @@ namespace ArdupilotMega.GCSViews
{
selectedrow = e.RowIndex;
string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString();
string cmd = Commands[0, selectedrow].Value.ToString();
string cmd;
try
{
cmd = Commands[Command.Index, selectedrow].Value.ToString();
}
catch { cmd = option; }
Console.WriteLine("editformat " + option + " value " + cmd);
ChangeColumnHeader(cmd);
}
@ -681,6 +691,15 @@ namespace ArdupilotMega.GCSViews
private void Commands_RowsAdded(object sender, DataGridViewRowsAddedEventArgs e)
{
for (int i = 0; i < Commands.ColumnCount; i++)
{
DataGridViewCell tcell = Commands.Rows[e.RowIndex].Cells[i];
if (tcell.GetType() == typeof(DataGridViewTextBoxCell))
{
tcell.Value = "0";
}
}
DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell;
if (cell.Value == null)
{
@ -873,14 +892,8 @@ namespace ArdupilotMega.GCSViews
{
if (Commands.Rows[a].HeaderCell.Value == null)
{
if (ArdupilotMega.MainV2.MAC)
{
Commands.Rows[a].HeaderCell.Value = " " + (a + 1).ToString(); // mac doesnt auto center header text
}
else
{
Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter;
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
}
// skip rows with the correct number
string rowno = Commands.Rows[a].HeaderCell.Value.ToString();
@ -920,14 +933,14 @@ namespace ArdupilotMega.GCSViews
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2));
avglong += double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString());
avglat += double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString());
avglong += double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString());
avglat += double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString());
usable++;
maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), maxlong);
maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), maxlat);
minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), minlong);
minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), minlat);
maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), maxlong);
maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), maxlat);
minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), minlong);
minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), minlat);
System.Diagnostics.Debug.WriteLine(temp - System.Diagnostics.Stopwatch.GetTimestamp());
}
@ -974,9 +987,11 @@ namespace ArdupilotMega.GCSViews
else if (home.Length > 5 && usable == 0)
{
lookat = "<LookAt> <longitude>" + TXT_homelng.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</longitude> <latitude>" + TXT_homelat.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</latitude> <range>4000</range> </LookAt>";
MainMap.HoldInvalidation = true;
MainMap.ZoomAndCenterMarkers("objects");
MainMap.Zoom -= 2;
MainMap_OnMapZoomChanged();
MainMap.HoldInvalidation = false;
}
RegeneratePolygon();
@ -2073,6 +2088,18 @@ namespace ArdupilotMega.GCSViews
// update row headers
((ComboBox)sender).ForeColor = Color.White;
ChangeColumnHeader(((ComboBox)sender).Text);
try
{
for (int i = 0; i < Commands.ColumnCount; i++)
{
DataGridViewCell tcell = Commands.Rows[selectedrow].Cells[i];
if (tcell.GetType() == typeof(DataGridViewTextBoxCell))
{
tcell.Value = "0";
}
}
}
catch { }
}
/// <summary>
/// Get the Google earth ALT for a given coord
@ -2176,12 +2203,21 @@ namespace ArdupilotMega.GCSViews
private void BUT_Prefetch_Click(object sender, EventArgs e)
{
RectLatLng area = MainMap.SelectedArea;
if (area.IsEmpty)
{
DialogResult res = MessageBox.Show("No ripp area defined, ripp displayed on screen?", "Rip", MessageBoxButtons.YesNo);
if (res == DialogResult.Yes)
{
area = MainMap.CurrentViewArea;
}
}
if (!area.IsEmpty)
{
for (int i = (int)MainMap.Zoom; i <= MainMap.MaxZoom; i++)
{
DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + i + " ?", "GMap.NET", MessageBoxButtons.YesNoCancel);
DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + (int)MainMap.Zoom + " ?", "GMap.NET", MessageBoxButtons.YesNo);
for (int i = 1; i <= MainMap.MaxZoom; i++)
{
if (res == DialogResult.Yes)
{
TilePrefetcher obj = new TilePrefetcher();
@ -2588,6 +2624,7 @@ namespace ArdupilotMega.GCSViews
private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e)
{
Commands.Rows.Clear();
selectedrow = 0;
writeKML();
}
@ -2611,7 +2648,7 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = 1;
Commands.Rows[row].Cells[Param3.Index].Value = repeat;
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
}
private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e)
@ -2627,7 +2664,7 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = wp;
Commands.Rows[row].Cells[Param3.Index].Value = repeat;
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
}
private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e)
@ -2697,5 +2734,31 @@ namespace ArdupilotMega.GCSViews
MainV2.fixtheme(form);
form.Show();
}
private void panelMap_Resize(object sender, EventArgs e)
{
// this is a mono fix for the zoom bar
Console.WriteLine("panelmap "+panelMap.Size.ToString());
MainMap.Size = new Size(panelMap.Size.Width - 50,panelMap.Size.Height);
trackBar1.Location = new Point(panelMap.Size.Width - 50,trackBar1.Location.Y);
trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y);
label11.Location = new Point(panelMap.Size.Width - 50, label11.Location.Y);
}
private void BUT_zoomto_Click(object sender, EventArgs e)
{
string place = "Perth, Australia";
Common.InputBox("Location", "Enter your location", ref place);
GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place);
if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
{
MessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
}
else
{
MainMap.Zoom = 15;
}
}
}
}

View File

@ -127,7 +127,7 @@
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_altmode.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 31</value>
<value>213, 31</value>
</data>
<data name="CHK_altmode.Size" type="System.Drawing.Size, System.Drawing">
<value>82, 17</value>
@ -148,7 +148,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_altmode.ZOrder" xml:space="preserve">
<value>3</value>
<value>4</value>
</data>
<data name="CHK_holdalt.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -157,7 +157,7 @@
<value>NoControl</value>
</data>
<data name="CHK_holdalt.Location" type="System.Drawing.Point, System.Drawing">
<value>411, 24</value>
<value>298, 24</value>
</data>
<data name="CHK_holdalt.Size" type="System.Drawing.Size, System.Drawing">
<value>98, 17</value>
@ -178,7 +178,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_holdalt.ZOrder" xml:space="preserve">
<value>8</value>
<value>9</value>
</data>
<data name="Commands.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Bottom, Left, Right</value>
@ -340,7 +340,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;Commands.ZOrder" xml:space="preserve">
<value>10</value>
<value>11</value>
</data>
<data name="CHK_geheight.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -349,7 +349,7 @@
<value>NoControl</value>
</data>
<data name="CHK_geheight.Location" type="System.Drawing.Point, System.Drawing">
<value>411, 40</value>
<value>298, 40</value>
</data>
<data name="CHK_geheight.Size" type="System.Drawing.Size, System.Drawing">
<value>86, 17</value>
@ -370,10 +370,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_geheight.ZOrder" xml:space="preserve">
<value>12</value>
<value>13</value>
</data>
<data name="TXT_WPRad.Location" type="System.Drawing.Point, System.Drawing">
<value>73, 32</value>
<value>23, 36</value>
</data>
<data name="TXT_WPRad.Size" type="System.Drawing.Size, System.Drawing">
<value>36, 20</value>
@ -394,10 +394,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_WPRad.ZOrder" xml:space="preserve">
<value>13</value>
<value>14</value>
</data>
<data name="TXT_DefaultAlt.Location" type="System.Drawing.Point, System.Drawing">
<value>280, 32</value>
<value>154, 36</value>
</data>
<data name="TXT_DefaultAlt.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 20</value>
@ -418,7 +418,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_DefaultAlt.ZOrder" xml:space="preserve">
<value>11</value>
<value>12</value>
</data>
<data name="LBL_WPRad.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -427,7 +427,7 @@
<value>NoControl</value>
</data>
<data name="LBL_WPRad.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 32</value>
<value>9, 24</value>
</data>
<data name="LBL_WPRad.Size" type="System.Drawing.Size, System.Drawing">
<value>61, 13</value>
@ -448,7 +448,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;LBL_WPRad.ZOrder" xml:space="preserve">
<value>4</value>
<value>5</value>
</data>
<data name="LBL_defalutalt.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -457,7 +457,7 @@
<value>NoControl</value>
</data>
<data name="LBL_defalutalt.Location" type="System.Drawing.Point, System.Drawing">
<value>221, 32</value>
<value>151, 24</value>
</data>
<data name="LBL_defalutalt.Size" type="System.Drawing.Size, System.Drawing">
<value>56, 13</value>
@ -478,10 +478,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;LBL_defalutalt.ZOrder" xml:space="preserve">
<value>9</value>
<value>10</value>
</data>
<data name="TXT_loiterrad.Location" type="System.Drawing.Point, System.Drawing">
<value>184, 32</value>
<value>89, 36</value>
</data>
<data name="TXT_loiterrad.Size" type="System.Drawing.Size, System.Drawing">
<value>36, 20</value>
@ -502,7 +502,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_loiterrad.ZOrder" xml:space="preserve">
<value>7</value>
<value>8</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -511,7 +511,7 @@
<value>NoControl</value>
</data>
<data name="label5.Location" type="System.Drawing.Point, System.Drawing">
<value>112, 32</value>
<value>76, 24</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>69, 13</value>
@ -532,7 +532,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
<value>6</value>
<value>7</value>
</data>
<data name="panel5.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Right</value>
@ -556,7 +556,7 @@
<value>BUT_write</value>
</data>
<data name="&gt;&gt;BUT_write.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_write.Parent" xml:space="preserve">
<value>panel5</value>
@ -583,7 +583,7 @@
<value>BUT_read</value>
</data>
<data name="&gt;&gt;BUT_read.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_read.Parent" xml:space="preserve">
<value>panel5</value>
@ -610,7 +610,7 @@
<value>SaveFile</value>
</data>
<data name="&gt;&gt;SaveFile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;SaveFile.Parent" xml:space="preserve">
<value>panel5</value>
@ -637,7 +637,7 @@
<value>BUT_loadwpfile</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Parent" xml:space="preserve">
<value>panel5</value>
@ -1239,11 +1239,41 @@
<data name="&gt;&gt;splitter1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_zoomto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_zoomto.Location" type="System.Drawing.Point, System.Drawing">
<value>746, 26</value>
</data>
<data name="BUT_zoomto.Size" type="System.Drawing.Size, System.Drawing">
<value>62, 23</value>
</data>
<data name="BUT_zoomto.TabIndex" type="System.Int32, mscorlib">
<value>53</value>
</data>
<data name="BUT_zoomto.Text" xml:space="preserve">
<value>Zoom To</value>
</data>
<data name="BUT_zoomto.ToolTip" xml:space="preserve">
<value>Get Camera settings for overlap</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Name" xml:space="preserve">
<value>BUT_zoomto</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_zoomto.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_Camera.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Camera.Location" type="System.Drawing.Point, System.Drawing">
<value>809, 26</value>
<value>692, 26</value>
</data>
<data name="BUT_Camera.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 23</value>
@ -1261,19 +1291,19 @@
<value>BUT_Camera</value>
</data>
<data name="&gt;&gt;BUT_Camera.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Camera.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Camera.ZOrder" xml:space="preserve">
<value>0</value>
<value>1</value>
</data>
<data name="BUT_grid.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_grid.Location" type="System.Drawing.Point, System.Drawing">
<value>755, 26</value>
<value>638, 26</value>
</data>
<data name="BUT_grid.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 23</value>
@ -1291,19 +1321,19 @@
<value>BUT_grid</value>
</data>
<data name="&gt;&gt;BUT_grid.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_grid.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_grid.ZOrder" xml:space="preserve">
<value>1</value>
<value>2</value>
</data>
<data name="BUT_Prefetch.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Prefetch.Location" type="System.Drawing.Point, System.Drawing">
<value>693, 26</value>
<value>576, 26</value>
</data>
<data name="BUT_Prefetch.Size" type="System.Drawing.Size, System.Drawing">
<value>56, 23</value>
@ -1321,19 +1351,19 @@
<value>BUT_Prefetch</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.ZOrder" xml:space="preserve">
<value>2</value>
<value>3</value>
</data>
<data name="button1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="button1.Location" type="System.Drawing.Point, System.Drawing">
<value>596, 26</value>
<value>479, 26</value>
</data>
<data name="button1.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 23</value>
@ -1351,19 +1381,19 @@
<value>button1</value>
</data>
<data name="&gt;&gt;button1.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;button1.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;button1.ZOrder" xml:space="preserve">
<value>5</value>
<value>6</value>
</data>
<data name="BUT_Add.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Add.Location" type="System.Drawing.Point, System.Drawing">
<value>515, 26</value>
<value>398, 26</value>
</data>
<data name="BUT_Add.Size" type="System.Drawing.Size, System.Drawing">
<value>75, 23</value>
@ -1381,13 +1411,13 @@
<value>BUT_Add</value>
</data>
<data name="&gt;&gt;BUT_Add.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Add.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Add.ZOrder" xml:space="preserve">
<value>14</value>
<value>15</value>
</data>
<data name="panelWaypoints.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Bottom</value>
@ -1627,7 +1657,7 @@
<value>Clear Mission</value>
</data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 186</value>
<value>168, 164</value>
</data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value>
@ -1636,7 +1666,7 @@
<value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="MainMap.Location" type="System.Drawing.Point, System.Drawing">
<value>3, 4</value>
<value>0, 0</value>
</data>
<data name="MainMap.Size" type="System.Drawing.Size, System.Drawing">
<value>838, 306</value>
@ -1823,7 +1853,7 @@
<value>trackBar1</value>
</data>
<data name="&gt;&gt;trackBar1.Type" xml:space="preserve">
<value>ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;trackBar1.Parent" xml:space="preserve">
<value>panelMap</value>
@ -2105,6 +2135,6 @@
<value>FlightPlanner</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
</root>

View File

@ -767,4 +767,8 @@
<data name="$this.ToolTip" xml:space="preserve">
<value />
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="MAVCmd" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\Resources\MAVCmd.zh-Hans.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
</data>
</root>

View File

@ -556,7 +556,7 @@ namespace ArdupilotMega.GCSViews
processArduPilot();
}
}
catch { }
catch (Exception ex) { Console.WriteLine("SIM Main loop exception " + ex.ToString()); }
if (hzcounttime.Second != DateTime.Now.Second)
{

View File

@ -178,6 +178,9 @@
<data name="label11.Text" xml:space="preserve">
<value>飞机 IMU</value>
</data>
<data name="label7.Text" xml:space="preserve">
<value>朝向</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>俯仰</value>
</data>
@ -296,13 +299,13 @@
<value>31, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>仅在</value>
<value>仅 在</value>
</data>
<data name="CHKdisplayall.Size" type="System.Drawing.Size, System.Drawing">
<value>178, 17</value>
<value>77, 17</value>
</data>
<data name="CHKdisplayall.Text" xml:space="preserve">
<value>显示所有 (重启程序- 高速 PC)</value>
<value>显示所有 </value>
</data>
<data name="but_advsettings.Text" xml:space="preserve">
<value>高级设置</value>
@ -313,4 +316,25 @@
<data name="chkSensor.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
<value>56, 17</value>
</data>
<data name="CHK_quad.Text" xml:space="preserve">
<value>四 轴</value>
</data>
<data name="BUT_startfgquad.Text" xml:space="preserve">
<value>启动 FG 四轴</value>
</data>
<data name="BUT_startfgplane.Text" xml:space="preserve">
<value>启动 FG 固定翼</value>
</data>
<data name="BUT_startxplane.Text" xml:space="preserve">
<value>启动 Xplane</value>
</data>
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
<value>62, 17</value>
</data>
<data name="CHK_heli.Text" xml:space="preserve">
<value>直升机</value>
</data>
</root>

View File

@ -146,6 +146,11 @@ namespace ArdupilotMega.HIL
accel3D += new Vector3d(0, 0, -gravity);
accel3D += air_resistance;
Random rand = new Random();
int fixme;
//velocity.X += .05 + rand.NextDouble() * .03;
//velocity.Y += .05 + rand.NextDouble() * .03;
//# new velocity vector
velocity += accel3D * delta_time.TotalSeconds;

View File

@ -203,7 +203,14 @@ namespace ArdupilotMega
if (getparams == true)
getParamList();
}
catch (Exception e) { MainV2.givecomport = false; frm.Close(); throw e; }
catch (Exception e) {
try {
BaseStream.Close();
} catch { }
MainV2.givecomport = false;
frm.Close();
throw e;
}
frm.Close();
@ -466,6 +473,8 @@ namespace ArdupilotMega
packetcount++;
//System.Threading.Thread.Sleep(1);
}
@ -485,6 +494,12 @@ namespace ArdupilotMega
/// <param name="value"></param>
public bool setParam(string paramname, float value)
{
if (!param.ContainsKey(paramname))
{
Console.WriteLine("Param doesnt exist " + paramname);
return false;
}
MainV2.givecomport = true;
__mavlink_param_set_t req = new __mavlink_param_set_t();
@ -805,7 +820,7 @@ namespace ArdupilotMega
}
}
public bool doCommand(MAV_CMD actionid)
public bool doCommand(MAV_CMD actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7)
{
MainV2.givecomport = true;
@ -818,6 +833,14 @@ namespace ArdupilotMega
req.command = (ushort)actionid;
req.param1 = p1;
req.param2 = p2;
req.param3 = p3;
req.param4 = p4;
req.param5 = p5;
req.param6 = p6;
req.param7 = p7;
generatePacket(MAVLINK_MSG_ID_COMMAND_LONG, req);
DateTime start = DateTime.Now;

View File

@ -48,6 +48,7 @@
//
// MenuFlightData
//
this.MenuFlightData.AutoSize = false;
this.MenuFlightData.BackgroundImage = global::ArdupilotMega.Properties.Resources.data;
this.MenuFlightData.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFlightData.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -59,6 +60,7 @@
//
// MenuFlightPlanner
//
this.MenuFlightPlanner.AutoSize = false;
this.MenuFlightPlanner.BackgroundImage = global::ArdupilotMega.Properties.Resources.planner;
this.MenuFlightPlanner.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFlightPlanner.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -72,6 +74,7 @@
//
// MenuConfiguration
//
this.MenuConfiguration.AutoSize = false;
this.MenuConfiguration.BackgroundImage = global::ArdupilotMega.Properties.Resources.configuration;
this.MenuConfiguration.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConfiguration.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -85,6 +88,7 @@
//
// MenuSimulation
//
this.MenuSimulation.AutoSize = false;
this.MenuSimulation.BackgroundImage = global::ArdupilotMega.Properties.Resources.simulation;
this.MenuSimulation.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuSimulation.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -98,6 +102,7 @@
//
// MenuFirmware
//
this.MenuFirmware.AutoSize = false;
this.MenuFirmware.BackgroundImage = global::ArdupilotMega.Properties.Resources.firmware;
this.MenuFirmware.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFirmware.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -112,6 +117,7 @@
// MenuConnect
//
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.MenuConnect.AutoSize = false;
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -132,6 +138,7 @@
//
// MainMenu
//
this.MainMenu.AutoSize = false;
this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
@ -159,6 +166,7 @@
//
// MenuTerminal
//
this.MenuTerminal.AutoSize = false;
this.MenuTerminal.BackgroundImage = global::ArdupilotMega.Properties.Resources.terminal;
this.MenuTerminal.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuTerminal.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -198,6 +206,7 @@
//
// MenuHelp
//
this.MenuHelp.AutoSize = false;
this.MenuHelp.BackgroundImage = global::ArdupilotMega.Properties.Resources.help;
this.MenuHelp.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuHelp.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -247,7 +256,6 @@
this.MainMenu.ResumeLayout(false);
this.MainMenu.PerformLayout();
this.ResumeLayout(false);
this.PerformLayout();
}

View File

@ -19,6 +19,7 @@ using System.Speech.Synthesis;
using System.Globalization;
using System.Threading;
using System.Net.Sockets;
using IronPython.Hosting;
namespace ArdupilotMega
{
@ -37,7 +38,7 @@ namespace ArdupilotMega
public static Hashtable config = new Hashtable();
public static bool givecomport = false;
public static Firmwares APMFirmware = Firmwares.ArduPlane;
public static bool MAC = false;
public static bool MONO = false;
public static bool speechenable = false;
public static SpeechSynthesizer talk = new SpeechSynthesizer();
@ -78,6 +79,11 @@ namespace ArdupilotMega
GCSViews.Firmware Firmware;
GCSViews.Terminal Terminal;
public void testpython()
{
Console.WriteLine("hello world from c# via python");
}
public MainV2()
{
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
@ -91,8 +97,17 @@ namespace ArdupilotMega
//return;
var engine = Python.CreateEngine();
var scope = engine.CreateScope();
scope.SetVariable("MainV2",this);
Console.WriteLine(DateTime.Now.Millisecond);
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
Console.WriteLine(DateTime.Now.Millisecond);
engine.CreateScriptSourceFromString("MainV2.testpython()").Execute(scope);
Console.WriteLine(DateTime.Now.Millisecond);
var t = Type.GetType("Mono.Runtime");
MAC = (t != null);
MONO = (t != null);
Form splash = new Splash();
splash.Show();
@ -146,7 +161,7 @@ namespace ArdupilotMega
if (config.ContainsKey("language") && !string.IsNullOrEmpty((string)config["language"]))
changelanguage(getcultureinfo((string)config["language"]));
if (!MAC) // windows only
if (!MONO) // windows only
{
if (MainV2.config["showconsole"] != null && MainV2.config["showconsole"].ToString() == "True")
{
@ -208,7 +223,7 @@ namespace ArdupilotMega
//System.Threading.Thread.Sleep(2000);
// make sure new enough .net framework is installed
if (!MAC)
if (!MONO)
{
Microsoft.Win32.RegistryKey installed_versions = Microsoft.Win32.Registry.LocalMachine.OpenSubKey(@"SOFTWARE\Microsoft\NET Framework Setup\NDP");
string[] version_names = installed_versions.GetSubKeyNames();
@ -216,9 +231,9 @@ namespace ArdupilotMega
double Framework = Convert.ToDouble(version_names[version_names.Length - 1].Remove(0, 1), CultureInfo.InvariantCulture);
int SP = Convert.ToInt32(installed_versions.OpenSubKey(version_names[version_names.Length - 1]).GetValue("SP", 0));
if (Framework < 3.5)
if (Framework < 4.0)
{
MessageBox.Show("This program requires .NET Framework 3.5 +. You currently have " + Framework);
MessageBox.Show("This program requires .NET Framework 4.0 +. You currently have " + Framework);
}
}
@ -742,9 +757,17 @@ namespace ArdupilotMega
{
comportname = CMB_serialport.Text;
if (comportname == "UDP" || comportname == "TCP")
{
CMB_baudrate.Enabled = false;
if (comportname == "TCP")
MainV2.comPort.BaseStream = new TcpSerial();
if (comportname == "UDP")
MainV2.comPort.BaseStream = new UdpSerial();
}
else
{
CMB_baudrate.Enabled = true;
}
try
{
@ -801,7 +824,7 @@ namespace ArdupilotMega
{
try
{
System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None);
//System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None);
XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII);
xmlwriter.Formatting = Formatting.Indented;
@ -816,9 +839,9 @@ namespace ArdupilotMega
xmlwriter.WriteElementString("APMFirmware", APMFirmware.ToString());
appconfig.AppSettings.Settings.Add("comport", comportname);
appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text);
appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString());
//appconfig.AppSettings.Settings.Add("comport", comportname);
//appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text);
//appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString());
foreach (string key in config.Keys)
{
@ -828,7 +851,7 @@ namespace ArdupilotMega
continue;
xmlwriter.WriteElementString(key, config[key].ToString());
appconfig.AppSettings.Settings.Add(key, config[key].ToString());
//appconfig.AppSettings.Settings.Add(key, config[key].ToString());
}
catch { }
}
@ -838,7 +861,7 @@ namespace ArdupilotMega
xmlwriter.WriteEndDocument();
xmlwriter.Close();
appconfig.Save();
//appconfig.Save();
}
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
}
@ -918,7 +941,7 @@ namespace ArdupilotMega
{
try
{
if (!MAC)
if (!MONO)
{
//joystick stuff
@ -972,7 +995,7 @@ namespace ArdupilotMega
int minbytes = 10;
if (MAC)
if (MONO)
minbytes = 0;
DateTime menuupdate = DateTime.Now;
@ -1393,7 +1416,7 @@ namespace ArdupilotMega
string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
bool update = updatecheck(loadinglabel, baseurl, "");
System.Diagnostics.Process P = new System.Diagnostics.Process();
if (MAC)
if (MONO)
{
P.StartInfo.FileName = "mono";
P.StartInfo.Arguments = " \"" + Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "Updater.exe\"";

View File

@ -231,7 +231,7 @@ namespace ArdupilotMega
// create kmz - aka zip file
FileStream fs = File.Open(filename.Replace(".tlog.kml", ".kmz"), FileMode.Create);
FileStream fs = File.Open(filename.Replace(Path.GetExtension(filename), ".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
@ -246,14 +246,12 @@ namespace ArdupilotMega
// Zip the file in buffered chunks
// the "using" will close the stream even if an exception occurs
byte[] buffer = new byte[4096];
using (FileStream streamReader = File.OpenRead(filename))
using (FileStream streamReader = File.Open(filename,FileMode.Open,FileAccess.Read,FileShare.ReadWrite))
{
StreamUtils.Copy(streamReader, zipStream, buffer);
}
zipStream.CloseEntry();
File.Delete(filename);
filename = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "block_plane_0.dae";
// entry 2
@ -275,6 +273,9 @@ namespace ArdupilotMega
zipStream.IsStreamOwner = true; // Makes the Close also Close the underlying stream
zipStream.Close();
File.Delete(filename);
flightdata.Clear();
}

View File

@ -24,7 +24,7 @@ namespace ArdupilotMega
Application.Idle += new EventHandler(Application_Idle);
MessageBox.Show("NOTE: This version may break advanced mission scripting");
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
Application.EnableVisualStyles();
Application.SetCompatibleTextRenderingDefault(false);

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.94")]
[assembly: AssemblyFileVersion("1.0.96")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -1,7 +1,7 @@
//------------------------------------------------------------------------------
// <auto-generated>
// This code was generated by a tool.
// Runtime Version:4.0.30319.235
// Runtime Version:4.0.30319.239
//
// Changes to this file may cause incorrect behavior and will be lost if
// the code is regenerated.

View File

@ -0,0 +1,36 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
namespace ArdupilotMega
{
public class Script
{
DateTime timeout = DateTime.Now;
public enum Conditional
{
LT = 0,
LTEQ,
EQ,
GT,
GTEQ
}
public bool WaitFor(string item, Conditional cond,double value ,int timeoutms)
{
timeout = DateTime.Now;
while (DateTime.Now < timeout.AddMilliseconds(timeoutms))
{
//if (item)
{
}
}
return false;
}
}
}

View File

@ -1444,6 +1444,7 @@
this.Controls.Add(this.tabControl1);
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow;
this.Name = "Setup";
this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing);
this.Load += new System.EventHandler(this.Setup_Load);
this.tabControl1.ResumeLayout(false);
this.tabReset.ResumeLayout(false);

View File

@ -75,7 +75,7 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabHeli)
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "0")
if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
return;
if (HS3.minline == 0)
@ -1055,8 +1055,8 @@ namespace ArdupilotMega.Setup
try
{
#if MAVLINK10
int fixme;
// MainV2.comPort.doCommand(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);
int fixme; // needs to be accel only
MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1);
#else
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);
#endif
@ -1254,5 +1254,11 @@ namespace ArdupilotMega.Setup
if (int.Parse(temp.Text) > 2100)
temp.Text = "2100";
}
private void Setup_FormClosing(object sender, FormClosingEventArgs e)
{
timer.Stop();
timer.Dispose();
}
}
}

View File

@ -117,12 +117,24 @@
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<data name="tabReset.Text" xml:space="preserve">
<value>重置</value>
</data>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
</data>
<data name="tabBattery.Text" xml:space="preserve">
<value>电池</value>
</data>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
@ -151,8 +163,41 @@
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
<value>校准遥控</value>
</data>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
@ -205,21 +250,12 @@
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label106.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label105.Text" xml:space="preserve">
<value>监视器</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
@ -229,14 +265,56 @@
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablebattmon.Text" xml:space="preserve">
<value>启用电池监视器</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<value>电压传感器校准:
1. 测量APM输入电压输入到下方的文本框中
2. 测量电池电压,输入到下方的文本框中
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 13</value>
@ -244,9 +322,6 @@
<data name="label28.Text" xml:space="preserve">
<value>设置水平面的默认加速度计偏移</value>
</data>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
<value>261, 13</value>
</data>
@ -259,17 +334,95 @@
<data name="label15.Text" xml:space="preserve">
<value>机架设置 (+ 或 x)</value>
</data>
<data name="label27.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>陀螺仪感度</value>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="GYR_ENABLE_.Size" type="System.Drawing.Size, System.Drawing">
<value>86, 17</value>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="GYR_ENABLE_.Text" xml:space="preserve">
<value>启用陀螺仪</value>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
@ -283,12 +436,6 @@
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>0 总螺距:</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
@ -301,66 +448,12 @@
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>逆转舵机</value>
</data>
<data name="HS4_REV.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="HS4_REV.Text" xml:space="preserve">
<value>逆转 4</value>
</data>
<data name="label20.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 13</value>
</data>
<data name="label20.Text" xml:space="preserve">
<value>舵机 3</value>
</data>
<data name="label19.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 13</value>
</data>
<data name="label19.Text" xml:space="preserve">
<value>舵机 2</value>
</data>
<data name="label18.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 13</value>
</data>
<data name="label18.Text" xml:space="preserve">
<value>舵机 1</value>
</data>
<data name="HS3_REV.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="HS3_REV.Text" xml:space="preserve">
<value>逆转 3</value>
</data>
<data name="HS2_REV.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="HS2_REV.Text" xml:space="preserve">
<value>逆转 2</value>
</data>
<data name="HS1_REV.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="HS1_REV.Text" xml:space="preserve">
<value>逆转 1</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="BUT_saveheliconfig.Text" xml:space="preserve">
<value>保存行程</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>设置0总螺距</value>
</data>
<data name="$this.Text" xml:space="preserve">
<value>APM设置</value>
</data>

View File

@ -3,6 +3,10 @@
<configSections>
</configSections>
<startup>
<supportedRuntime version="v2.0.50727"/>
<supportedRuntime version="v4.0" sku=".NETFramework,Version=v4.0"/></startup>
<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>
</configuration>

View File

@ -3,15 +3,18 @@
<assemblyIdentity name="ArdupilotMegaPlanner.application" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" xmlns="urn:schemas-microsoft-com:asm.v1" />
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
<deployment install="true" />
<compatibleFrameworks xmlns="urn:schemas-microsoft-com:clickonce.v2">
<framework targetVersion="4.0" profile="Full" supportedRuntime="4.0.30319" />
</compatibleFrameworks>
<dependency>
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="18547">
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="19987">
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
<hash>
<dsig:Transforms>
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>N43U7y77mNy6nfkD9v5DNdwNLps=</dsig:DigestValue>
<dsig:DigestValue>l2Rn8qTiwOzQt8/BkJyqqyHeXA0=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>

View File

@ -3,6 +3,10 @@
<configSections>
</configSections>
<startup>
<supportedRuntime version="v2.0.50727"/>
<supportedRuntime version="v4.0" sku=".NETFramework,Version=v4.0"/></startup>
<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>
</configuration>

View File

@ -127,7 +127,7 @@
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_altmode.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 31</value>
<value>213, 31</value>
</data>
<data name="CHK_altmode.Size" type="System.Drawing.Size, System.Drawing">
<value>82, 17</value>
@ -148,7 +148,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_altmode.ZOrder" xml:space="preserve">
<value>3</value>
<value>4</value>
</data>
<data name="CHK_holdalt.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -157,7 +157,7 @@
<value>NoControl</value>
</data>
<data name="CHK_holdalt.Location" type="System.Drawing.Point, System.Drawing">
<value>411, 24</value>
<value>298, 24</value>
</data>
<data name="CHK_holdalt.Size" type="System.Drawing.Size, System.Drawing">
<value>98, 17</value>
@ -178,7 +178,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_holdalt.ZOrder" xml:space="preserve">
<value>8</value>
<value>9</value>
</data>
<data name="Commands.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Bottom, Left, Right</value>
@ -340,7 +340,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;Commands.ZOrder" xml:space="preserve">
<value>10</value>
<value>11</value>
</data>
<data name="CHK_geheight.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -349,7 +349,7 @@
<value>NoControl</value>
</data>
<data name="CHK_geheight.Location" type="System.Drawing.Point, System.Drawing">
<value>411, 40</value>
<value>298, 40</value>
</data>
<data name="CHK_geheight.Size" type="System.Drawing.Size, System.Drawing">
<value>86, 17</value>
@ -370,10 +370,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;CHK_geheight.ZOrder" xml:space="preserve">
<value>12</value>
<value>13</value>
</data>
<data name="TXT_WPRad.Location" type="System.Drawing.Point, System.Drawing">
<value>73, 32</value>
<value>23, 36</value>
</data>
<data name="TXT_WPRad.Size" type="System.Drawing.Size, System.Drawing">
<value>36, 20</value>
@ -394,10 +394,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_WPRad.ZOrder" xml:space="preserve">
<value>13</value>
<value>14</value>
</data>
<data name="TXT_DefaultAlt.Location" type="System.Drawing.Point, System.Drawing">
<value>280, 32</value>
<value>154, 36</value>
</data>
<data name="TXT_DefaultAlt.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 20</value>
@ -418,7 +418,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_DefaultAlt.ZOrder" xml:space="preserve">
<value>11</value>
<value>12</value>
</data>
<data name="LBL_WPRad.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -427,7 +427,7 @@
<value>NoControl</value>
</data>
<data name="LBL_WPRad.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 32</value>
<value>9, 24</value>
</data>
<data name="LBL_WPRad.Size" type="System.Drawing.Size, System.Drawing">
<value>61, 13</value>
@ -448,7 +448,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;LBL_WPRad.ZOrder" xml:space="preserve">
<value>4</value>
<value>5</value>
</data>
<data name="LBL_defalutalt.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -457,7 +457,7 @@
<value>NoControl</value>
</data>
<data name="LBL_defalutalt.Location" type="System.Drawing.Point, System.Drawing">
<value>221, 32</value>
<value>151, 24</value>
</data>
<data name="LBL_defalutalt.Size" type="System.Drawing.Size, System.Drawing">
<value>56, 13</value>
@ -478,10 +478,10 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;LBL_defalutalt.ZOrder" xml:space="preserve">
<value>9</value>
<value>10</value>
</data>
<data name="TXT_loiterrad.Location" type="System.Drawing.Point, System.Drawing">
<value>184, 32</value>
<value>89, 36</value>
</data>
<data name="TXT_loiterrad.Size" type="System.Drawing.Size, System.Drawing">
<value>36, 20</value>
@ -502,7 +502,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;TXT_loiterrad.ZOrder" xml:space="preserve">
<value>7</value>
<value>8</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -511,7 +511,7 @@
<value>NoControl</value>
</data>
<data name="label5.Location" type="System.Drawing.Point, System.Drawing">
<value>112, 32</value>
<value>76, 24</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>69, 13</value>
@ -532,7 +532,7 @@
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
<value>6</value>
<value>7</value>
</data>
<data name="panel5.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Right</value>
@ -556,7 +556,7 @@
<value>BUT_write</value>
</data>
<data name="&gt;&gt;BUT_write.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_write.Parent" xml:space="preserve">
<value>panel5</value>
@ -583,7 +583,7 @@
<value>BUT_read</value>
</data>
<data name="&gt;&gt;BUT_read.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_read.Parent" xml:space="preserve">
<value>panel5</value>
@ -610,7 +610,7 @@
<value>SaveFile</value>
</data>
<data name="&gt;&gt;SaveFile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;SaveFile.Parent" xml:space="preserve">
<value>panel5</value>
@ -637,7 +637,7 @@
<value>BUT_loadwpfile</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Parent" xml:space="preserve">
<value>panel5</value>
@ -1239,11 +1239,41 @@
<data name="&gt;&gt;splitter1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_zoomto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_zoomto.Location" type="System.Drawing.Point, System.Drawing">
<value>746, 26</value>
</data>
<data name="BUT_zoomto.Size" type="System.Drawing.Size, System.Drawing">
<value>62, 23</value>
</data>
<data name="BUT_zoomto.TabIndex" type="System.Int32, mscorlib">
<value>53</value>
</data>
<data name="BUT_zoomto.Text" xml:space="preserve">
<value>Zoom To</value>
</data>
<data name="BUT_zoomto.ToolTip" xml:space="preserve">
<value>Get Camera settings for overlap</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Name" xml:space="preserve">
<value>BUT_zoomto</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_zoomto.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_Camera.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Camera.Location" type="System.Drawing.Point, System.Drawing">
<value>809, 26</value>
<value>692, 26</value>
</data>
<data name="BUT_Camera.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 23</value>
@ -1261,19 +1291,19 @@
<value>BUT_Camera</value>
</data>
<data name="&gt;&gt;BUT_Camera.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Camera.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Camera.ZOrder" xml:space="preserve">
<value>0</value>
<value>1</value>
</data>
<data name="BUT_grid.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_grid.Location" type="System.Drawing.Point, System.Drawing">
<value>755, 26</value>
<value>638, 26</value>
</data>
<data name="BUT_grid.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 23</value>
@ -1291,19 +1321,19 @@
<value>BUT_grid</value>
</data>
<data name="&gt;&gt;BUT_grid.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_grid.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_grid.ZOrder" xml:space="preserve">
<value>1</value>
<value>2</value>
</data>
<data name="BUT_Prefetch.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Prefetch.Location" type="System.Drawing.Point, System.Drawing">
<value>693, 26</value>
<value>576, 26</value>
</data>
<data name="BUT_Prefetch.Size" type="System.Drawing.Size, System.Drawing">
<value>56, 23</value>
@ -1321,19 +1351,19 @@
<value>BUT_Prefetch</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.ZOrder" xml:space="preserve">
<value>2</value>
<value>3</value>
</data>
<data name="button1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="button1.Location" type="System.Drawing.Point, System.Drawing">
<value>596, 26</value>
<value>479, 26</value>
</data>
<data name="button1.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 23</value>
@ -1351,19 +1381,19 @@
<value>button1</value>
</data>
<data name="&gt;&gt;button1.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;button1.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;button1.ZOrder" xml:space="preserve">
<value>5</value>
<value>6</value>
</data>
<data name="BUT_Add.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_Add.Location" type="System.Drawing.Point, System.Drawing">
<value>515, 26</value>
<value>398, 26</value>
</data>
<data name="BUT_Add.Size" type="System.Drawing.Size, System.Drawing">
<value>75, 23</value>
@ -1381,13 +1411,13 @@
<value>BUT_Add</value>
</data>
<data name="&gt;&gt;BUT_Add.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Add.Parent" xml:space="preserve">
<value>panelWaypoints</value>
</data>
<data name="&gt;&gt;BUT_Add.ZOrder" xml:space="preserve">
<value>14</value>
<value>15</value>
</data>
<data name="panelWaypoints.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Bottom</value>
@ -1627,7 +1657,7 @@
<value>Clear Mission</value>
</data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 186</value>
<value>168, 164</value>
</data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value>
@ -1636,7 +1666,7 @@
<value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="MainMap.Location" type="System.Drawing.Point, System.Drawing">
<value>3, 4</value>
<value>0, 0</value>
</data>
<data name="MainMap.Size" type="System.Drawing.Size, System.Drawing">
<value>838, 306</value>
@ -1823,7 +1853,7 @@
<value>trackBar1</value>
</data>
<data name="&gt;&gt;trackBar1.Type" xml:space="preserve">
<value>ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;trackBar1.Parent" xml:space="preserve">
<value>panelMap</value>
@ -2105,6 +2135,6 @@
<value>FlightPlanner</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
</root>

View File

@ -1,133 +1,133 @@
<?xml version="1.0"?>
<!-- TAGS ARE CASE SENSATIVE -->
<LOGFORMAT>
<AC2>
<GPS>
<F1>Time</F1>
<F2>Sats</F2>
<F3>Lat</F3>
<F4>Long</F4>
<F5>Mix Alt</F5>
<F6>GPSAlt</F6>
<F7>GR Speed</F7>
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
<F2>Target Bear</F2>
<F3>Long Err</F3>
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
</CTUN>
<PM>
<F1>control mode</F1>
<F2>yaw mode</F2>
<F3>r p mode</F3>
<F4>thro mode</F4>
<F5>thro cruise</F5>
<F6>thro int</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>
<GPS>
<F1>Time</F1>
<F2>Fix</F2>
<F3>Sats</F3>
<F4>Lat</F4>
<F5>Long</F5>
<F6>Mix Alt</F6>
<F7>GPSAlt</F7>
<F8>GR Speed</F8>
<F9>CRS</F9>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
</ATT>
<NTUN>
<F1>Yaw</F1>
<F2>WP dist</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Alt Err</F5>
<F6>AS</F6>
<F7>NavGScaler</F7>
<F8></F8>
<F9></F9>
</NTUN>
<CTUN>
<F1>Servo Roll</F1>
<F2>nav_roll</F2>
<F3>roll_sensor</F3>
<F4>Servo Pitch</F4>
<F5>nav_pitch</F5>
<F6>pitch_sensor</F6>
<F7>Servo Throttle</F7>
<F8>Servo Rudder</F8>
<F9>AN 4</F9>
</CTUN>
<PM>
<F1>loop time</F1>
<F2>Main count</F2>
<F3>G_Dt_max</F3>
<F4>Gyro Sat</F4>
<F5>adc constr</F5>
<F6>renorm_sqrt</F6>
<F7>renorm_blowup</F7>
<F8>gps_fix count</F8>
<F9>imu_health</F9>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
</APM>
</LOGFORMAT>
<AC2>
<GPS>
<F1>Time</F1>
<F2>Sats</F2>
<F3>Lat</F3>
<F4>Long</F4>
<F5>Mix Alt</F5>
<F6>GPSAlt</F6>
<F7>GR Speed</F7>
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
<F2>Target Bear</F2>
<F3>Long Err</F3>
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
</CTUN>
<PM>
<F1>control mode</F1>
<F2>yaw mode</F2>
<F3>r p mode</F3>
<F4>thro mode</F4>
<F5>thro cruise</F5>
<F6>thro int</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>
<GPS>
<F1>Time</F1>
<F2>Fix</F2>
<F3>Sats</F3>
<F4>Lat</F4>
<F5>Long</F5>
<F6>Mix Alt</F6>
<F7>GPSAlt</F7>
<F8>GR Speed</F8>
<F9>CRS</F9>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
</ATT>
<NTUN>
<F1>Yaw</F1>
<F2>WP dist</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Alt Err</F5>
<F6>AS</F6>
<F7>NavGScaler</F7>
<F8></F8>
<F9></F9>
</NTUN>
<CTUN>
<F1>Servo Roll</F1>
<F2>nav_roll</F2>
<F3>roll_sensor</F3>
<F4>Servo Pitch</F4>
<F5>nav_pitch</F5>
<F6>pitch_sensor</F6>
<F7>Servo Throttle</F7>
<F8>Servo Rudder</F8>
<F9>AN 4</F9>
</CTUN>
<PM>
<F1>loop time</F1>
<F2>Main count</F2>
<F3>G_Dt_max</F3>
<F4>Gyro Sat</F4>
<F5>adc constr</F5>
<F6>renorm_sqrt</F6>
<F7>renorm_blowup</F7>
<F8>gps_fix count</F8>
<F9>imu_health</F9>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
</APM>
</LOGFORMAT>

View File

@ -1,62 +1,478 @@
<?xml version="1.0"?>
<!-- TAGS ARE CASE SENSATIVE -->
<CMD>
<AC2>
<WAYPOINT><P1>Delay</P1><P2>Hit Rad</P2><P3></P3><P4>Yaw Ang</P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></WAYPOINT>
<LOITER_UNLIM><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_UNLIM>
<LOITER_TURNS><P1>Turns</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TURNS>
<LOITER_TIME><P1>Time s</P1><P2></P2><P3>rad</P3><P4>yaw per</P4><X></X><Y></Y><Z></Z></LOITER_TIME>
<RETURN_TO_LAUNCH><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></RETURN_TO_LAUNCH>
<LAND><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></LAND>
<TAKEOFF><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></TAKEOFF>
<ROI><P1>MAV_ROI</P1><P2>WP#</P2><P3>ROI#</P3><P4></P4><X></X><Y></Y><Z></Z></ROI>
<PATHPLANNING><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></PATHPLANNING>
<CONDITION_DELAY><P1>Time (sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DELAY>
<CONDITION_CHANGE_ALT><P1>Rate (cm/sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE><P1>Dist (m)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DISTANCE>
<CONDITION_YAW><P1>Deg</P1><P2>Sec</P2><P3>Dir 1=CW</P3><P4>rel/abs</P4><X></X><Y></Y><Z></Z></CONDITION_YAW>
<DO_SET_MODE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_MODE>
<DO_JUMP><P1>WP #</P1><P2>Repeat#</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_JUMP>
<DO_CHANGE_SPEED><P1>Type (0=as 1=gs)</P1><P2>Throttle(%)</P2><P3>Speed (m/s)</P3><P4></P4><X></X><Y></Y><Z></Z></DO_CHANGE_SPEED>
<DO_SET_HOME><P1>Current(1)/Spec(0)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_HOME>
<DO_SET_PARAMETER><P1>#</P1><P2>Value</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_PARAMETER>
<DO_SET_RELAY><P1>off(0)/on(1)</P1><P2>Delay (s)</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_RELAY>
<DO_REPEAT_RELAY><P1></P1><P2>Delay (s)</P2><P3>Repeat#</P3><P4></P4><X></X><Y></Y><Z></Z></DO_REPEAT_RELAY>
<DO_SET_SERVO><P1>Ser No</P1><P2>PWM</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_SERVO>
<DO_REPEAT_SERVO><P1>Ser No</P1><P2>Repeat#</P2><P3>Delay (s)</P3><P4>PWM</P4><X></X><Y></Y><Z></Z></DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONTROL>
</AC2>
<!-- -->
<APM>
<WAYPOINT><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></WAYPOINT>
<LOITER_UNLIM><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_UNLIM>
<LOITER_TURNS><P1>Turns</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TURNS>
<LOITER_TIME><P1>Time s</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TIME>
<RETURN_TO_LAUNCH><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></RETURN_TO_LAUNCH>
<LAND><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LAND>
<TAKEOFF><P1>Angle</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></TAKEOFF>
<ROI><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></ROI>
<PATHPLANNING><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></PATHPLANNING>
<CONDITION_DELAY><P1>Time (sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DELAY>
<CONDITION_CHANGE_ALT><P1>Rate (cm/sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE><P1>Dist (m)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DISTANCE>
<CONDITION_YAW><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_YAW>
<DO_SET_MODE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_MODE>
<DO_JUMP><P1>WP #</P1><P2>Repeat#</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_JUMP>
<DO_CHANGE_SPEED><P1>Type (0=as 1=gs)</P1><P2>Throttle(%)</P2><P3>Speed (m/s)</P3><P4></P4><X></X><Y></Y><Z></Z></DO_CHANGE_SPEED>
<DO_SET_HOME><P1>Current(1)/Spec(0)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_HOME>
<DO_SET_PARAMETER><P1>#</P1><P2>Value</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_PARAMETER>
<DO_SET_RELAY><P1>off(0)/on(1)</P1><P2>Delay (s)</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_RELAY>
<DO_REPEAT_RELAY><P1></P1><P2>Delay (s)</P2><P3>Repeat#</P3><P4></P4><X></X><Y></Y><Z></Z></DO_REPEAT_RELAY>
<DO_SET_SERVO><P1>Ser No</P1><P2>PWM</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_SERVO>
<DO_REPEAT_SERVO><P1>Ser No</P1><P2>Repeat#</P2><P3>Delay (s)</P3><P4>PWM</P4><X></X><Y></Y><Z></Z></DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONTROL>
</APM>
<AC2>
<WAYPOINT>
<P1>Delay</P1>
<P2>Hit Rad</P2>
<P3></P3>
<P4>Yaw Ang</P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</WAYPOINT>
<LOITER_UNLIM>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_UNLIM>
<LOITER_TURNS>
<P1>Turns</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TURNS>
<LOITER_TIME>
<P1>Time s</P1>
<P2></P2>
<P3>rad</P3>
<P4>yaw per</P4>
<X></X>
<Y></Y>
<Z></Z>
</LOITER_TIME>
<RETURN_TO_LAUNCH>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</RETURN_TO_LAUNCH>
<LAND>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</LAND>
<TAKEOFF>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</TAKEOFF>
<ROI>
<P1>MAV_ROI</P1>
<P2>WP#</P2>
<P3>ROI#</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</ROI>
<PATHPLANNING>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</PATHPLANNING>
<CONDITION_DELAY>
<P1>Time (sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DELAY>
<CONDITION_CHANGE_ALT>
<P1>Rate (cm/sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE>
<P1>Dist (m)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DISTANCE>
<CONDITION_YAW>
<P1>Deg</P1>
<P2>Sec</P2>
<P3>Dir 1=CW</P3>
<P4>rel/abs</P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_YAW>
<DO_SET_MODE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_MODE>
<DO_JUMP>
<P1>WP #</P1>
<P2>Repeat#</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_JUMP>
<DO_CHANGE_SPEED>
<P1>Type (0=as 1=gs)</P1>
<P2>Throttle(%)</P2>
<P3>Speed (m/s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_CHANGE_SPEED>
<DO_SET_HOME>
<P1>Current(1)/Spec(0)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_HOME>
<DO_SET_PARAMETER>
<P1>#</P1>
<P2>Value</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_PARAMETER>
<DO_SET_RELAY>
<P1>off(0)/on(1)</P1>
<P2>Delay (s)</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_RELAY>
<DO_REPEAT_RELAY>
<P1></P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_RELAY>
<DO_SET_SERVO>
<P1>Ser No</P1>
<P2>PWM</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONTROL>
</AC2>
<!-- -->
<APM>
<WAYPOINT>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</WAYPOINT>
<LOITER_UNLIM>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_UNLIM>
<LOITER_TURNS>
<P1>Turns</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TURNS>
<LOITER_TIME>
<P1>Time s</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TIME>
<RETURN_TO_LAUNCH>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</RETURN_TO_LAUNCH>
<LAND>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LAND>
<TAKEOFF>
<P1>Angle</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</TAKEOFF>
<ROI>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</ROI>
<PATHPLANNING>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</PATHPLANNING>
<CONDITION_DELAY>
<P1>Time (sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DELAY>
<CONDITION_CHANGE_ALT>
<P1>Rate (cm/sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE>
<P1>Dist (m)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DISTANCE>
<CONDITION_YAW>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_YAW>
<DO_SET_MODE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_MODE>
<DO_JUMP>
<P1>WP #</P1>
<P2>Repeat#</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_JUMP>
<DO_CHANGE_SPEED>
<P1>Type (0=as 1=gs)</P1>
<P2>Throttle(%)</P2>
<P3>Speed (m/s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_CHANGE_SPEED>
<DO_SET_HOME>
<P1>Current(1)/Spec(0)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_HOME>
<DO_SET_PARAMETER>
<P1>#</P1>
<P2>Value</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_PARAMETER>
<DO_SET_RELAY>
<P1>off(0)/on(1)</P1>
<P2>Delay (s)</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_RELAY>
<DO_REPEAT_RELAY>
<P1></P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_RELAY>
<DO_SET_SERVO>
<P1>Ser No</P1>
<P2>PWM</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONTROL>
</APM>
</CMD>

View File

@ -1,133 +1,133 @@
<?xml version="1.0"?>
<!-- TAGS ARE CASE SENSATIVE -->
<LOGFORMAT>
<AC2>
<GPS>
<F1>Time</F1>
<F2>Sats</F2>
<F3>Lat</F3>
<F4>Long</F4>
<F5>Mix Alt</F5>
<F6>GPSAlt</F6>
<F7>GR Speed</F7>
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
<F2>Target Bear</F2>
<F3>Long Err</F3>
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
</CTUN>
<PM>
<F1>control mode</F1>
<F2>yaw mode</F2>
<F3>r p mode</F3>
<F4>thro mode</F4>
<F5>thro cruise</F5>
<F6>thro int</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>
<GPS>
<F1>Time</F1>
<F2>Fix</F2>
<F3>Sats</F3>
<F4>Lat</F4>
<F5>Long</F5>
<F6>Mix Alt</F6>
<F7>GPSAlt</F7>
<F8>GR Speed</F8>
<F9>CRS</F9>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
</ATT>
<NTUN>
<F1>Yaw</F1>
<F2>WP dist</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Alt Err</F5>
<F6>AS</F6>
<F7>NavGScaler</F7>
<F8></F8>
<F9></F9>
</NTUN>
<CTUN>
<F1>Servo Roll</F1>
<F2>nav_roll</F2>
<F3>roll_sensor</F3>
<F4>Servo Pitch</F4>
<F5>nav_pitch</F5>
<F6>pitch_sensor</F6>
<F7>Servo Throttle</F7>
<F8>Servo Rudder</F8>
<F9>AN 4</F9>
</CTUN>
<PM>
<F1>loop time</F1>
<F2>Main count</F2>
<F3>G_Dt_max</F3>
<F4>Gyro Sat</F4>
<F5>adc constr</F5>
<F6>renorm_sqrt</F6>
<F7>renorm_blowup</F7>
<F8>gps_fix count</F8>
<F9>imu_health</F9>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
</APM>
</LOGFORMAT>
<AC2>
<GPS>
<F1>Time</F1>
<F2>Sats</F2>
<F3>Lat</F3>
<F4>Long</F4>
<F5>Mix Alt</F5>
<F6>GPSAlt</F6>
<F7>GR Speed</F7>
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>rc1 servo</F4>
<F5>rc2 servo</F5>
<F6>rc3 servo</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
<F2>Target Bear</F2>
<F3>Long Err</F3>
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
<F2>Nav Yaw</F2>
<F3>Yaw Error</F3>
<F4>Sonar Alt</F4>
<F5>Baro Alt</F5>
<F6>Next WP Alt</F6>
<F7>Nav Throttle</F7>
<F8>Angle boost</F8>
<F9>Manual boost</F9>
<F10>rc3 servo out</F10>
<F11>alt hold int</F11>
<F12>thro int</F12>
</CTUN>
<PM>
<F1>control mode</F1>
<F2>yaw mode</F2>
<F3>r p mode</F3>
<F4>thro mode</F4>
<F5>thro cruise</F5>
<F6>thro int</F6>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>
<GPS>
<F1>Time</F1>
<F2>Fix</F2>
<F3>Sats</F3>
<F4>Lat</F4>
<F5>Long</F5>
<F6>Mix Alt</F6>
<F7>GPSAlt</F7>
<F8>GR Speed</F8>
<F9>CRS</F9>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
</ATT>
<NTUN>
<F1>Yaw</F1>
<F2>WP dist</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Alt Err</F5>
<F6>AS</F6>
<F7>NavGScaler</F7>
<F8></F8>
<F9></F9>
</NTUN>
<CTUN>
<F1>Servo Roll</F1>
<F2>nav_roll</F2>
<F3>roll_sensor</F3>
<F4>Servo Pitch</F4>
<F5>nav_pitch</F5>
<F6>pitch_sensor</F6>
<F7>Servo Throttle</F7>
<F8>Servo Rudder</F8>
<F9>AN 4</F9>
</CTUN>
<PM>
<F1>loop time</F1>
<F2>Main count</F2>
<F3>G_Dt_max</F3>
<F4>Gyro Sat</F4>
<F5>adc constr</F5>
<F6>renorm_sqrt</F6>
<F7>renorm_blowup</F7>
<F8>gps_fix count</F8>
<F9>imu_health</F9>
</PM>
<RAW>
<F1>Gyro X</F1>
<F2>Gyro Y</F2>
<F3>Gyro Z</F3>
<F4>Accel X</F4>
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
</APM>
</LOGFORMAT>

View File

@ -0,0 +1,48 @@
using System;
using System.Runtime.InteropServices;
namespace hires
{
public class Stopwatch
{
[DllImport("Kernel32.dll")]
private static extern bool QueryPerformanceCounter(
out long lpPerformanceCount);
[DllImport("Kernel32.dll")]
private static extern bool QueryPerformanceFrequency(
out long lpFrequency);
private long start=0;
private long stop=0;
// static - so this value used in all instances of
private static double frequency = getFrequency();
// Note this is static- called once, before any constructor!
private static double getFrequency()
{
long tempfrequency;
QueryPerformanceFrequency(out tempfrequency);
return tempfrequency; // implicit casting to double from long
}
public void Start()
{
QueryPerformanceCounter(out start);
}
public void Stop()
{
QueryPerformanceCounter(out stop);
}
public double Elapsed
{
get
{
return (double)(stop - start) / frequency;
}
}
}
}

View File

@ -1,62 +1,478 @@
<?xml version="1.0"?>
<!-- TAGS ARE CASE SENSATIVE -->
<CMD>
<AC2>
<WAYPOINT><P1>Delay</P1><P2>Hit Rad</P2><P3></P3><P4>Yaw Ang</P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></WAYPOINT>
<LOITER_UNLIM><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_UNLIM>
<LOITER_TURNS><P1>Turns</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TURNS>
<LOITER_TIME><P1>Time s</P1><P2></P2><P3>rad</P3><P4>yaw per</P4><X></X><Y></Y><Z></Z></LOITER_TIME>
<RETURN_TO_LAUNCH><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></RETURN_TO_LAUNCH>
<LAND><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></LAND>
<TAKEOFF><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></TAKEOFF>
<ROI><P1>MAV_ROI</P1><P2>WP#</P2><P3>ROI#</P3><P4></P4><X></X><Y></Y><Z></Z></ROI>
<PATHPLANNING><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></PATHPLANNING>
<CONDITION_DELAY><P1>Time (sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DELAY>
<CONDITION_CHANGE_ALT><P1>Rate (cm/sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE><P1>Dist (m)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DISTANCE>
<CONDITION_YAW><P1>Deg</P1><P2>Sec</P2><P3>Dir 1=CW</P3><P4>rel/abs</P4><X></X><Y></Y><Z></Z></CONDITION_YAW>
<DO_SET_MODE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_MODE>
<DO_JUMP><P1>WP #</P1><P2>Repeat#</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_JUMP>
<DO_CHANGE_SPEED><P1>Type (0=as 1=gs)</P1><P2>Throttle(%)</P2><P3>Speed (m/s)</P3><P4></P4><X></X><Y></Y><Z></Z></DO_CHANGE_SPEED>
<DO_SET_HOME><P1>Current(1)/Spec(0)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_HOME>
<DO_SET_PARAMETER><P1>#</P1><P2>Value</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_PARAMETER>
<DO_SET_RELAY><P1>off(0)/on(1)</P1><P2>Delay (s)</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_RELAY>
<DO_REPEAT_RELAY><P1></P1><P2>Delay (s)</P2><P3>Repeat#</P3><P4></P4><X></X><Y></Y><Z></Z></DO_REPEAT_RELAY>
<DO_SET_SERVO><P1>Ser No</P1><P2>PWM</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_SERVO>
<DO_REPEAT_SERVO><P1>Ser No</P1><P2>Repeat#</P2><P3>Delay (s)</P3><P4>PWM</P4><X></X><Y></Y><Z></Z></DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONTROL>
</AC2>
<!-- -->
<APM>
<WAYPOINT><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></WAYPOINT>
<LOITER_UNLIM><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_UNLIM>
<LOITER_TURNS><P1>Turns</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TURNS>
<LOITER_TIME><P1>Time s</P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LOITER_TIME>
<RETURN_TO_LAUNCH><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></RETURN_TO_LAUNCH>
<LAND><P1></P1><P2></P2><P3></P3><P4></P4><X>Lat</X><Y>Long</Y><Z>Alt</Z></LAND>
<TAKEOFF><P1>Angle</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></TAKEOFF>
<ROI><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></ROI>
<PATHPLANNING><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></PATHPLANNING>
<CONDITION_DELAY><P1>Time (sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DELAY>
<CONDITION_CHANGE_ALT><P1>Rate (cm/sec)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z>Alt</Z></CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE><P1>Dist (m)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_DISTANCE>
<CONDITION_YAW><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></CONDITION_YAW>
<DO_SET_MODE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_MODE>
<DO_JUMP><P1>WP #</P1><P2>Repeat#</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_JUMP>
<DO_CHANGE_SPEED><P1>Type (0=as 1=gs)</P1><P2>Throttle(%)</P2><P3>Speed (m/s)</P3><P4></P4><X></X><Y></Y><Z></Z></DO_CHANGE_SPEED>
<DO_SET_HOME><P1>Current(1)/Spec(0)</P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_HOME>
<DO_SET_PARAMETER><P1>#</P1><P2>Value</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_PARAMETER>
<DO_SET_RELAY><P1>off(0)/on(1)</P1><P2>Delay (s)</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_RELAY>
<DO_REPEAT_RELAY><P1></P1><P2>Delay (s)</P2><P3>Repeat#</P3><P4></P4><X></X><Y></Y><Z></Z></DO_REPEAT_RELAY>
<DO_SET_SERVO><P1>Ser No</P1><P2>PWM</P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_SET_SERVO>
<DO_REPEAT_SERVO><P1>Ser No</P1><P2>Repeat#</P2><P3>Delay (s)</P3><P4>PWM</P4><X></X><Y></Y><Z></Z></DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL><P1></P1><P2></P2><P3></P3><P4></P4><X></X><Y></Y><Z></Z></DO_MOUNT_CONTROL>
</APM>
<AC2>
<WAYPOINT>
<P1>Delay</P1>
<P2>Hit Rad</P2>
<P3></P3>
<P4>Yaw Ang</P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</WAYPOINT>
<LOITER_UNLIM>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_UNLIM>
<LOITER_TURNS>
<P1>Turns</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TURNS>
<LOITER_TIME>
<P1>Time s</P1>
<P2></P2>
<P3>rad</P3>
<P4>yaw per</P4>
<X></X>
<Y></Y>
<Z></Z>
</LOITER_TIME>
<RETURN_TO_LAUNCH>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</RETURN_TO_LAUNCH>
<LAND>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</LAND>
<TAKEOFF>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</TAKEOFF>
<ROI>
<P1>MAV_ROI</P1>
<P2>WP#</P2>
<P3>ROI#</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</ROI>
<PATHPLANNING>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</PATHPLANNING>
<CONDITION_DELAY>
<P1>Time (sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DELAY>
<CONDITION_CHANGE_ALT>
<P1>Rate (cm/sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE>
<P1>Dist (m)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DISTANCE>
<CONDITION_YAW>
<P1>Deg</P1>
<P2>Sec</P2>
<P3>Dir 1=CW</P3>
<P4>rel/abs</P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_YAW>
<DO_SET_MODE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_MODE>
<DO_JUMP>
<P1>WP #</P1>
<P2>Repeat#</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_JUMP>
<DO_CHANGE_SPEED>
<P1>Type (0=as 1=gs)</P1>
<P2>Throttle(%)</P2>
<P3>Speed (m/s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_CHANGE_SPEED>
<DO_SET_HOME>
<P1>Current(1)/Spec(0)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_HOME>
<DO_SET_PARAMETER>
<P1>#</P1>
<P2>Value</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_PARAMETER>
<DO_SET_RELAY>
<P1>off(0)/on(1)</P1>
<P2>Delay (s)</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_RELAY>
<DO_REPEAT_RELAY>
<P1></P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_RELAY>
<DO_SET_SERVO>
<P1>Ser No</P1>
<P2>PWM</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONTROL>
</AC2>
<!-- -->
<APM>
<WAYPOINT>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</WAYPOINT>
<LOITER_UNLIM>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_UNLIM>
<LOITER_TURNS>
<P1>Turns</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TURNS>
<LOITER_TIME>
<P1>Time s</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LOITER_TIME>
<RETURN_TO_LAUNCH>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</RETURN_TO_LAUNCH>
<LAND>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</LAND>
<TAKEOFF>
<P1>Angle</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</TAKEOFF>
<ROI>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</ROI>
<PATHPLANNING>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</PATHPLANNING>
<CONDITION_DELAY>
<P1>Time (sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DELAY>
<CONDITION_CHANGE_ALT>
<P1>Rate (cm/sec)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z>Alt</Z>
</CONDITION_CHANGE_ALT>
<CONDITION_DISTANCE>
<P1>Dist (m)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_DISTANCE>
<CONDITION_YAW>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</CONDITION_YAW>
<DO_SET_MODE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_MODE>
<DO_JUMP>
<P1>WP #</P1>
<P2>Repeat#</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_JUMP>
<DO_CHANGE_SPEED>
<P1>Type (0=as 1=gs)</P1>
<P2>Throttle(%)</P2>
<P3>Speed (m/s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_CHANGE_SPEED>
<DO_SET_HOME>
<P1>Current(1)/Spec(0)</P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_HOME>
<DO_SET_PARAMETER>
<P1>#</P1>
<P2>Value</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_PARAMETER>
<DO_SET_RELAY>
<P1>off(0)/on(1)</P1>
<P2>Delay (s)</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_RELAY>
<DO_REPEAT_RELAY>
<P1></P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_RELAY>
<DO_SET_SERVO>
<P1>Ser No</P1>
<P2>PWM</P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_SET_SERVO>
<DO_REPEAT_SERVO>
<P1>Ser No</P1>
<P2>Repeat#</P2>
<P3>Delay (s)</P3>
<P4>PWM</P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_REPEAT_SERVO>
<DO_DIGICAM_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONFIGURE>
<DO_DIGICAM_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_DIGICAM_CONTROL>
<DO_MOUNT_CONFIGURE>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONFIGURE>
<DO_MOUNT_CONTROL>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
</DO_MOUNT_CONTROL>
</APM>
</CMD>

Binary file not shown.

View File

@ -175,7 +175,7 @@ def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None):
mavproxy.send('switch 4\n') # auto mode
wait_mode(mav, 'AUTO')
#wait_altitude(mav, 30, 40)
ret = wait_waypoint(mav, 0, num_wp, timeout=90)
ret = wait_waypoint(mav, 0, num_wp, timeout=500)
print("test: MISSION COMPLETE: passed=%s" % ret)
# wait here until ready
mavproxy.send('switch 5\n')
@ -326,19 +326,19 @@ def fly_ArduCopter(viewerip=None):
failed = True
print("# Upload mission1")
if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")):
if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission2.txt")):
failed = True
# this grabs our mission count
print("# store mission1 locally")
if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")):
if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission2.txt")):
failed = True
print("# Fly mission 1")
print("# Fly mission 2")
if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10):
failed = True
else:
print("Flew mission1 OK")
print("Flew mission2 OK")
print("# Land")
if not land(mavproxy, mav):

View File

@ -43,7 +43,7 @@ def dump_logs(atype):
mavproxy.expect("Log]")
for i in range(numlogs):
mavproxy.send("dump %u\n" % (i+1))
mavproxy.expect("logs enabled:", timeout=120)
mavproxy.expect("logs enabled:", timeout=400)
mavproxy.expect("Log]")
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
@ -247,6 +247,7 @@ def run_tests(steps):
if not passed:
print("FAILED %u tests: %s" % (len(failed), failed))
results.addglob("Google Earth track", '*.kml')
results.addfile('Full Logs', 'autotest-output.txt')
results.addglob('DataFlash Log', '*.flashlog')
results.addglob("MAVLink log", '*.mavlog')

View File

@ -63,12 +63,18 @@ def current_location(mav):
mav.messages['VFR_HUD'].alt)
def wait_altitude(mav, alt_min, alt_max, timeout=30):
climb_rate = 0
previous_alt = 0
'''wait for a given altitude range'''
tstart = time.time()
print("Waiting for altitude between %u and %u" % (alt_min, alt_max))
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Altitude %u" % m.alt)
climb_rate = m.alt - previous_alt
previous_alt = m.alt
print("Altitude %u, rate: %u" % (m.alt, climb_rate))
if abs(climb_rate) > 0:
tstart = time.time();
if m.alt >= alt_min and m.alt <= alt_max:
return True
print("Failed to attain altitude range")

Some files were not shown because too many files have changed in this diff Show More