mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
955d159c91
|
@ -52,3 +52,22 @@
|
|||
|
||||
//#define RATE_ROLL_I 0.18
|
||||
//#define RATE_PITCH_I 0.18
|
||||
|
||||
|
||||
|
||||
|
||||
// agmatthews USERHOOKS
|
||||
// the choice of function names is up to the user and does not have to match these
|
||||
// uncomment these hooks and ensure there is a matching function un your "UserCode.pde" file
|
||||
//#define USERHOOK_FASTLOOP userhook_FastLoop();
|
||||
#define USERHOOK_50HZLOOP userhook_50Hz();
|
||||
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop();
|
||||
//#define USERHOOK_SLOWLOOP userhook_SlowLoop();
|
||||
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop();
|
||||
#define USERHOOK_INIT userhook_init();
|
||||
|
||||
// the choice of includeed variables file (*.h) is up to the user and does not have to match this one
|
||||
// Ensure the defined file exists and is in the arducopter directory
|
||||
#define USERHOOK_VARIABLES "UserVariables.h"
|
||||
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "ArduCopter V2.0.48 Beta"
|
||||
#define THISFIRMWARE "ArduCopter V2.0.49 Beta"
|
||||
/*
|
||||
ArduCopter Version 2.0 Beta
|
||||
Authors: Jason Short
|
||||
|
@ -210,6 +210,14 @@ ModeFilter sonar_mode_filter;
|
|||
#error Unrecognised SONAR_TYPE setting.
|
||||
#endif
|
||||
|
||||
// agmatthews USERHOOKS
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// User variables
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#ifdef USERHOOK_VARIABLES
|
||||
#include USERHOOK_VARIABLES
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Global variables
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -425,13 +433,13 @@ static int event_repeat; // how many times to fire : 0 = forever, 1 = do
|
|||
static int event_value; // per command value, such as PWM for servos
|
||||
static int event_undo_value; // the value used to undo commands
|
||||
//static byte repeat_forever;
|
||||
static byte undo_event; // counter for timing the undo
|
||||
//static byte undo_event; // counter for timing the undo
|
||||
|
||||
// delay command
|
||||
// --------------
|
||||
static long condition_value; // used in condition commands (eg delay, change alt, etc.)
|
||||
static long condition_start;
|
||||
static int condition_rate;
|
||||
//static int condition_rate;
|
||||
|
||||
// land command
|
||||
// ------------
|
||||
|
@ -445,12 +453,10 @@ static struct Location prev_WP; // last waypoint
|
|||
static struct Location current_loc; // current location
|
||||
static struct Location next_WP; // next waypoint
|
||||
static struct Location target_WP; // where do we want to you towards?
|
||||
static struct Location simple_WP; //
|
||||
static struct Location next_command; // command preloaded
|
||||
static struct Location guided_WP; // guided mode waypoint
|
||||
static long target_altitude; // used for
|
||||
static boolean home_is_set; // Flag for if we have g_gps lock and have set the home location
|
||||
static boolean new_location; // flag to tell us if location has been updated
|
||||
|
||||
// IMU variables
|
||||
// -------------
|
||||
|
@ -567,6 +573,12 @@ static void fast_loop()
|
|||
|
||||
//if(motor_armed)
|
||||
//Log_Write_Attitude();
|
||||
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_FASTLOOP
|
||||
USERHOOK_FASTLOOP
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
static void medium_loop()
|
||||
|
@ -721,6 +733,10 @@ static void medium_loop()
|
|||
medium_loopCounter = 0;
|
||||
break;
|
||||
}
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_MEDIUMLOOP
|
||||
USERHOOK_MEDIUMLOOP
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
@ -737,6 +753,10 @@ static void fifty_hz_loop()
|
|||
if(g.sonar_enabled){
|
||||
sonar_alt = sonar.read();
|
||||
}
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_50HZLOOP
|
||||
USERHOOK_50HZLOOP
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED && FRAME_CONFIG != HELI_FRAME
|
||||
// HIL for a copter needs very fast update of the servo values
|
||||
|
@ -833,6 +853,11 @@ static void slow_loop()
|
|||
break;
|
||||
|
||||
}
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_SLOWLOOP
|
||||
USERHOOK_SLOWLOOP
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
// 1Hz loop
|
||||
|
@ -842,6 +867,10 @@ static void super_slow_loop()
|
|||
Log_Write_Current();
|
||||
|
||||
gcs_send_message(MSG_HEARTBEAT);
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||
USERHOOK_SUPERSLOWLOOP
|
||||
#endif
|
||||
}
|
||||
|
||||
static void update_GPS(void)
|
||||
|
@ -1047,9 +1076,14 @@ static void update_navigation()
|
|||
case GUIDED:
|
||||
wp_control = WP_MODE;
|
||||
// check if we are close to point > loiter
|
||||
verify_nav_wp();
|
||||
wp_verify_byte = 0;
|
||||
verify_nav_wp();
|
||||
|
||||
update_auto_yaw();
|
||||
if (wp_control == WP_MODE) {
|
||||
update_auto_yaw();
|
||||
} else {
|
||||
set_mode(LOITER);
|
||||
}
|
||||
update_nav_wp();
|
||||
break;
|
||||
|
||||
|
|
|
@ -20,8 +20,11 @@ camera_stabilization()
|
|||
// allow control mixing
|
||||
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor);
|
||||
|
||||
g.rc_camera_pitch.servo_out = (float)g.rc_camera_pitch.servo_out * g.camera_pitch_gain;
|
||||
|
||||
// limit
|
||||
g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500);
|
||||
//g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500);
|
||||
|
||||
// dont allow control mixing
|
||||
/*
|
||||
|
@ -38,10 +41,10 @@ camera_stabilization()
|
|||
*/
|
||||
|
||||
// dont allow control mixing
|
||||
g.rc_camera_roll.servo_out = (float)-dcm.roll_sensor * g.camera_roll_gain;
|
||||
|
||||
// limit
|
||||
g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);
|
||||
|
||||
|
||||
//g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);
|
||||
|
||||
// Output
|
||||
// ------
|
||||
|
|
|
@ -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 = 110;
|
||||
static const uint16_t k_format_version = 111;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
|
@ -128,6 +128,8 @@ public:
|
|||
k_param_throttle_cruise,
|
||||
k_param_esc_calibrate,
|
||||
k_param_radio_tuning,
|
||||
k_param_camera_pitch_gain,
|
||||
k_param_camera_roll_gain,
|
||||
|
||||
//
|
||||
// 210: flight modes
|
||||
|
@ -262,6 +264,8 @@ 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;
|
||||
|
||||
// PI/D controllers
|
||||
APM_PI pi_rate_roll;
|
||||
|
@ -364,8 +368,13 @@ public:
|
|||
rc_6 (k_param_rc_6, PSTR("RC6_")),
|
||||
rc_7 (k_param_rc_7, PSTR("RC7_")),
|
||||
rc_8 (k_param_rc_8, PSTR("RC8_")),
|
||||
rc_camera_pitch (k_param_rc_9, PSTR("RC_CP_")),
|
||||
rc_camera_roll (k_param_rc_10, PSTR("RC_CR_")),
|
||||
rc_camera_pitch (k_param_rc_9, PSTR("CAM_P_")),
|
||||
rc_camera_roll (k_param_rc_10, PSTR("CAM_R_")),
|
||||
|
||||
// variable default key name
|
||||
//-------------------------------------------------------------------------------------------------------------------
|
||||
camera_pitch_gain (CAM_PITCH_GAIN, k_param_camera_pitch_gain, PSTR("CAM_P_G")),
|
||||
camera_roll_gain (CAM_ROLL_GAIN, k_param_camera_roll_gain, PSTR("CAM_R_G")),
|
||||
|
||||
// PI controller group key name initial P initial I initial imax
|
||||
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
|
|
|
@ -0,0 +1,15 @@
|
|||
// agmatthews USERHOOKS
|
||||
|
||||
void userhook_init()
|
||||
{
|
||||
// put your initialisation code here
|
||||
|
||||
|
||||
}
|
||||
|
||||
void userhook_50Hz()
|
||||
{
|
||||
// put your 50Hz code here
|
||||
|
||||
|
||||
}
|
|
@ -0,0 +1,13 @@
|
|||
// agmatthews USERHOOKS
|
||||
// user defined variables
|
||||
|
||||
// example variables used in Wii camera testing - replace with your own variables
|
||||
#if WII_CAMERA == 1
|
||||
WiiCamera ircam;
|
||||
int WiiRange=0;
|
||||
int WiiRotation=0;
|
||||
int WiiDisplacementX=0;
|
||||
int WiiDisplacementY=0;
|
||||
#endif
|
||||
|
||||
|
|
@ -179,6 +179,16 @@
|
|||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// CAMERA GAINS
|
||||
#ifndef CAM_ROLL_GAIN
|
||||
# define CAM_ROLL_GAIN 1.0
|
||||
#endif
|
||||
#ifndef CAM_PITCH_GAIN
|
||||
# define CAM_PITCH_GAIN 1.0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// OPTICAL_FLOW
|
||||
#if defined( __AVR_ATmega2560__ ) // determines if optical flow code is included
|
||||
|
@ -451,15 +461,13 @@
|
|||
#endif
|
||||
|
||||
#ifndef WAYPOINT_SPEED_MAX
|
||||
# define WAYPOINT_SPEED_MAX 300 // for 6m/s error = 13mph
|
||||
# define WAYPOINT_SPEED_MAX 400 // for 6m/s error = 13mph
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Throttle control gains
|
||||
//
|
||||
|
||||
|
||||
#ifndef THROTTLE_CRUISE
|
||||
# define THROTTLE_CRUISE 350 //
|
||||
#endif
|
||||
|
|
|
@ -42,23 +42,24 @@ static void reset_control_switch()
|
|||
read_control_switch();
|
||||
}
|
||||
|
||||
#if CH7_OPTION == CH7_SET_HOVER
|
||||
static boolean trim_flag;
|
||||
#endif
|
||||
|
||||
// read at 10 hz
|
||||
// set this to your trainer switch
|
||||
static void read_trim_switch()
|
||||
{
|
||||
#if CH7_OPTION == CH7_FLIP
|
||||
#if CH7_OPTION == CH7_FLIP
|
||||
if (g.rc_7.control_in > 800 && g.rc_3.control_in != 0){
|
||||
do_flip = true;
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_SIMPLE_MODE
|
||||
|
||||
#elif CH7_OPTION == CH7_SIMPLE_MODE
|
||||
do_simple = (g.rc_7.control_in > 800);
|
||||
//Serial.println(g.rc_7.control_in, DEC);
|
||||
|
||||
#elif CH7_OPTION == CH7_RTL
|
||||
#elif CH7_OPTION == CH7_RTL
|
||||
static bool ch7_rtl_flag = false;
|
||||
|
||||
if (ch7_rtl_flag == false && g.rc_7.control_in > 800){
|
||||
|
@ -73,7 +74,7 @@ static void read_trim_switch()
|
|||
}
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_SET_HOVER
|
||||
#elif CH7_OPTION == CH7_SET_HOVER
|
||||
// switch is engaged
|
||||
if (g.rc_7.control_in > 800){
|
||||
trim_flag = true;
|
||||
|
@ -90,17 +91,19 @@ static void read_trim_switch()
|
|||
trim_flag = false;
|
||||
}
|
||||
}
|
||||
#elif CH7_OPTION == CH7_ADC_FILTER
|
||||
|
||||
#elif CH7_OPTION == CH7_ADC_FILTER
|
||||
if (g.rc_7.control_in > 800){
|
||||
adc.filter_result = true;
|
||||
}else{
|
||||
adc.filter_result = false;
|
||||
}
|
||||
#elif CH7_OPTION == CH7_AUTO_TRIM
|
||||
|
||||
#elif CH7_OPTION == CH7_AUTO_TRIM
|
||||
if (g.rc_7.control_in > 800){
|
||||
auto_level_counter = 10;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -20,30 +20,30 @@ 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);
|
||||
g.heli_servo_2.set_range(0,1000);
|
||||
g.heli_servo_3.set_range(0,1000);
|
||||
g.heli_servo_4.set_angle(4500);
|
||||
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos));
|
||||
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos));
|
||||
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos));
|
||||
|
||||
|
||||
// roll factors
|
||||
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90));
|
||||
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90));
|
||||
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90));
|
||||
|
||||
|
||||
// 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]);
|
||||
}
|
||||
|
||||
|
||||
// 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];
|
||||
|
@ -51,11 +51,11 @@ static void heli_init_swash()
|
|||
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];
|
||||
|
||||
|
||||
// reset the servo averaging
|
||||
for( i=0; i<=3; i++ )
|
||||
heli_servo_out[i] = 0;
|
||||
|
||||
|
||||
// double check heli_servo_averaging is reasonable
|
||||
if( g.heli_servo_averaging < 0 || g.heli_servo_averaging < 0 > 5 ) {
|
||||
g.heli_servo_averaging = 0;
|
||||
|
@ -87,36 +87,36 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
|||
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);
|
||||
if( g.heli_servo_1.get_reverse() )
|
||||
g.heli_servo_1.servo_out = 3000 - g.heli_servo_1.servo_out;
|
||||
|
||||
|
||||
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);
|
||||
if( g.heli_servo_2.get_reverse() )
|
||||
g.heli_servo_2.servo_out = 3000 - g.heli_servo_2.servo_out;
|
||||
|
||||
|
||||
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);
|
||||
if( g.heli_servo_3.get_reverse() )
|
||||
g.heli_servo_3.servo_out = 3000 - g.heli_servo_3.servo_out;
|
||||
|
||||
|
||||
if( g.heli_servo_4.get_reverse() )
|
||||
g.heli_servo_4.servo_out = -yaw_out; // should probably just use rc_4 directly like we do for a tricopter
|
||||
else
|
||||
g.heli_servo_4.servo_out = yaw_out;
|
||||
|
||||
|
||||
// use servo_out to calculate pwm_out and radio_out
|
||||
g.heli_servo_1.calc_pwm();
|
||||
g.heli_servo_2.calc_pwm();
|
||||
g.heli_servo_3.calc_pwm();
|
||||
g.heli_servo_4.calc_pwm();
|
||||
|
||||
g.heli_servo_4.calc_pwm();
|
||||
|
||||
// add the servo values to the averaging
|
||||
heli_servo_out[0] += g.heli_servo_1.servo_out;
|
||||
heli_servo_out[1] += g.heli_servo_2.servo_out;
|
||||
heli_servo_out[2] += g.heli_servo_3.servo_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 ) {
|
||||
|
||||
|
||||
// average the values if necessary
|
||||
if( g.heli_servo_averaging >= 2 ) {
|
||||
heli_servo_out[0] /= g.heli_servo_averaging;
|
||||
|
@ -124,22 +124,24 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
|||
heli_servo_out[2] /= g.heli_servo_averaging;
|
||||
heli_servo_out[3] /= g.heli_servo_averaging;
|
||||
}
|
||||
|
||||
|
||||
// actually move the servos
|
||||
APM_RC.OutputCh(CH_1, heli_servo_out[0]);
|
||||
APM_RC.OutputCh(CH_2, heli_servo_out[1]);
|
||||
APM_RC.OutputCh(CH_3, heli_servo_out[2]);
|
||||
APM_RC.OutputCh(CH_4, heli_servo_out[3]);
|
||||
|
||||
|
||||
// output gyro value
|
||||
if( g.heli_ext_gyro_enabled ) {
|
||||
APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
|
||||
}
|
||||
|
||||
// InstantPWM - force message to the servos
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
|
||||
#endif
|
||||
|
||||
// reset the averaging
|
||||
heli_servo_out_count = 0;
|
||||
heli_servo_out[0] = 0;
|
||||
|
@ -149,6 +151,15 @@ 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
|
||||
ICR3 = 40000; // 50 hz output CH 7, 8, 11
|
||||
#endif
|
||||
}
|
||||
|
||||
// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
|
||||
static void output_motors_armed()
|
||||
{
|
||||
|
|
|
@ -95,9 +95,16 @@ static void calc_loiter(int x_error, int y_error)
|
|||
// nav_roll, nav_pitch
|
||||
static void calc_loiter_pitch_roll()
|
||||
{
|
||||
|
||||
float temp = radians((float)(9000 - (dcm.yaw_sensor))/100.0);
|
||||
float _cos_yaw_x = cos(temp);
|
||||
float _sin_yaw_y = sin(temp);
|
||||
|
||||
// Serial.printf("ys %ld, cyx %1.4f, _cyx %1.4f\n", dcm.yaw_sensor, cos_yaw_x, _cos_yaw_x);
|
||||
|
||||
// rotate the vector
|
||||
nav_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * cos_yaw_x;
|
||||
nav_pitch = (float)nav_lon * cos_yaw_x + (float)nav_lat * sin_yaw_y;
|
||||
nav_roll = (float)nav_lon * _sin_yaw_y - (float)nav_lat * _cos_yaw_x;
|
||||
nav_pitch = (float)nav_lon * _cos_yaw_x + (float)nav_lat * _sin_yaw_y;
|
||||
|
||||
// flip pitch because forward is negative
|
||||
nav_pitch = -nav_pitch;
|
||||
|
@ -115,7 +122,12 @@ static void calc_nav_rate(int max_speed)
|
|||
|
||||
// limit the ramp up of the speed
|
||||
if(waypoint_speed_gov < max_speed){
|
||||
waypoint_speed_gov += 10;
|
||||
|
||||
waypoint_speed_gov += (int)(150.0 * dTnav); // increase at 1.5/ms
|
||||
|
||||
// go at least 1m/s
|
||||
max_speed = max(100, waypoint_speed_gov);
|
||||
// limit with governer
|
||||
max_speed = min(max_speed, waypoint_speed_gov);
|
||||
}
|
||||
|
||||
|
@ -232,7 +244,7 @@ static void reset_crosstrack()
|
|||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
||||
}
|
||||
*/
|
||||
static long get_altitude_above_home(void)
|
||||
/*static long get_altitude_above_home(void)
|
||||
{
|
||||
// This is the altitude above the home location
|
||||
// The GPS gives us altitude at Sea Level
|
||||
|
@ -240,7 +252,7 @@ static long get_altitude_above_home(void)
|
|||
// -------------------------------------------------------------
|
||||
return current_loc.alt - home.alt;
|
||||
}
|
||||
|
||||
*/
|
||||
// distance is returned in meters
|
||||
static long get_distance(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
|
@ -252,12 +264,12 @@ static long get_distance(struct Location *loc1, struct Location *loc2)
|
|||
float dlong = ((float)(loc2->lng - loc1->lng)) * scaleLongDown;
|
||||
return sqrt(sq(dlat) + sq(dlong)) * .01113195;
|
||||
}
|
||||
|
||||
/*
|
||||
static long get_alt_distance(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
return abs(loc1->alt - loc2->alt);
|
||||
}
|
||||
|
||||
*/
|
||||
static long get_bearing(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
long off_x = loc2->lng - loc1->lng;
|
||||
|
|
|
@ -184,11 +184,3 @@ static void trim_radio()
|
|||
g.rc_4.save_eeprom();
|
||||
}
|
||||
|
||||
static void trim_yaw()
|
||||
{
|
||||
for (byte i = 0; i < 30; i++){
|
||||
read_radio();
|
||||
}
|
||||
g.rc_4.trim(); // yaw
|
||||
}
|
||||
|
||||
|
|
|
@ -1,112 +0,0 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#if 0
|
||||
|
||||
#define INPUT_BUF_LEN 40
|
||||
char input_buffer[INPUT_BUF_LEN];
|
||||
|
||||
static void readCommands(void)
|
||||
{
|
||||
static byte header[2];
|
||||
const byte read_GS_header[] = {0x21, 0x21}; //!! Used to verify the payload msg header
|
||||
|
||||
if(Serial.available()){
|
||||
//Serial.println("Serial.available");
|
||||
byte bufferPointer;
|
||||
|
||||
header[0] = Serial.read();
|
||||
header[1] = Serial.read();
|
||||
|
||||
if((header[0] == read_GS_header[0]) && (header[1] == read_GS_header[1])){
|
||||
|
||||
// Block until we read full command
|
||||
// --------------------------------
|
||||
delay(20);
|
||||
byte incoming_val = 0;
|
||||
|
||||
// Ground Station communication
|
||||
// ----------------------------
|
||||
while(Serial.available() > 0)
|
||||
{
|
||||
incoming_val = Serial.read();
|
||||
|
||||
if (incoming_val != 13 && incoming_val != 10 ) {
|
||||
input_buffer[bufferPointer++] = incoming_val;
|
||||
}
|
||||
|
||||
if(bufferPointer >= INPUT_BUF_LEN){
|
||||
Serial.println("Big buffer overrun");
|
||||
bufferPointer = 0;
|
||||
input_buffer[0] = 1;
|
||||
Serial.flush();
|
||||
memset(input_buffer,0,sizeof(input_buffer));
|
||||
return;
|
||||
}
|
||||
}
|
||||
parseCommand(input_buffer);
|
||||
|
||||
// clear buffer of old data
|
||||
// ------------------------
|
||||
memset(input_buffer,0,sizeof(input_buffer));
|
||||
|
||||
}else{
|
||||
Serial.flush();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Commands can be sent as !!a:100|b:200|c:1
|
||||
// -----------------------------------------
|
||||
static void parseCommand(char *buffer)
|
||||
{
|
||||
Serial.println("got cmd ");
|
||||
Serial.println(buffer);
|
||||
char *token, *saveptr1, *saveptr2;
|
||||
|
||||
for (int j = 1;; j++, buffer = NULL) {
|
||||
token = strtok_r(buffer, "|", &saveptr1);
|
||||
if (token == NULL) break;
|
||||
|
||||
char * cmd = strtok_r(token, ":", &saveptr2);
|
||||
long value = strtol(strtok_r (NULL,":", &saveptr2), NULL,0);
|
||||
|
||||
///*
|
||||
Serial.print("cmd ");
|
||||
Serial.print(cmd[0]);
|
||||
Serial.print("\tval ");
|
||||
Serial.println(value);
|
||||
Serial.println("");
|
||||
//*/
|
||||
///*
|
||||
switch(cmd[0]){
|
||||
case 'P':
|
||||
g.pi_stabilize_roll.kP((float)value / 1000);
|
||||
g.pi_stabilize_pitch.kP((float)value / 1000);
|
||||
g.pi_stabilize_pitch.save_gains();
|
||||
break;
|
||||
|
||||
case 'I':
|
||||
g.pi_stabilize_roll.kI((float)value / 1000);
|
||||
g.pi_stabilize_pitch.kI((float)value / 1000);
|
||||
g.pi_stabilize_pitch.save_gains();
|
||||
break;
|
||||
|
||||
case 'D':
|
||||
//g.pi_stabilize_roll.kD((float)value / 1000);
|
||||
//g.pi_stabilize_pitch.kD((float)value / 1000);
|
||||
break;
|
||||
|
||||
case 'X':
|
||||
g.pi_stabilize_roll.imax(value * 100);
|
||||
g.pi_stabilize_pitch.imax(value * 100);
|
||||
g.pi_stabilize_pitch.save_gains();
|
||||
break;
|
||||
|
||||
case 'R':
|
||||
//g.stabilize_dampener.set_and_save((float)value / 1000);
|
||||
break;
|
||||
}
|
||||
//*/
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -132,7 +132,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||
return(-1);
|
||||
|
||||
AP_Var::erase_all();
|
||||
Serial.printf_P(PSTR("\nFACTORY RESET complete - reboot APM"));
|
||||
Serial.printf_P(PSTR("\nReboot APM"));
|
||||
|
||||
delay(1000);
|
||||
//default_gains();
|
||||
|
@ -936,7 +936,7 @@ void report_optflow()
|
|||
static void report_heli()
|
||||
{
|
||||
int servo_rate;
|
||||
|
||||
|
||||
Serial.printf_P(PSTR("Heli\n"));
|
||||
print_divider();
|
||||
|
||||
|
@ -950,7 +950,7 @@ static void report_heli()
|
|||
Serial.printf_P(PSTR("roll max: \t%d\n"), (int)g.heli_roll_max);
|
||||
Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)g.heli_pitch_max);
|
||||
Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_coll_min, (int)g.heli_coll_mid, (int)g.heli_coll_max);
|
||||
|
||||
|
||||
// calculate and print servo rate
|
||||
if( g.heli_servo_averaging <= 1 ) {
|
||||
servo_rate = 250;
|
||||
|
|
|
@ -83,7 +83,6 @@ static void init_ardupilot()
|
|||
//
|
||||
report_version();
|
||||
|
||||
|
||||
// setup IO pins
|
||||
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
|
||||
|
@ -143,6 +142,7 @@ static void init_ardupilot()
|
|||
}
|
||||
|
||||
}else{
|
||||
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Var::load_all();
|
||||
}
|
||||
|
@ -157,7 +157,6 @@ static void init_ardupilot()
|
|||
//
|
||||
Serial3.begin(map_baudrate(g.serial3_baud,SERIAL3_BAUD), 128, 128);
|
||||
|
||||
|
||||
#ifdef RADIO_OVERRIDE_DEFAULTS
|
||||
{
|
||||
int16_t rc_override[8] = RADIO_OVERRIDE_DEFAULTS;
|
||||
|
@ -216,11 +215,7 @@ static void init_ardupilot()
|
|||
//
|
||||
if (check_startup_for_CLI()) {
|
||||
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
|
||||
Serial.printf_P(PSTR("\n"
|
||||
"Entering interactive setup mode...\n"
|
||||
"\n"
|
||||
"Type 'help' to list commands, 'exit' to leave a submenu.\n"
|
||||
"Visit the 'setup' menu for first-time configuration.\n\n"));
|
||||
Serial.printf_P(PSTR("\nCLI:\n\n"));
|
||||
for (;;) {
|
||||
//Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
|
||||
main_menu.run();
|
||||
|
@ -544,6 +539,6 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
|||
case 111: return 111100;
|
||||
case 115: return 115200;
|
||||
}
|
||||
Serial.println_P(PSTR("Invalid SERIAL3_BAUD"));
|
||||
//Serial.println_P(PSTR("Invalid SERIAL3_BAUD"));
|
||||
return default_baud;
|
||||
}
|
||||
|
|
|
@ -29,7 +29,7 @@ static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
|||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t test_optflow(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_mission(uint8_t argc, const Menu::arg *argv);
|
||||
|
|
|
@ -0,0 +1,190 @@
|
|||
%% ArduCopter.cpp
|
||||
%% ArduCopter.o
|
||||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
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
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
|
||||
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/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
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
|
||||
/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:277: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/AP_Relay/AP_Relay.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopter.elf
|
||||
%% ArduCopter.eep
|
||||
%% ArduCopter.hex
|
|
@ -0,0 +1,674 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
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 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
|
||||
00000001 b counter_one_herz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b do_simple
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B relay
|
||||
00000002 T userhook_50Hz()
|
||||
00000002 T userhook_init()
|
||||
00000002 b climb_rate
|
||||
00000002 b loiter_sum
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b loiter_total
|
||||
00000002 b nav_throttle
|
||||
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 event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b waypoint_speed_gov
|
||||
00000002 b heli_manual_override
|
||||
00000002 b heli_servo_out_count
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b airspeed
|
||||
00000002 b sonar_alt
|
||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b simple_cos_x
|
||||
00000004 b simple_sin_y
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b old_target_bearing
|
||||
00000004 b throttle_integrator
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 b original_target_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 B tuning_value
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r report_tuning()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r report_heli()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r init_ardupilot()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r report_gyro()::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a T piezo_on()
|
||||
0000000a T piezo_off()
|
||||
0000000a r 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
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t setup_accel(unsigned char, Menu::arg const*)
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b heli_rollFactor
|
||||
0000000c b heli_pitchFactor
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__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 test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e t send_statustext(mavlink_channel_t)
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r arm_motors()::__c
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_heli(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 print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r report_heli()::__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 b heli_servo_out
|
||||
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_gyro()::__c
|
||||
00000010 r report_heli()::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r setup_heli(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
|
||||
00000012 t gcs_update()
|
||||
00000012 t startup_ground()
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r setup_heli(unsigned char, Menu::arg const*)::__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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r setup_heli(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_heli(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
|
||||
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001a r Log_Read_Nav_Tuning()::__c
|
||||
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
0000001b r report_heli()::__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
|
||||
0000001d r Log_Read_Attitude()::__c
|
||||
0000001e r report_heli()::__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_heli(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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000026 t print_done()
|
||||
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_heli(unsigned char, Menu::arg const*)::__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*)
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t setup_motors(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
0000002f r init_ardupilot()::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000030 t send_heartbeat(mavlink_channel_t)
|
||||
00000030 B imu
|
||||
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000032 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 r Log_Read_GPS()::__c
|
||||
00000033 b pending_status
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 t heli_get_servo(int)
|
||||
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()
|
||||
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()
|
||||
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 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000042 T output_min()
|
||||
00000042 t report_sonar()
|
||||
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000048 t change_command(unsigned char)
|
||||
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 setup_show(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
00000052 W AP_IMU_Shim::update()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
0000005a t report_frame()
|
||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
0000005f r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
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 read_num_from_serial()
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
00000074 t output_motors_armed()
|
||||
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()
|
||||
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 t dump_log(unsigned char, Menu::arg const*)
|
||||
00000092 t report_gyro()
|
||||
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 Log_Read_Motors()
|
||||
0000009b B gcs0
|
||||
0000009b 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
|
||||
000000a6 t send_servo_out(mavlink_channel_t)
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000aa t Log_Read_Nav_Tuning()
|
||||
000000ab B compass
|
||||
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t read_radio()
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
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_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 get_bearing(Location*, Location*)
|
||||
000000d2 t print_switch(unsigned char, unsigned char, bool)
|
||||
000000d4 t get_stabilize_roll(long)
|
||||
000000d4 t get_stabilize_pitch(long)
|
||||
000000d4 t Log_Read(int, int)
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000e0 r test_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()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
00000100 r setup_menu_commands
|
||||
00000106 t setup_gyro(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
00000130 t report_compass()
|
||||
00000148 t Log_Read_GPS()
|
||||
00000156 t update_commands()
|
||||
0000015c t update_trig()
|
||||
00000160 t send_location(mavlink_channel_t)
|
||||
00000160 t send_nav_controller_output(mavlink_channel_t)
|
||||
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)
|
||||
000001a8 t print_radio_values()
|
||||
000001cc t start_new_log()
|
||||
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*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000022a t send_gps_raw(mavlink_channel_t)
|
||||
00000242 t calc_loiter(int, int)
|
||||
0000030c t heli_init_swash()
|
||||
00000312 W Parameters::~Parameters()
|
||||
0000032a t report_heli()
|
||||
00000330 t tuning()
|
||||
00000384 t print_log_menu()
|
||||
0000039a T update_throttle_mode()
|
||||
0000039c t __static_initialization_and_destruction_0(int, int)
|
||||
000003a0 t read_battery()
|
||||
0000045c T update_yaw_mode()
|
||||
0000046e T update_roll_pitch_mode()
|
||||
0000052e t heli_move_swash(int, int, int, int)
|
||||
00000622 t init_ardupilot()
|
||||
0000071a t update_nav_wp()
|
||||
000007ec t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000870 t process_next_command()
|
||||
000009b4 W Parameters::Parameters()
|
||||
00000a1f b g
|
||||
00000ffc T loop
|
||||
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
|
@ -0,0 +1,190 @@
|
|||
%% ArduCopter.cpp
|
||||
%% ArduCopter.o
|
||||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
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
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
|
||||
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/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
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
|
||||
/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:277: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/AP_Relay/AP_Relay.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopter.elf
|
||||
%% ArduCopter.eep
|
||||
%% ArduCopter.hex
|
|
@ -0,0 +1,674 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
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 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
|
||||
00000001 b counter_one_herz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b do_simple
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B relay
|
||||
00000002 T userhook_50Hz()
|
||||
00000002 T userhook_init()
|
||||
00000002 b climb_rate
|
||||
00000002 b loiter_sum
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b loiter_total
|
||||
00000002 b nav_throttle
|
||||
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 event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b waypoint_speed_gov
|
||||
00000002 b heli_manual_override
|
||||
00000002 b heli_servo_out_count
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b airspeed
|
||||
00000002 b sonar_alt
|
||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b simple_cos_x
|
||||
00000004 b simple_sin_y
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b old_target_bearing
|
||||
00000004 b throttle_integrator
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 b original_target_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 B tuning_value
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r report_tuning()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r report_heli()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r init_ardupilot()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r report_gyro()::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a T piezo_on()
|
||||
0000000a T piezo_off()
|
||||
0000000a r 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
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t setup_accel(unsigned char, Menu::arg const*)
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b heli_rollFactor
|
||||
0000000c b heli_pitchFactor
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__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 test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e t send_statustext(mavlink_channel_t)
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r arm_motors()::__c
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_heli(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 print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r report_heli()::__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 b heli_servo_out
|
||||
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_gyro()::__c
|
||||
00000010 r report_heli()::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r setup_heli(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
|
||||
00000012 t gcs_update()
|
||||
00000012 t startup_ground()
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r setup_heli(unsigned char, Menu::arg const*)::__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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r setup_heli(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_heli(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
|
||||
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001a r Log_Read_Nav_Tuning()::__c
|
||||
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
0000001b r report_heli()::__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
|
||||
0000001d r Log_Read_Attitude()::__c
|
||||
0000001e r report_heli()::__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_heli(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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000026 t print_done()
|
||||
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_heli(unsigned char, Menu::arg const*)::__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*)
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t setup_motors(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
0000002f r init_ardupilot()::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000030 t send_heartbeat(mavlink_channel_t)
|
||||
00000030 B imu
|
||||
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000032 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 r Log_Read_GPS()::__c
|
||||
00000033 b pending_status
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 t heli_get_servo(int)
|
||||
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()
|
||||
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()
|
||||
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 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000042 T output_min()
|
||||
00000042 t report_sonar()
|
||||
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000048 t change_command(unsigned char)
|
||||
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 setup_show(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
0000005a t report_frame()
|
||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
0000005f r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
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 read_num_from_serial()
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
00000074 t output_motors_armed()
|
||||
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()
|
||||
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*)
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
00000090 t report_gyro()
|
||||
00000090 t init_compass()
|
||||
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 Log_Read_Motors()
|
||||
0000009b B gcs0
|
||||
0000009b 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
|
||||
000000a6 t send_servo_out(mavlink_channel_t)
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000aa t Log_Read_Nav_Tuning()
|
||||
000000ab B compass
|
||||
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t read_radio()
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000be t update_events()
|
||||
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_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*)
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 t print_switch(unsigned char, unsigned char, bool)
|
||||
000000d4 t get_stabilize_roll(long)
|
||||
000000d4 t get_stabilize_pitch(long)
|
||||
000000d4 t Log_Read(int, int)
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000e0 r test_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()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
00000100 r setup_menu_commands
|
||||
00000108 t setup_gyro(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
00000130 t report_compass()
|
||||
00000148 t Log_Read_GPS()
|
||||
00000156 t update_commands()
|
||||
0000015c t update_trig()
|
||||
00000160 t send_location(mavlink_channel_t)
|
||||
00000160 t send_nav_controller_output(mavlink_channel_t)
|
||||
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)
|
||||
000001a8 t print_radio_values()
|
||||
000001cc t start_new_log()
|
||||
000001e4 t verify_nav_wp()
|
||||
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*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000022a t send_gps_raw(mavlink_channel_t)
|
||||
00000242 t calc_loiter(int, int)
|
||||
0000030c t heli_init_swash()
|
||||
00000312 W Parameters::~Parameters()
|
||||
00000328 t report_heli()
|
||||
00000330 t tuning()
|
||||
00000382 t print_log_menu()
|
||||
0000039a T update_throttle_mode()
|
||||
0000039c t __static_initialization_and_destruction_0(int, int)
|
||||
000003a0 t read_battery()
|
||||
0000045c T update_yaw_mode()
|
||||
0000046e T update_roll_pitch_mode()
|
||||
0000052e t heli_move_swash(int, int, int, int)
|
||||
00000620 t init_ardupilot()
|
||||
0000071a t update_nav_wp()
|
||||
000007e8 t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000870 t process_next_command()
|
||||
000009b4 W Parameters::Parameters()
|
||||
00000a1f b g
|
||||
00000ffc T loop
|
||||
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
|
@ -1,63 +1,48 @@
|
|||
%% ArduCopter.cpp
|
||||
%% ArduCopter.o
|
||||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
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/heli.pde: In function 'void heli_init_swash()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_roll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:444: warning: 'temp' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
|
||||
autogenerated: At global scope:
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
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/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' 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/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:991: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:284: warning: 'heli_servo_out' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:443: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:449: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:463: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used
|
||||
/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:277: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' 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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
|
@ -88,38 +73,13 @@ autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never de
|
|||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/AP_Relay/AP_Relay.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
|
@ -129,6 +89,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
|||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
|
|
|
@ -4,19 +4,19 @@
|
|||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
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 wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b new_radio_frame
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
|
@ -27,48 +27,51 @@
|
|||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b do_simple
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000001 B relay
|
||||
00000002 T userhook_50Hz()
|
||||
00000002 T userhook_init()
|
||||
00000002 b climb_rate
|
||||
00000002 b loiter_sum
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b loiter_total
|
||||
00000002 b nav_throttle
|
||||
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 mainLoop_count
|
||||
00000002 b x_actual_speed
|
||||
00000002 b y_actual_speed
|
||||
00000002 b loiter_time_max
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b waypoint_speed_gov
|
||||
00000002 b heli_manual_override
|
||||
00000002 b heli_servo_out_count
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -77,11 +80,6 @@
|
|||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -94,16 +92,15 @@
|
|||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b circle_angle
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b simple_cos_x
|
||||
00000004 b simple_sin_y
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
|
@ -117,24 +114,21 @@
|
|||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b old_target_bearing
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 b original_target_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
|
@ -155,9 +149,8 @@
|
|||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -175,6 +168,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r report_tuning()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
|
@ -223,6 +217,8 @@
|
|||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
|
@ -230,6 +226,7 @@
|
|||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r init_ardupilot()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -239,9 +236,11 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r report_gyro()::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
|
@ -269,17 +268,19 @@
|
|||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a T piezo_on()
|
||||
0000000a T piezo_off()
|
||||
0000000a r 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
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
|
@ -295,15 +296,16 @@
|
|||
0000000c b heli_pitchFactor
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(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
|
||||
|
@ -319,6 +321,7 @@
|
|||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e t send_statustext(mavlink_channel_t)
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
|
@ -365,22 +368,23 @@
|
|||
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 b heli_servo_out
|
||||
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_gyro()::__c
|
||||
00000010 r report_heli()::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 t gcs_update()
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
|
@ -397,6 +401,8 @@
|
|||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
|
@ -410,23 +416,21 @@
|
|||
00000014 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r setup_heli(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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000017 r __menu_name__main_menu
|
||||
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
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001a r Log_Read_Nav_Tuning()::__c
|
||||
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
0000001b r report_heli()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
|
@ -436,19 +440,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
|
||||
0000001d r Log_Read_Attitude()::__c
|
||||
0000001e r report_heli()::__c
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__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 t byte_swap_4
|
||||
00000021 r setup_heli(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()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
|
@ -459,16 +465,13 @@
|
|||
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
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*)
|
||||
|
@ -479,90 +482,94 @@
|
|||
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 r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t setup_motors(unsigned char, Menu::arg const*)
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
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 Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
0000002f r init_ardupilot()::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000030 t send_heartbeat(mavlink_channel_t)
|
||||
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000032 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 r Log_Read_GPS()::__c
|
||||
00000033 b pending_status
|
||||
00000034 t heli_get_servo(int)
|
||||
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()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
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()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
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 t read_AHRS()
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 B adc
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 T output_min()
|
||||
00000042 t report_sonar()
|
||||
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000048 t change_command(unsigned char)
|
||||
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 setup_show(unsigned char, Menu::arg const*)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 b mavlink_queue
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000050 B imu
|
||||
00000052 t report_version()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t report_frame()
|
||||
0000005a t read_control_switch()
|
||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
0000005f r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 B barometer
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
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 read_num_from_serial()
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
00000074 t output_motors_armed()
|
||||
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()
|
||||
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
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000082 t Log_Write_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
|
@ -571,100 +578,112 @@
|
|||
00000092 t report_gyro()
|
||||
00000092 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000092 t report_tuning()
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
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()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009b B gcs0
|
||||
0000009b 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
|
||||
000000a6 t send_servo_out(mavlink_channel_t)
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000b0 t read_radio()
|
||||
000000aa t Log_Read_Nav_Tuning()
|
||||
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b4 t read_radio()
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
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_Attitude()
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c6 t Log_Read(int, int)
|
||||
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 get_bearing(Location*, Location*)
|
||||
000000d2 t print_switch(unsigned char, unsigned char, bool)
|
||||
000000d4 t get_stabilize_roll(long)
|
||||
000000d4 t get_stabilize_pitch(long)
|
||||
000000d4 t Log_Read(int, int)
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000de t test_adc(unsigned char, Menu::arg const*)
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
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&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
00000100 r setup_menu_commands
|
||||
00000106 t setup_gyro(unsigned char, Menu::arg const*)
|
||||
0000010a t mavlink_delay(unsigned long)
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(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)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
0000011c t get_command_with_index(int)
|
||||
0000012c t calc_loiter_pitch_roll()
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000148 t Log_Read_GPS()
|
||||
00000156 t update_commands()
|
||||
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)
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
00000166 t send_vfr_hud(mavlink_channel_t)
|
||||
00000168 T GCS_MAVLINK::update()
|
||||
0000016c t test_imu(unsigned char, Menu::arg const*)
|
||||
0000016e t send_attitude(mavlink_channel_t)
|
||||
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||
000001a8 t print_radio_values()
|
||||
000001b8 t test_imu(unsigned char, Menu::arg const*)
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t arm_motors()
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
00000202 t set_mode(unsigned char)
|
||||
000001be t arm_motors()
|
||||
000001cc t start_new_log()
|
||||
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000001e6 t verify_nav_wp()
|
||||
000001ea t init_home()
|
||||
00000216 t set_mode(unsigned char)
|
||||
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*)
|
||||
000002b8 t heli_init_swash()
|
||||
000002d0 t report_heli()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000368 t heli_move_swash(int, int, int, int)
|
||||
0000022a t send_gps_raw(mavlink_channel_t)
|
||||
00000242 t calc_loiter(int, int)
|
||||
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||
0000030c t heli_init_swash()
|
||||
00000312 W Parameters::~Parameters()
|
||||
0000032a t report_heli()
|
||||
00000330 t tuning()
|
||||
00000384 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
0000042a T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000556 T update_roll_pitch_mode()
|
||||
00000632 t init_ardupilot()
|
||||
0000071a t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000818 t __static_initialization_and_destruction_0(int, int)
|
||||
000008e4 t process_next_command()
|
||||
0000097a W Parameters::Parameters()
|
||||
000009ad b g
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001af6 T loop
|
||||
0000039a T update_throttle_mode()
|
||||
000003a0 t read_battery()
|
||||
0000045c T update_yaw_mode()
|
||||
0000046e T update_roll_pitch_mode()
|
||||
0000052e t heli_move_swash(int, int, int, int)
|
||||
000005cc t __static_initialization_and_destruction_0(int, int)
|
||||
00000640 t init_ardupilot()
|
||||
0000071a t update_nav_wp()
|
||||
000007ec t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000870 t process_next_command()
|
||||
000009b4 W Parameters::Parameters()
|
||||
00000a1f b g
|
||||
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
0000158a T loop
|
||||
|
|
|
@ -1,63 +1,48 @@
|
|||
%% ArduCopter.cpp
|
||||
%% ArduCopter.o
|
||||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
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/heli.pde: In function 'void heli_init_swash()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_roll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:444: warning: 'temp' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
|
||||
autogenerated: At global scope:
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
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/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' 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/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:991: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:284: warning: 'heli_servo_out' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:443: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:449: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:463: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used
|
||||
/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:277: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' 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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
|
@ -88,38 +73,13 @@ autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never de
|
|||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/AP_Relay/AP_Relay.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
|
@ -129,6 +89,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
|||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
|
|
|
@ -4,19 +4,19 @@
|
|||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
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 wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b new_radio_frame
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
|
@ -27,48 +27,51 @@
|
|||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b do_simple
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000001 B relay
|
||||
00000002 T userhook_50Hz()
|
||||
00000002 T userhook_init()
|
||||
00000002 b climb_rate
|
||||
00000002 b loiter_sum
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b loiter_total
|
||||
00000002 b nav_throttle
|
||||
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 mainLoop_count
|
||||
00000002 b x_actual_speed
|
||||
00000002 b y_actual_speed
|
||||
00000002 b loiter_time_max
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b waypoint_speed_gov
|
||||
00000002 b heli_manual_override
|
||||
00000002 b heli_servo_out_count
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -77,11 +80,6 @@
|
|||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -94,16 +92,15 @@
|
|||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b circle_angle
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b simple_cos_x
|
||||
00000004 b simple_sin_y
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
|
@ -117,24 +114,21 @@
|
|||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b old_target_bearing
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 b original_target_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
|
@ -155,9 +149,8 @@
|
|||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -175,6 +168,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r report_tuning()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
|
@ -223,6 +217,8 @@
|
|||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
|
@ -230,6 +226,7 @@
|
|||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r init_ardupilot()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -239,9 +236,11 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r report_gyro()::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
|
@ -269,17 +268,19 @@
|
|||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a T piezo_on()
|
||||
0000000a T piezo_off()
|
||||
0000000a r 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
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
|
@ -295,15 +296,16 @@
|
|||
0000000c b heli_pitchFactor
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r print_switch(unsigned char, unsigned char, bool)::__c
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(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
|
||||
|
@ -319,6 +321,7 @@
|
|||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e t send_statustext(mavlink_channel_t)
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
|
@ -365,22 +368,23 @@
|
|||
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 b heli_servo_out
|
||||
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_gyro()::__c
|
||||
00000010 r report_heli()::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 t gcs_update()
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
|
@ -397,6 +401,8 @@
|
|||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
00000013 r report_heli()::__c
|
||||
|
@ -410,23 +416,21 @@
|
|||
00000014 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r setup_heli(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_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000017 r __menu_name__main_menu
|
||||
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
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001a r Log_Read_Nav_Tuning()::__c
|
||||
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
0000001b r report_heli()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
|
@ -436,19 +440,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
|
||||
0000001d r Log_Read_Attitude()::__c
|
||||
0000001e r report_heli()::__c
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__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 t byte_swap_4
|
||||
00000021 r setup_heli(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()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
|
@ -459,16 +465,13 @@
|
|||
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
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*)
|
||||
|
@ -479,90 +482,94 @@
|
|||
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 r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t setup_motors(unsigned char, Menu::arg const*)
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
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 Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
0000002f r init_ardupilot()::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000030 t send_heartbeat(mavlink_channel_t)
|
||||
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000032 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000032 r Log_Read_GPS()::__c
|
||||
00000033 b pending_status
|
||||
00000034 t heli_get_servo(int)
|
||||
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()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
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()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
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 t read_AHRS()
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 B adc
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 T output_min()
|
||||
00000042 t report_sonar()
|
||||
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000048 t change_command(unsigned char)
|
||||
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 setup_show(unsigned char, Menu::arg const*)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 b mavlink_queue
|
||||
00000050 t report_version()
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000050 B imu
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t report_frame()
|
||||
0000005a t read_control_switch()
|
||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
0000005f r setup_heli(unsigned char, Menu::arg const*)::__c
|
||||
00000060 t print_switch(unsigned char, unsigned char)
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 B barometer
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
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 read_num_from_serial()
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
00000074 t output_motors_armed()
|
||||
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*)
|
||||
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
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000082 t Log_Write_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
|
@ -571,100 +578,112 @@
|
|||
00000090 t report_gyro()
|
||||
00000090 t report_tuning()
|
||||
00000092 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
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()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009b B gcs0
|
||||
0000009b 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
|
||||
000000a6 t send_servo_out(mavlink_channel_t)
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000b0 t read_radio()
|
||||
000000aa t Log_Read_Nav_Tuning()
|
||||
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b4 t read_radio()
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000be t update_events()
|
||||
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_Attitude()
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t Log_Read(int, int)
|
||||
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 get_bearing(Location*, Location*)
|
||||
000000d0 t print_switch(unsigned char, unsigned char, bool)
|
||||
000000d4 t get_stabilize_roll(long)
|
||||
000000d4 t get_stabilize_pitch(long)
|
||||
000000d4 t Log_Read(int, int)
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000dc t test_adc(unsigned char, Menu::arg const*)
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
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&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
00000100 r setup_menu_commands
|
||||
00000108 t setup_gyro(unsigned char, Menu::arg const*)
|
||||
0000010a t mavlink_delay(unsigned long)
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(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)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
0000011c t get_command_with_index(int)
|
||||
0000012c t calc_loiter_pitch_roll()
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000148 t Log_Read_GPS()
|
||||
00000156 t update_commands()
|
||||
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)
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
00000166 t send_vfr_hud(mavlink_channel_t)
|
||||
00000168 T GCS_MAVLINK::update()
|
||||
0000016c t test_imu(unsigned char, Menu::arg const*)
|
||||
0000016e t send_attitude(mavlink_channel_t)
|
||||
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||
000001a8 t print_radio_values()
|
||||
000001b8 t test_imu(unsigned char, Menu::arg const*)
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t arm_motors()
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
00000202 t set_mode(unsigned char)
|
||||
000001be t arm_motors()
|
||||
000001cc t start_new_log()
|
||||
000001e4 t verify_nav_wp()
|
||||
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000001ea t init_home()
|
||||
00000216 t set_mode(unsigned char)
|
||||
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*)
|
||||
000002b8 t heli_init_swash()
|
||||
000002d0 t report_heli()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000368 t heli_move_swash(int, int, int, int)
|
||||
0000022a t send_gps_raw(mavlink_channel_t)
|
||||
00000242 t calc_loiter(int, int)
|
||||
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||
0000030c t heli_init_swash()
|
||||
00000312 W Parameters::~Parameters()
|
||||
00000328 t report_heli()
|
||||
00000330 t tuning()
|
||||
00000382 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
0000042a T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000556 T update_roll_pitch_mode()
|
||||
00000632 t init_ardupilot()
|
||||
00000718 t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000818 t __static_initialization_and_destruction_0(int, int)
|
||||
000008e4 t process_next_command()
|
||||
0000097a W Parameters::Parameters()
|
||||
000009ad b g
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001af4 T loop
|
||||
0000039a T update_throttle_mode()
|
||||
000003a0 t read_battery()
|
||||
0000045c T update_yaw_mode()
|
||||
0000046e T update_roll_pitch_mode()
|
||||
0000052e t heli_move_swash(int, int, int, int)
|
||||
000005cc t __static_initialization_and_destruction_0(int, int)
|
||||
0000063e t init_ardupilot()
|
||||
0000071a t update_nav_wp()
|
||||
000007e8 t setup_heli(unsigned char, Menu::arg const*)
|
||||
00000870 t process_next_command()
|
||||
000009b4 W Parameters::Parameters()
|
||||
00000a1f b g
|
||||
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
0000158a T loop
|
||||
|
|
|
@ -1,12 +1,5 @@
|
|||
<?xml version="1.0" encoding="utf-8" ?>
|
||||
<options>
|
||||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/crap-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/crap-2560.hex</url2560>
|
||||
<name>Please Update</name>
|
||||
<desc></desc>
|
||||
<format_version>0</format_version>
|
||||
</Firmware>
|
||||
<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>
|
||||
|
@ -102,7 +95,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.43 Beta Heli (2560 only)</name>
|
||||
<name>ArduCopter V2.0.49 Beta Heli (2560 only)</name>
|
||||
<desc>
|
||||
#define AUTO_RESET_LOITER 0
|
||||
#define FRAME_CONFIG HELI_FRAME
|
||||
|
@ -143,7 +136,7 @@
|
|||
#define NAV_LOITER_IMAX 10
|
||||
|
||||
</desc>
|
||||
<format_version>108</format_version>
|
||||
<format_version>111</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
||||
|
@ -161,9 +154,9 @@
|
|||
<format_version>110</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELIHIL-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELIHIL-2560.hex</url2560>
|
||||
<name>Please Update</name>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.49 Beta Heli Hil</name>
|
||||
<desc>
|
||||
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
|
@ -209,6 +202,6 @@
|
|||
|
||||
|
||||
</desc>
|
||||
<format_version>0</format_version>
|
||||
<format_version>111</format_version>
|
||||
</Firmware>
|
||||
</options>
|
||||
|
|
|
@ -1 +1,26 @@
|
|||
Already up-to-date.
|
||||
From https://code.google.com/p/ardupilot-mega
|
||||
6a8104d..b4f49d1 APM_Camera -> origin/APM_Camera
|
||||
d5ab678..7f6c49b master -> origin/master
|
||||
Updating d5ab678..7f6c49b
|
||||
Fast-forward
|
||||
ArduCopter/APM_Config.h | 19 ++++++
|
||||
ArduCopter/ArduCopter.pde | 48 +++++++++++++--
|
||||
ArduCopter/Camera.pde | 11 ++-
|
||||
ArduCopter/Parameters.h | 15 ++++-
|
||||
ArduCopter/UserCode.pde | 15 +++++
|
||||
ArduCopter/UserVariables.h | 13 ++++
|
||||
ArduCopter/config.h | 14 ++++-
|
||||
ArduCopter/control_modes.pde | 19 ++++---
|
||||
ArduCopter/heli.pde | 49 ++++++++++------
|
||||
ArduCopter/navigation.pde | 26 ++++++--
|
||||
ArduCopter/radio.pde | 8 ---
|
||||
ArduCopter/read_commands.pde | 112 ------------------------------------
|
||||
ArduCopter/setup.pde | 6 +-
|
||||
ArduCopter/system.pde | 11 +---
|
||||
ArduCopter/test.pde | 2 +-
|
||||
libraries/Desktop/Desktop.mk | 18 +++---
|
||||
libraries/Desktop/Makefile.desktop | 5 +-
|
||||
17 files changed, 198 insertions(+), 193 deletions(-)
|
||||
create mode 100644 ArduCopter/UserCode.pde
|
||||
create mode 100644 ArduCopter/UserVariables.h
|
||||
delete mode 100644 ArduCopter/read_commands.pde
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#
|
||||
# Copyright (c) 2010 Andrew Tridgell. All rights reserved.
|
||||
# based on Arduino.mk, Copyright (c) 2010 Michael Smith
|
||||
#
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
|
@ -10,7 +10,7 @@
|
|||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in the
|
||||
# documentation and/or other materials provided with the distribution.
|
||||
#
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
|
||||
# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
|
@ -109,7 +109,7 @@ DEPFLAGS = -MD -MT $@
|
|||
# XXX warning options TBD
|
||||
CXXOPTS = -fno-exceptions -D__AVR_ATmega2560__ -I$(SKETCHBOOK)/libraries/Desktop/include -DDESKTOP_BUILD=1
|
||||
COPTS = -I$(SKETCHBOOK)/libraries/Desktop/include -DDESKTOP_BUILD=1
|
||||
ASOPTS = -assembler-with-cpp
|
||||
ASOPTS = -assembler-with-cpp
|
||||
|
||||
CXXFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(CXXOPTS)
|
||||
CFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(COPTS)
|
||||
|
@ -171,12 +171,12 @@ else
|
|||
endif
|
||||
|
||||
# these are library objects we don't want in the desktop build (maybe we'll add them later)
|
||||
NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
|
||||
NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp RC_Channel/RC_Channel_aux.cpp
|
||||
|
||||
#
|
||||
# Find sketchbook libraries referenced by the sketch.
|
||||
#
|
||||
# Include paths for sketch libraries
|
||||
# Include paths for sketch libraries
|
||||
#
|
||||
SKETCHLIBS := $(wildcard $(addprefix $(SKETCHBOOK)/libraries/,$(LIBTOKENS)))
|
||||
SKETCHLIBNAMES := $(notdir $(SKETCHLIBS))
|
||||
|
@ -196,10 +196,10 @@ ARDUINOLIBSRCDIRS := $(ARDUINOLIBS) $(addsuffix /utility,$(ARDUINOLIBS))
|
|||
ARDUINOLIBSRCS := $(wildcard $(foreach suffix,$(SRCSUFFIXES),$(addsuffix /$(suffix),$(ARDUINOLIBSRCDIRS))))
|
||||
ARDUINOLIBOBJS := $(addsuffix .o,$(basename $(subst $(ARDUINO),$(BUILDROOT),$(ARDUINOLIBSRCS))))
|
||||
ARDUINOLIBINCLUDES := $(addprefix -I,$(ARDUINOLIBS))
|
||||
ARDUINOLIBINCLUDES := $(ARDUINOLIBINCLUDES)
|
||||
ARDUINOLIBINCLUDES := $(ARDUINOLIBINCLUDES)
|
||||
|
||||
# Library object files
|
||||
LIBOBJS := $(SKETCHLIBOBJS)
|
||||
LIBOBJS := $(SKETCHLIBOBJS)
|
||||
|
||||
################################################################################
|
||||
# Built products
|
||||
|
@ -212,7 +212,7 @@ SKETCHELF = $(BUILDROOT)/$(SKETCH).elf
|
|||
SKETCHMAP = $(BUILDROOT)/$(SKETCH).map
|
||||
|
||||
# The core library
|
||||
CORELIB =
|
||||
CORELIB =
|
||||
|
||||
# All of the objects that may be built
|
||||
ALLOBJS = $(SKETCHOBJS) $(LIBOBJS) $(CORELIBOBJS)
|
||||
|
@ -338,7 +338,7 @@ $(CORELIB): $(CORELIBOBJS)
|
|||
# This process strives to be as faithful to the Arduino implementation as
|
||||
# possible. Conceptually, the process is as follows:
|
||||
#
|
||||
# * All of the .pde files are concatenated, starting with the file named
|
||||
# * All of the .pde files are concatenated, starting with the file named
|
||||
# for the sketch and followed by the others in alphabetical order.
|
||||
# * An insertion point is created in the concatenated file at
|
||||
# the first statement that isn't a preprocessor directive or comment.
|
||||
|
|
|
@ -3,7 +3,7 @@ DESKTOP=$(PWD)/../libraries/Desktop
|
|||
include ../libraries/Desktop/Desktop.mk
|
||||
|
||||
default:
|
||||
make -f $(DESKTOP)/Makefile.desktop
|
||||
make -f $(DESKTOP)/Makefile.desktop
|
||||
|
||||
nologging:
|
||||
make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DLOGGING_ENABLED=DISABLED"
|
||||
|
@ -22,3 +22,6 @@ hilnocli:
|
|||
|
||||
heli:
|
||||
make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME"
|
||||
|
||||
helihil:
|
||||
make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME -DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
|
||||
|
|
Loading…
Reference in New Issue