mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
d3a30f8d70
|
@ -0,0 +1,3 @@
|
|||
.metadata/
|
||||
Tools/ArdupilotMegaPlanner/bin/Release/logs/
|
||||
config.mk
|
|
@ -296,6 +296,7 @@ static boolean motor_auto_armed; // if true,
|
|||
//int max_stabilize_dampener; //
|
||||
//int max_yaw_dampener; //
|
||||
static Vector3f omega;
|
||||
float tuning_value;
|
||||
|
||||
// LED output
|
||||
// ----------
|
||||
|
@ -315,11 +316,13 @@ static bool did_ground_start = false; // have we ground started after first ar
|
|||
// ---------------------
|
||||
static const float radius_of_earth = 6378100; // meters
|
||||
static const float gravity = 9.81; // meters/ sec^2
|
||||
static long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate
|
||||
//static long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate
|
||||
static long target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
||||
|
||||
static bool xtrack_enabled = false;
|
||||
static long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
//static bool xtrack_enabled = false;
|
||||
//static long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
//static long crosstrack_correction; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
|
||||
static int climb_rate; // m/s * 100 - For future implementation of controlled ascent/descent by rate
|
||||
static long circle_angle = 0;
|
||||
static byte wp_control; // used to control - navgation or loiter
|
||||
|
@ -348,7 +351,7 @@ static int airspeed; // m/s * 100
|
|||
|
||||
// Location Errors
|
||||
// ---------------
|
||||
static long bearing_error; // deg * 100 : 0 to 36000
|
||||
//static long bearing_error; // deg * 100 : 0 to 36000
|
||||
static long altitude_error; // meters * 100 we are off in altitude
|
||||
static long old_altitude;
|
||||
static long yaw_error; // how off are we pointed
|
||||
|
@ -507,7 +510,7 @@ static byte simple_timer; // for limiting the execution of flight mode thi
|
|||
|
||||
static unsigned long dTnav; // Delta Time in milliseconds for navigation computations
|
||||
static unsigned long nav_loopTimer; // used to track the elapsed ime for GPS nav
|
||||
static float load; // % MCU cycles used
|
||||
//static float load; // % MCU cycles used
|
||||
|
||||
static byte counter_one_herz;
|
||||
static bool GPS_enabled = false;
|
||||
|
@ -526,11 +529,11 @@ void loop()
|
|||
{
|
||||
// We want this to execute fast
|
||||
// ----------------------------
|
||||
if (millis() - fast_loopTimer >= 5) {
|
||||
if (millis() - fast_loopTimer >= 4) {
|
||||
//PORTK |= B00010000;
|
||||
delta_ms_fast_loop = millis() - fast_loopTimer;
|
||||
fast_loopTimer = millis();
|
||||
load = float(fast_loopTimeStamp - fast_loopTimer) / delta_ms_fast_loop;
|
||||
//load = float(fast_loopTimeStamp - fast_loopTimer) / delta_ms_fast_loop;
|
||||
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
|
||||
mainLoop_count++;
|
||||
|
||||
|
@ -542,6 +545,7 @@ void loop()
|
|||
fast_loop();
|
||||
fast_loopTimeStamp = millis();
|
||||
}
|
||||
//PORTK &= B11101111;
|
||||
|
||||
if (millis() - fiftyhz_loopTimer > 19) {
|
||||
delta_ms_fiftyhz = millis() - fiftyhz_loopTimer;
|
||||
|
@ -576,7 +580,6 @@ void loop()
|
|||
}
|
||||
//PORTK &= B10111111;
|
||||
}
|
||||
//PORTK &= B11101111;
|
||||
}
|
||||
// PORTK |= B01000000;
|
||||
// PORTK &= B10111111;
|
||||
|
@ -673,8 +676,8 @@ static void medium_loop()
|
|||
// ------------------------------------------------------
|
||||
navigate();
|
||||
|
||||
// control mode specific updates to nav_bearing
|
||||
// --------------------------------------------
|
||||
// control mode specific updates
|
||||
// -----------------------------
|
||||
update_navigation();
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_NTUN)
|
||||
|
@ -798,7 +801,7 @@ static void fifty_hz_loop()
|
|||
#endif
|
||||
|
||||
// use Yaw to find our bearing error
|
||||
calc_bearing_error();
|
||||
//calc_bearing_error();
|
||||
|
||||
//if (throttle_slew < 0)
|
||||
// throttle_slew++;
|
||||
|
@ -907,16 +910,15 @@ static void slow_loop()
|
|||
// between 1 and 5 Hz
|
||||
#else
|
||||
gcs.send_message(MSG_LOCATION);
|
||||
gcs.send_message(MSG_CPU_LOAD, load*100);
|
||||
//gcs.send_message(MSG_CPU_LOAD, load*100);
|
||||
#endif
|
||||
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0)
|
||||
hil.data_stream_send(1,5);
|
||||
#endif
|
||||
|
||||
#if CHANNEL_6_TUNING != CH6_NONE
|
||||
if(g.radio_tuning > 0)
|
||||
tuning();
|
||||
#endif
|
||||
|
||||
// filter out the baro offset.
|
||||
//if(baro_alt_offset > 0) baro_alt_offset--;
|
||||
|
@ -1246,7 +1248,7 @@ static void update_navigation()
|
|||
wp_control = WP_MODE;
|
||||
}else{
|
||||
set_mode(LOITER);
|
||||
xtrack_enabled = false;
|
||||
//xtrack_enabled = false;
|
||||
}
|
||||
|
||||
|
||||
|
@ -1268,16 +1270,13 @@ static void update_navigation()
|
|||
// calculates desired Yaw
|
||||
update_auto_yaw();
|
||||
{
|
||||
circle_angle += dTnav; //1000 * (dTnav/1000);
|
||||
|
||||
if (circle_angle >= 36000)
|
||||
circle_angle -= 36000;
|
||||
//circle_angle += dTnav; //1000 * (dTnav/1000);
|
||||
circle_angle = wrap_360(target_bearing + 2000 + 18000);
|
||||
|
||||
target_WP.lng = next_WP.lng + g.loiter_radius * cos(radians(90 - circle_angle));
|
||||
target_WP.lat = next_WP.lat + g.loiter_radius * sin(radians(90 - circle_angle));
|
||||
}
|
||||
|
||||
|
||||
// calc the lat and long error to the target
|
||||
calc_location_error(&target_WP);
|
||||
|
||||
|
@ -1301,7 +1300,7 @@ static void read_AHRS(void)
|
|||
hil.update();
|
||||
#endif
|
||||
|
||||
dcm.update_DCM(G_Dt);
|
||||
dcm.update_DCM_fast(G_Dt);//, _tog);
|
||||
omega = dcm.get_gyro();
|
||||
}
|
||||
|
||||
|
@ -1396,68 +1395,75 @@ adjust_altitude()
|
|||
}
|
||||
|
||||
static void tuning(){
|
||||
tuning_value = (float)g.rc_6.control_in / 1000.0;
|
||||
|
||||
//Outer Loop : Attitude
|
||||
#if CHANNEL_6_TUNING == CH6_STABILIZE_KP
|
||||
g.pi_stabilize_roll.kP((float)g.rc_6.control_in / 1000.0);
|
||||
g.pi_stabilize_pitch.kP((float)g.rc_6.control_in / 1000.0);
|
||||
switch(g.radio_tuning){
|
||||
case CH6_STABILIZE_KP:
|
||||
g.rc_6.set_range(0,8000); // 0 to 8
|
||||
g.pi_stabilize_roll.kP(tuning_value);
|
||||
g.pi_stabilize_pitch.kP(tuning_value);
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_STABILIZE_KI
|
||||
g.pi_stabilize_roll.kI((float)g.rc_6.control_in / 1000.0);
|
||||
g.pi_stabilize_pitch.kI((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_STABILIZE_KI:
|
||||
g.rc_6.set_range(0,300); // 0 to .3
|
||||
tuning_value = (float)g.rc_6.control_in / 1000.0;
|
||||
g.pi_stabilize_roll.kI(tuning_value);
|
||||
g.pi_stabilize_pitch.kI(tuning_value);
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_KP
|
||||
g.pi_stabilize_yaw.kP((float)g.rc_6.control_in / 1000.0); // range from 0.0 ~ 5.0
|
||||
case CH6_RATE_KP:
|
||||
g.rc_6.set_range(0,300); // 0 to .3
|
||||
g.pi_rate_roll.kP(tuning_value);
|
||||
g.pi_rate_pitch.kP(tuning_value);
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_KI
|
||||
g.pi_stabilize_yaw.kI((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_RATE_KI:
|
||||
g.rc_6.set_range(0,300); // 0 to .3
|
||||
g.pi_rate_roll.kI(tuning_value);
|
||||
g.pi_rate_pitch.kI(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_YAW_KP:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.pi_stabilize_yaw.kP(tuning_value);
|
||||
break;
|
||||
|
||||
//Inner Loop : Rate
|
||||
#elif CHANNEL_6_TUNING == CH6_RATE_KP
|
||||
g.pi_rate_roll.kP((float)g.rc_6.control_in / 1000.0);
|
||||
g.pi_rate_pitch.kP((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_YAW_RATE_KP:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.pi_rate_yaw.kP(tuning_value);
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_RATE_KI
|
||||
g.pi_rate_roll.kI((float)g.rc_6.control_in / 1000.0);
|
||||
g.pi_rate_pitch.kI((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_THROTTLE_KP:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.pi_throttle.kP(tuning_value);
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_RATE_KP
|
||||
g.pi_rate_yaw.kP((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_TOP_BOTTOM_RATIO:
|
||||
g.rc_6.set_range(800,1000); // .8 to 1
|
||||
g.top_bottom_ratio = tuning_value;
|
||||
break;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_RATE_KI
|
||||
g.pi_rate_yaw.kI((float)g.rc_6.control_in / 1000.0);
|
||||
case CH6_RELAY:
|
||||
g.rc_6.set_range(0,1000);
|
||||
if (g.rc_6.control_in <= 600) relay_on();
|
||||
if (g.rc_6.control_in >= 400) relay_off();
|
||||
break;
|
||||
|
||||
case CH6_TRAVERSE_SPEED:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.waypoint_speed_max = g.rc_6.control_in;
|
||||
break;
|
||||
|
||||
//Altitude Hold
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KP
|
||||
g.pi_throttle.kP((float)g.rc_6.control_in / 1000.0); // 0 to 1
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KD
|
||||
g.pi_throttle.kD((float)g.rc_6.control_in / 1000.0); // 0 to 1
|
||||
|
||||
//Extras
|
||||
#elif CHANNEL_6_TUNING == CH6_TOP_BOTTOM_RATIO
|
||||
g.top_bottom_ratio = (float)g.rc_6.control_in / 1000.0;
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_TRAVERSE_SPEED
|
||||
g.waypoint_speed_max = (float)g.rc_6.control_in / 1000.0;
|
||||
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_PMAX
|
||||
g.pitch_max.set(g.rc_6.control_in * 2); // 0 to 2000
|
||||
|
||||
// Simple relay control
|
||||
#elif CHANNEL_6_TUNING == CH6_RELAY
|
||||
if(g.rc_6.control_in <= 600) relay_on();
|
||||
if(g.rc_6.control_in >= 400) relay_off();
|
||||
|
||||
#endif
|
||||
case CH6_NAV_P:
|
||||
g.rc_6.set_range(0,6000);
|
||||
g.pi_nav_lat.kP(tuning_value);
|
||||
g.pi_nav_lon.kP(tuning_value);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void update_nav_wp()
|
||||
{
|
||||
// XXX Guided mode!!!
|
||||
if(wp_control == LOITER_MODE){
|
||||
|
||||
// calc a pitch to the target
|
||||
|
|
|
@ -102,7 +102,7 @@ get_nav_throttle(long z_error, int target_speed)
|
|||
rate_error = constrain(rate_error, -110, 110);
|
||||
|
||||
throttle = g.pi_throttle.get_pi(rate_error, delta_ms_medium_loop);
|
||||
return g.throttle_cruise + rate_error;
|
||||
return g.throttle_cruise + throttle;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -12,7 +12,7 @@ void HIL_XPLANE::output_HIL(void)
|
|||
output_int((int)(g.rc_3.servo_out)); // 2 bytes 4, 5
|
||||
output_int((int)(g.rc_4.servo_out)); // 3 bytes 6, 7
|
||||
output_int((int)wp_distance); // 4 bytes 8,9
|
||||
output_int((int)bearing_error); // 5 bytes 10,11
|
||||
//output_int((int)bearing_error); // 5 bytes 10,11
|
||||
output_int((int)altitude_error); // 6 bytes 12, 13
|
||||
output_int((int)energy_error); // 7 bytes 14,15
|
||||
output_byte((int)g.waypoint_index); // 8 bytes 16
|
||||
|
|
|
@ -537,9 +537,8 @@ static void Log_Write_Nav_Tuning()
|
|||
DataFlash.WriteInt((int)wp_distance); // 1
|
||||
DataFlash.WriteByte(wp_verify_byte); // 2
|
||||
DataFlash.WriteInt((int)(target_bearing/100)); // 3
|
||||
DataFlash.WriteInt((int)(nav_bearing/100)); // 4
|
||||
DataFlash.WriteInt((int)long_error); // 5
|
||||
DataFlash.WriteInt((int)lat_error); // 6
|
||||
DataFlash.WriteInt((int)long_error); // 4
|
||||
DataFlash.WriteInt((int)lat_error); // 5
|
||||
|
||||
|
||||
/*
|
||||
|
@ -568,7 +567,6 @@ static void Log_Read_Nav_Tuning()
|
|||
DataFlash.ReadInt(), // distance
|
||||
DataFlash.ReadByte(), // wp_verify_byte
|
||||
DataFlash.ReadInt(), // target_bearing
|
||||
DataFlash.ReadInt(), // nav_bearing
|
||||
|
||||
DataFlash.ReadInt(), // long_error
|
||||
DataFlash.ReadInt()); // lat_error
|
||||
|
|
|
@ -87,7 +87,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
|
|||
mode,
|
||||
nav_mode,
|
||||
status,
|
||||
load * 1000,
|
||||
0,
|
||||
battery_voltage * 1000,
|
||||
battery_remaining,
|
||||
packet_drops);
|
||||
|
@ -142,7 +142,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
|
|||
chan,
|
||||
nav_roll / 1.0e2,
|
||||
nav_pitch / 1.0e2,
|
||||
nav_bearing / 1.0e2,
|
||||
target_bearing / 1.0e2,
|
||||
target_bearing / 1.0e2,
|
||||
wp_distance,
|
||||
altitude_error / 1.0e2,
|
||||
|
@ -294,14 +294,14 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
|
|||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
Vector3f mag_offsets = compass.get_offsets();
|
||||
|
||||
mavlink_msg_sensor_offsets_send(chan,
|
||||
mavlink_msg_sensor_offsets_send(chan,
|
||||
mag_offsets.x,
|
||||
mag_offsets.y,
|
||||
mag_offsets.z,
|
||||
compass.get_declination(),
|
||||
barometer.RawPress,
|
||||
barometer.RawPress,
|
||||
barometer.RawTemp,
|
||||
imu.gx(), imu.gy(), imu.gz(),
|
||||
imu.gx(), imu.gy(), imu.gz(),
|
||||
imu.ax(), imu.ay(), imu.az());
|
||||
break;
|
||||
}
|
||||
|
@ -353,8 +353,8 @@ static void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint16_t pa
|
|||
|
||||
// see if we can send the deferred messages, if any
|
||||
while (q->num_deferred_messages != 0) {
|
||||
if (!mavlink_try_send_message(chan,
|
||||
q->deferred_messages[q->next_deferred_message],
|
||||
if (!mavlink_try_send_message(chan,
|
||||
q->deferred_messages[q->next_deferred_message],
|
||||
packet_drops)) {
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -77,6 +77,7 @@ public:
|
|||
k_param_frame_orientation,
|
||||
k_param_top_bottom_ratio,
|
||||
k_param_optflow_enabled,
|
||||
k_param_input_voltage,
|
||||
|
||||
//
|
||||
// 160: Navigation parameters
|
||||
|
@ -105,6 +106,7 @@ public:
|
|||
k_param_throttle_fs_value,
|
||||
k_param_throttle_cruise,
|
||||
k_param_esc_calibrate,
|
||||
k_param_radio_tuning,
|
||||
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
@ -231,9 +233,12 @@ public:
|
|||
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
||||
AP_Int8 compass_enabled;
|
||||
AP_Int8 esc_calibrate;
|
||||
AP_Int8 radio_tuning;
|
||||
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Float top_bottom_ratio;
|
||||
AP_Int8 optflow_enabled;
|
||||
AP_Float input_voltage;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Heli
|
||||
|
@ -296,6 +301,7 @@ public:
|
|||
pack_capacity (HIGH_DISCHARGE, k_param_pack_capacity, PSTR("BATT_CAPACITY")),
|
||||
compass_enabled (MAGNETOMETER, k_param_compass_enabled, PSTR("MAG_ENABLE")),
|
||||
optflow_enabled (OPTFLOW, k_param_optflow_enabled, PSTR("FLOW_ENABLE")),
|
||||
input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("IN_VOLT")),
|
||||
|
||||
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
|
||||
waypoint_total (0, k_param_waypoint_total, PSTR("WP_TOTAL")),
|
||||
|
@ -324,6 +330,7 @@ public:
|
|||
log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")),
|
||||
RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
|
||||
esc_calibrate (0, k_param_esc_calibrate, PSTR("ESC")),
|
||||
radio_tuning (0, k_param_radio_tuning, PSTR("TUNE")),
|
||||
frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")),
|
||||
top_bottom_ratio (TOP_BOTTOM_RATIO, k_param_top_bottom_ratio, PSTR("TB_RATIO")),
|
||||
|
||||
|
|
|
@ -1,5 +1,18 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
|
||||
/*static void init_auto()
|
||||
{
|
||||
//if (g.waypoint_index == g.waypoint_total) {
|
||||
// do_RTL();
|
||||
//}
|
||||
|
||||
// initialize commands
|
||||
// -------------------
|
||||
init_commands();
|
||||
}
|
||||
*/
|
||||
|
||||
static void init_commands()
|
||||
{
|
||||
// zero is home, but we always load the next command (1), in the code.
|
||||
|
@ -20,18 +33,6 @@ static void clear_command_queue(){
|
|||
next_command.id = NO_COMMAND;
|
||||
}
|
||||
|
||||
static void init_auto()
|
||||
{
|
||||
//if (g.waypoint_index == g.waypoint_total) {
|
||||
// Serial.println("ia_f");
|
||||
// do_RTL();
|
||||
//}
|
||||
|
||||
// initialize commands
|
||||
// -------------------
|
||||
init_commands();
|
||||
}
|
||||
|
||||
// Getters
|
||||
// -------
|
||||
static struct Location get_command_with_index(int i)
|
||||
|
@ -41,8 +42,6 @@ static struct Location get_command_with_index(int i)
|
|||
// Find out proper location in memory by using the start_byte position + the index
|
||||
// --------------------------------------------------------------------------------
|
||||
if (i > g.waypoint_total) {
|
||||
Serial.println("XCD");
|
||||
|
||||
// we do not have a valid command to load
|
||||
// return a WP with a "Blank" id
|
||||
temp.id = CMD_BLANK;
|
||||
|
@ -51,7 +50,6 @@ static struct Location get_command_with_index(int i)
|
|||
return temp;
|
||||
|
||||
}else{
|
||||
//Serial.println("LD");
|
||||
// we can load a command, we don't process it yet
|
||||
// read WP position
|
||||
long mem = (WP_START_BYTE) + (i * WP_SIZE);
|
||||
|
@ -75,10 +73,9 @@ static struct Location get_command_with_index(int i)
|
|||
}
|
||||
|
||||
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
|
||||
if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & WP_OPTION_ALT_RELATIVE){
|
||||
//if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & WP_OPTION_ALT_RELATIVE){
|
||||
//temp.alt += home.alt;
|
||||
}
|
||||
//Serial.println("ADD ALT");
|
||||
//}
|
||||
|
||||
if(temp.options & WP_OPTION_RELATIVE){
|
||||
// If were relative, just offset from home
|
||||
|
@ -190,7 +187,6 @@ static void set_next_WP(struct Location *wp)
|
|||
wp_totalDistance = get_distance(¤t_loc, &next_WP);
|
||||
wp_distance = wp_totalDistance;
|
||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
||||
nav_bearing = target_bearing;
|
||||
|
||||
// to check if we have missed the WP
|
||||
// ----------------------------
|
||||
|
@ -198,7 +194,7 @@ static void set_next_WP(struct Location *wp)
|
|||
|
||||
// set a new crosstrack bearing
|
||||
// ----------------------------
|
||||
crosstrack_bearing = target_bearing; // Used for track following
|
||||
//crosstrack_bearing = target_bearing; // Used for track following
|
||||
|
||||
gcs.print_current_waypoints();
|
||||
}
|
||||
|
@ -218,14 +214,12 @@ static void init_home()
|
|||
home.lng = g_gps->longitude; // Lon * 10**7
|
||||
home.lat = g_gps->latitude; // Lat * 10**7
|
||||
//home.alt = max(g_gps->altitude, 0); // we sometimes get negatives from GPS, not valid
|
||||
home.alt = 0; // this is a test
|
||||
home.alt = 0; // Home is always 0
|
||||
home_is_set = true;
|
||||
|
||||
// to point yaw towards home until we set it with Mavlink
|
||||
target_WP = home;
|
||||
|
||||
//Serial.printf_P(PSTR("gps alt: %ld\n"), home.alt);
|
||||
|
||||
// Save Home to EEPROM
|
||||
// -------------------
|
||||
// no need to save this to EPROM
|
||||
|
@ -234,8 +228,14 @@ static void init_home()
|
|||
|
||||
// Save prev loc this makes the calcs look better before commands are loaded
|
||||
prev_WP = home;
|
||||
|
||||
// this is dangerous since we can get GPS lock at any time.
|
||||
//next_WP = home;
|
||||
|
||||
// Load home for a default guided_WP
|
||||
// -------------
|
||||
guided_WP = home;
|
||||
guided_WP.alt += g.RTL_altitude;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -105,17 +105,14 @@ static void handle_process_now()
|
|||
|
||||
static void handle_no_commands()
|
||||
{
|
||||
// we don't want to RTL yet. Maybe this will change in the future. RTL is kinda dangerous.
|
||||
// use landing commands
|
||||
/*
|
||||
switch (control_mode){
|
||||
default:
|
||||
//set_mode(RTL);
|
||||
set_mode(RTL);
|
||||
break;
|
||||
}
|
||||
return;
|
||||
*/
|
||||
Serial.println("Handle No CMDs");
|
||||
}*/
|
||||
//return;
|
||||
//Serial.println("Handle No CMDs");
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
|
|
|
@ -345,7 +345,7 @@
|
|||
|
||||
// CIRCLE Mode
|
||||
#ifndef CIRCLE_YAW
|
||||
# define CIRCLE_YAW YAW_HOLD
|
||||
# define CIRCLE_YAW YAW_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RP
|
||||
|
@ -482,10 +482,10 @@
|
|||
# define NAV_P 2.0 // for 4.5 ms error = 13.5 pitch
|
||||
#endif
|
||||
#ifndef NAV_I
|
||||
# define NAV_I 0.1 // this
|
||||
# define NAV_I 0.12 // this
|
||||
#endif
|
||||
#ifndef NAV_IMAX
|
||||
# define NAV_IMAX 16 // degrees
|
||||
# define NAV_IMAX 20 // degrees
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
@ -513,7 +513,7 @@
|
|||
// Throttle control gains
|
||||
//
|
||||
#ifndef THROTTLE_P
|
||||
# define THROTTLE_P 0.35 //
|
||||
# define THROTTLE_P 0.6 //
|
||||
#endif
|
||||
#ifndef THROTTLE_I
|
||||
# define THROTTLE_I 0.10 // with 4m error, 12.5s windup
|
||||
|
@ -522,7 +522,7 @@
|
|||
//# define THROTTLE_D 0.6 // upped with filter
|
||||
//#endif
|
||||
#ifndef THROTTLE_IMAX
|
||||
# define THROTTLE_IMAX 150
|
||||
# define THROTTLE_IMAX 300
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -87,14 +87,6 @@
|
|||
// Note channels are from 0!
|
||||
//
|
||||
// XXX these should be CH_n defines from RC.h at some point.
|
||||
#define CH_1 0
|
||||
#define CH_2 1
|
||||
#define CH_3 2
|
||||
#define CH_4 3
|
||||
#define CH_5 4
|
||||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
#define CH_10 9 //PB5
|
||||
#define CH_11 10 //PE3
|
||||
|
||||
|
@ -138,13 +130,6 @@
|
|||
#define CIRCLE 8 // AUTO control
|
||||
#define NUM_MODES 9
|
||||
|
||||
// YAW debug
|
||||
// ---------
|
||||
#define YAW_HOLD 0
|
||||
#define YAW_BRAKE 1
|
||||
#define YAW_RATE 2
|
||||
|
||||
|
||||
// CH_6 Tuning
|
||||
// -----------
|
||||
#define CH6_NONE 0
|
||||
|
@ -152,20 +137,18 @@
|
|||
#define CH6_STABILIZE_KP 1
|
||||
#define CH6_STABILIZE_KI 2
|
||||
#define CH6_YAW_KP 3
|
||||
#define CH6_YAW_KD 4
|
||||
// Rate
|
||||
#define CH6_RATE_KP 5
|
||||
#define CH6_RATE_KI 6
|
||||
#define CH6_YAW_RATE_KP 7
|
||||
#define CH6_YAW_RATE_KD 8
|
||||
#define CH6_RATE_KP 4
|
||||
#define CH6_RATE_KI 5
|
||||
#define CH6_YAW_RATE_KP 6
|
||||
// Altitude
|
||||
#define CH6_THROTTLE_KP 9
|
||||
#define CH6_THROTTLE_KD 10
|
||||
#define CH6_THROTTLE_KP 7
|
||||
// Extras
|
||||
#define CH6_TOP_BOTTOM_RATIO 11
|
||||
#define CH6_PMAX 12
|
||||
#define CH6_RELAY 13
|
||||
#define CH6_TRAVERSE_SPEED 14
|
||||
#define CH6_TOP_BOTTOM_RATIO 8
|
||||
#define CH6_RELAY 9
|
||||
#define CH6_TRAVERSE_SPEED 10
|
||||
|
||||
#define CH6_NAV_P 11
|
||||
|
||||
// nav byte mask
|
||||
// -------------
|
||||
|
@ -322,8 +305,8 @@
|
|||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
||||
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
|
||||
#define CURRENT_AMPS(x) ((x*(INPUT_VOLTAGE/1024.0))-CURR_AMPS_OFFSET)*CURR_AMP_PER_VOLT
|
||||
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*VOLT_DIV_RATIO
|
||||
#define CURRENT_AMPS(x) ((x*(g.input_voltage/1024.0))-CURR_AMPS_OFFSET)*CURR_AMP_PER_VOLT
|
||||
//#define BARO_FILTER_SIZE 8
|
||||
|
||||
/* ************************************************************** */
|
||||
|
|
|
@ -34,8 +34,9 @@ static void arm_motors()
|
|||
// Tune down DCM
|
||||
// -------------------
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
dcm.kp_roll_pitch(0.030000);
|
||||
dcm.ki_roll_pitch(0.000006);
|
||||
dcm.kp_roll_pitch(0.030000);
|
||||
dcm.ki_roll_pitch(0.00001278), // 50 hz I term
|
||||
//dcm.ki_roll_pitch(0.000006);
|
||||
#endif
|
||||
|
||||
// tune down compass
|
||||
|
@ -95,8 +96,8 @@ static void arm_motors()
|
|||
// Tune down DCM
|
||||
// -------------------
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
dcm.kp_roll_pitch(0.12); // higher for quads
|
||||
dcm.ki_roll_pitch(0.00000319); // 1/4 of the normal rate for 200 hz loop
|
||||
dcm.kp_roll_pitch(0.12); // higher for fast recovery
|
||||
//dcm.ki_roll_pitch(0.00000319); // 1/4 of the normal rate for 200 hz loop
|
||||
#endif
|
||||
|
||||
// tune up compass
|
||||
|
|
|
@ -138,21 +138,21 @@ static void output_motor_test()
|
|||
// 31
|
||||
// 24
|
||||
if(g.rc_1.control_in > 3000){ // right
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_1.control_in < -3000){ // left
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in > 3000){ // back
|
||||
motor_out[CH_8] += 50;
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_8] += 100;
|
||||
motor_out[CH_4] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in < -3000){ // front
|
||||
motor_out[CH_7] += 50;
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_7] += 100;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
}else{
|
||||
|
@ -160,21 +160,21 @@ static void output_motor_test()
|
|||
// 2 1
|
||||
// 4
|
||||
if(g.rc_1.control_in > 3000){ // right
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_8] += 50;
|
||||
motor_out[CH_4] += 100;
|
||||
motor_out[CH_8] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_1.control_in < -3000){ // left
|
||||
motor_out[CH_7] += 50;
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_7] += 100;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in > 3000){ // back
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in < -3000){ // front
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -189,27 +189,27 @@ static void output_motor_test()
|
|||
|
||||
/*
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 50);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
}
|
||||
*/
|
||||
|
|
|
@ -182,37 +182,75 @@ static void output_motors_disarmed()
|
|||
|
||||
static void output_motor_test()
|
||||
{
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
if( g.frame_orientation == X_FRAME || g.frame_orientation == PLUS_FRAME )
|
||||
{
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 50);
|
||||
delay(1000);
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
if( g.frame_orientation == V_FRAME )
|
||||
{
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -149,8 +149,37 @@ static void output_motors_disarmed()
|
|||
|
||||
static void output_motor_test()
|
||||
{
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100);
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -139,23 +139,23 @@ static void output_motor_test()
|
|||
// 31
|
||||
// 24
|
||||
if(g.rc_1.control_in > 3000){
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
motor_out[CH_4] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_1.control_in < -3000){
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in > 3000){
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
motor_out[CH_4] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in < -3000){
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
}else{
|
||||
|
@ -163,16 +163,16 @@ static void output_motor_test()
|
|||
// 2 1
|
||||
// 4
|
||||
if(g.rc_1.control_in > 3000)
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
|
||||
if(g.rc_1.control_in < -3000)
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
|
||||
if(g.rc_2.control_in > 3000)
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_4] += 100;
|
||||
|
||||
if(g.rc_2.control_in < -3000)
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||
|
|
|
@ -96,15 +96,15 @@ static void output_motor_test()
|
|||
|
||||
|
||||
if(g.rc_1.control_in > 3000){ // right
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_1.control_in < -3000){ // left
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in > 3000){ // back
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_4] += 100;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||
|
|
|
@ -144,18 +144,18 @@ static void output_motor_test()
|
|||
|
||||
|
||||
if(g.rc_1.control_in > 3000){ // right
|
||||
motor_out[CH_1] += 50;
|
||||
motor_out[CH_7] += 50;
|
||||
motor_out[CH_1] += 100;
|
||||
motor_out[CH_7] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_1.control_in < -3000){ // left
|
||||
motor_out[CH_2] += 50;
|
||||
motor_out[CH_3] += 50;
|
||||
motor_out[CH_2] += 100;
|
||||
motor_out[CH_3] += 100;
|
||||
}
|
||||
|
||||
if(g.rc_2.control_in > 3000){ // back
|
||||
motor_out[CH_8] += 50;
|
||||
motor_out[CH_4] += 50;
|
||||
motor_out[CH_8] += 100;
|
||||
motor_out[CH_4] += 100;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||
|
|
|
@ -34,11 +34,12 @@ static void navigate()
|
|||
// nav_bearing will include xtrac correction
|
||||
// -----------------------------------------
|
||||
//xtrack_enabled = false;
|
||||
if(xtrack_enabled){
|
||||
nav_bearing = wrap_360(target_bearing + get_crosstrack_correction());
|
||||
}else{
|
||||
nav_bearing = target_bearing;
|
||||
}
|
||||
|
||||
//if(xtrack_enabled){
|
||||
// crosstrack_correction = get_crosstrack_correction();
|
||||
//}else {
|
||||
// crosstrack_correction = 0;
|
||||
//}
|
||||
}
|
||||
|
||||
static bool check_missed_wp()
|
||||
|
@ -101,18 +102,20 @@ static void calc_nav_rate(int x_error, int y_error, int max_speed, int min_speed
|
|||
}
|
||||
|
||||
// find the rates:
|
||||
float temp = radians((float)g_gps->ground_course/100.0);
|
||||
|
||||
// calc the cos of the error to tell how fast we are moving towards the target in cm
|
||||
y_actual_speed = (float)g_gps->ground_speed * cos(radians((float)g_gps->ground_course/100.0));
|
||||
y_actual_speed = (float)g_gps->ground_speed * cos(temp);
|
||||
y_rate_error = y_target_speed - y_actual_speed; // 413
|
||||
y_rate_error = constrain(y_rate_error, -250, 250); // added a rate error limit to keep pitching down to a minimum
|
||||
y_rate_error = constrain(y_rate_error, -600, 600); // added a rate error limit to keep pitching down to a minimum
|
||||
nav_lat = constrain(g.pi_nav_lat.get_pi(y_rate_error, dTnav), -3500, 3500);
|
||||
|
||||
//Serial.printf("yr: %d, nav_lat: %d, int:%d \n",y_rate_error, nav_lat, g.pi_nav_lat.get_integrator());
|
||||
|
||||
// calc the sin of the error to tell how fast we are moving laterally to the target in cm
|
||||
x_actual_speed = (float)g_gps->ground_speed * sin(radians((float)g_gps->ground_course/100.0));
|
||||
x_actual_speed = (float)g_gps->ground_speed * sin(temp);
|
||||
x_rate_error = x_target_speed - x_actual_speed;
|
||||
x_rate_error = constrain(x_rate_error, -250, 250);
|
||||
x_rate_error = constrain(x_rate_error, -600, 600);
|
||||
nav_lon = constrain(g.pi_nav_lon.get_pi(x_rate_error, dTnav), -3500, 3500);
|
||||
}
|
||||
|
||||
|
@ -128,11 +131,11 @@ static void calc_nav_pitch_roll()
|
|||
}
|
||||
|
||||
// ------------------------------
|
||||
static void calc_bearing_error()
|
||||
/*static void calc_bearing_error()
|
||||
{
|
||||
bearing_error = nav_bearing - dcm.yaw_sensor;
|
||||
bearing_error = wrap_180(bearing_error);
|
||||
}
|
||||
}*/
|
||||
|
||||
static long get_altitude_error()
|
||||
{
|
||||
|
@ -189,6 +192,7 @@ static long wrap_180(long error)
|
|||
return error;
|
||||
}
|
||||
|
||||
/*
|
||||
static long get_crosstrack_correction(void)
|
||||
{
|
||||
// Crosstrack Error
|
||||
|
@ -206,19 +210,20 @@ static long get_crosstrack_correction(void)
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
*/
|
||||
/*
|
||||
static long cross_track_test()
|
||||
{
|
||||
long temp = wrap_180(target_bearing - crosstrack_bearing);
|
||||
return abs(temp);
|
||||
}
|
||||
|
||||
*/
|
||||
/*
|
||||
static void reset_crosstrack()
|
||||
{
|
||||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
||||
}
|
||||
|
||||
*/
|
||||
static long get_altitude_above_home(void)
|
||||
{
|
||||
// This is the altitude above the home location
|
||||
|
|
|
@ -35,30 +35,6 @@ static void init_rc_in()
|
|||
g.rc_7.set_range(0,1000);
|
||||
g.rc_8.set_range(0,1000);
|
||||
|
||||
#if CHANNEL_6_TUNING == CH6_RATE_KP
|
||||
g.rc_6.set_range(0,300); // 0 t0 .3
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_RATE_KI
|
||||
g.rc_6.set_range(0,300); // 0 t0 .3
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_STABILIZE_KP
|
||||
g.rc_6.set_range(0,8000); // 0 t0 .3
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_STABILIZE_KI
|
||||
g.rc_6.set_range(0,300); // 0 t0 .3
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KP
|
||||
g.rc_6.set_range(0,800); // 0 to .8
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KD
|
||||
g.rc_6.set_range(0,500); // 0 to .5
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_TOP_BOTTOM_RATIO
|
||||
g.rc_6.set_range(800,1000); // .8 to 1
|
||||
|
||||
/* #elif CHANNEL_6_TUNING == CH6_RELAY
|
||||
g.rc_6.set_range(0,1000); // 0 to 1 */
|
||||
#endif
|
||||
}
|
||||
|
||||
static void init_rc_out()
|
||||
|
|
|
@ -13,6 +13,7 @@ static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv);
|
|||
static int8_t setup_batt_monitor (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_sonar (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_tune (uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t setup_mag_offset (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_esc (uint8_t argc, const Menu::arg *argv);
|
||||
|
@ -41,6 +42,7 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
|
|||
{"battery", setup_batt_monitor},
|
||||
{"sonar", setup_sonar},
|
||||
{"compass", setup_compass},
|
||||
{"tune", setup_tune},
|
||||
// {"offsets", setup_mag_offset},
|
||||
{"declination", setup_declination},
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
|
@ -354,6 +356,15 @@ setup_declination(uint8_t argc, const Menu::arg *argv)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int8_t
|
||||
setup_tune(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
g.radio_tuning.set_and_save(argv[1].i);
|
||||
report_tuning();
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
static int8_t
|
||||
setup_erase(uint8_t argc, const Menu::arg *argv)
|
||||
|
@ -1131,3 +1142,15 @@ static void report_version()
|
|||
print_blanks(2);
|
||||
}
|
||||
|
||||
|
||||
static void report_tuning()
|
||||
{
|
||||
Serial.printf_P(PSTR("\nTUNE:\n"));
|
||||
print_divider();
|
||||
if (g.radio_tuning == 0){
|
||||
print_enabled(g.radio_tuning.get());
|
||||
}else{
|
||||
Serial.printf_P(PSTR(" %d\n"),(int)g.radio_tuning.get());
|
||||
}
|
||||
print_blanks(2);
|
||||
}
|
||||
|
|
|
@ -41,7 +41,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
|
|||
};
|
||||
|
||||
// Create the top-level menu object.
|
||||
MENU(main_menu, "ArduCopter 2.0.40 Beta", main_menu_commands);
|
||||
MENU(main_menu, "ArduCopter 2.0.43 Beta", main_menu_commands);
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
|
@ -362,7 +362,7 @@ static void set_mode(byte mode)
|
|||
led_mode = NORMAL_LEDS;
|
||||
|
||||
// most modes do not calculate crosstrack correction
|
||||
xtrack_enabled = false;
|
||||
//xtrack_enabled = false;
|
||||
reset_nav_I();
|
||||
|
||||
switch(control_mode)
|
||||
|
@ -407,11 +407,12 @@ static void set_mode(byte mode)
|
|||
init_throttle_cruise();
|
||||
|
||||
// loads the commands from where we left off
|
||||
init_auto();
|
||||
//init_auto();
|
||||
init_commands();
|
||||
|
||||
// do crosstrack correction
|
||||
// XXX move to flight commands
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
break;
|
||||
|
||||
case CIRCLE:
|
||||
|
@ -437,9 +438,10 @@ static void set_mode(byte mode)
|
|||
roll_pitch_mode = ROLL_PITCH_AUTO;
|
||||
throttle_mode = THROTTLE_AUTO;
|
||||
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
init_throttle_cruise();
|
||||
next_WP = current_loc;
|
||||
set_next_WP(&guided_WP);
|
||||
break;
|
||||
|
||||
case RTL:
|
||||
|
@ -447,7 +449,7 @@ static void set_mode(byte mode)
|
|||
roll_pitch_mode = RTL_RP;
|
||||
throttle_mode = RTL_THR;
|
||||
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
init_throttle_cruise();
|
||||
do_RTL();
|
||||
break;
|
||||
|
|
|
@ -447,7 +447,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
|||
accels.x, accels.y, accels.z,
|
||||
gyros.x, gyros.y, gyros.z);
|
||||
*/
|
||||
///*
|
||||
/*
|
||||
Serial.printf_P(PSTR("cp: %1.2f, sp: %1.2f, cr: %1.2f, sr: %1.2f, cy: %1.2f, sy: %1.2f,\n"),
|
||||
cos_pitch_x,
|
||||
sin_pitch_y,
|
||||
|
@ -636,59 +636,8 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
|
|||
while(1){
|
||||
delay(200);
|
||||
read_radio();
|
||||
|
||||
//Outer Loop : Attitude
|
||||
#if CHANNEL_6_TUNING == CH6_NONE
|
||||
Serial.printf_P(PSTR("disabled\n"));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_STABILIZE_KP
|
||||
Serial.printf_P(PSTR("stab kP: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_STABILIZE_KI
|
||||
Serial.printf_P(PSTR("stab kI: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_KP
|
||||
Serial.printf_P(PSTR("yaw Hold kP: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0)); // range from 0 ~ 5.0
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_KI
|
||||
Serial.printf_P(PSTR("yaw Hold kI: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
//Inner Loop : Rate
|
||||
#elif CHANNEL_6_TUNING == CH6_RATE_KP
|
||||
Serial.printf_P(PSTR("rate kD: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_RATE_KI
|
||||
Serial.printf_P(PSTR("rate kI: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_RATE_KP
|
||||
Serial.printf_P(PSTR("yaw rate kP: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_YAW_RATE_KI
|
||||
Serial.printf_P(PSTR("yaw rate kI: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
|
||||
//Altitude Hold
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KP
|
||||
Serial.printf_P(PSTR("throttle kP: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_THROTTLE_KD
|
||||
Serial.printf_P(PSTR("baro kD: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_TRAVERSE_SPEED
|
||||
Serial.printf_P(PSTR("traverse: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
|
||||
//Extras
|
||||
#elif CHANNEL_6_TUNING == CH6_TOP_BOTTOM_RATIO
|
||||
Serial.printf_P(PSTR("Y6: %1.3f\n"), ((float)g.rc_6.control_in / 1000.0));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_PMAX
|
||||
Serial.printf_P(PSTR("Y6: %d\n"), (g.rc_6.control_in * 2));
|
||||
|
||||
#elif CHANNEL_6_TUNING == CH6_RELAY
|
||||
Serial.printf_P(PSTR(" %d\n"), (g.rc_6.control_in ));
|
||||
|
||||
#endif
|
||||
tuning();
|
||||
Serial.printf_P(PSTR("tune: %1.3f\n"), tuning_value);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
|
@ -1009,10 +958,12 @@ test_mission(uint8_t argc, const Menu::arg *argv)
|
|||
return (0);
|
||||
}
|
||||
*/
|
||||
|
||||
static void print_hit_enter()
|
||||
{
|
||||
Serial.printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
}
|
||||
|
||||
/*
|
||||
static void fake_out_gps()
|
||||
{
|
||||
|
|
|
@ -1,5 +1,4 @@
|
|||
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// This file is just a placeholder for your configuration file. If you wish to change any of the setup parameters from
|
||||
// their default values, place the appropriate #define statements here.
|
||||
|
|
|
@ -304,19 +304,6 @@
|
|||
//#define FLIGHT_MODE_6 MANUAL
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RC_5_FUNCT OPTIONAL
|
||||
// RC_6_FUNCT OPTIONAL
|
||||
// RC_7_FUNCT OPTIONAL
|
||||
// RC_8_FUNCT OPTIONAL
|
||||
//
|
||||
// The channel 5 through 8 function assignments allow configuration of those
|
||||
// channels for use with differential ailerons, flaps, flaperons, or camera
|
||||
// or intrument mounts
|
||||
//
|
||||
//#define RC_5_FUNCT RC_5_FUNCT_NONE
|
||||
//etc.
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// For automatic flap operation based on speed setpoint. If the speed setpoint is above flap_1_speed
|
||||
// then the flap position shall be 0%. If the speed setpoint is between flap_1_speed and flap_2_speed
|
||||
|
@ -411,9 +398,9 @@
|
|||
// also means that you should avoid switching out of MANUAL while you have
|
||||
// any control stick deflection.
|
||||
//
|
||||
// The default is to enable AUTO_TRIM.
|
||||
// The default is to disable AUTO_TRIM.
|
||||
//
|
||||
//#define AUTO_TRIM ENABLED
|
||||
//#define AUTO_TRIM DISABLED
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -415,6 +415,7 @@ static unsigned long nav_loopTimer; // used to track the elapsed time for GP
|
|||
static unsigned long dTnav; // Delta Time in milliseconds for navigation computations
|
||||
static float load; // % MCU cycles used
|
||||
|
||||
RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Top-level logic
|
||||
|
@ -710,6 +711,8 @@ static void slow_loop()
|
|||
// ----------------------------------
|
||||
update_servo_switches();
|
||||
|
||||
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
|
||||
|
||||
break;
|
||||
|
||||
case 2:
|
||||
|
|
|
@ -61,7 +61,7 @@ static void stabilize()
|
|||
|
||||
// Mix Stick input to allow users to override control surfaces
|
||||
// -----------------------------------------------------------
|
||||
if ((control_mode < FLY_BY_WIRE_A) || (ENABLE_STICK_MIXING == 1 && control_mode > FLY_BY_WIRE_B)) {
|
||||
if ((control_mode < FLY_BY_WIRE_A) || (ENABLE_STICK_MIXING == 1 && control_mode > FLY_BY_WIRE_B && failsafe == FAILSAFE_NONE)) {
|
||||
|
||||
|
||||
// TODO: use RC_Channel control_mix function?
|
||||
|
@ -92,7 +92,7 @@ static void stabilize()
|
|||
// stick mixing performed for rudder for all cases including FBW unless disabled for higher modes
|
||||
// important for steering on the ground during landing
|
||||
// -----------------------------------------------
|
||||
if (control_mode <= FLY_BY_WIRE_B || ENABLE_STICK_MIXING == 1) {
|
||||
if (control_mode <= FLY_BY_WIRE_B || (ENABLE_STICK_MIXING == 1 && failsafe == FAILSAFE_NONE)) {
|
||||
ch4_inf = (float)g.channel_rudder.radio_in - (float)g.channel_rudder.radio_trim;
|
||||
ch4_inf = fabs(ch4_inf);
|
||||
ch4_inf = min(ch4_inf, 400.0);
|
||||
|
@ -274,21 +274,16 @@ static void set_servos(void)
|
|||
}
|
||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||
g.channel_rudder.radio_out = g.channel_rudder.radio_in;
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) g.rc_5.radio_out = g.rc_5.radio_in;
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) g.rc_6.radio_out = g.rc_6.radio_in;
|
||||
G_RC_AUX(k_aileron)->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;
|
||||
|
||||
} else {
|
||||
if (g.mix_mode == 0) {
|
||||
g.channel_roll.calc_pwm();
|
||||
g.channel_pitch.calc_pwm();
|
||||
g.channel_rudder.calc_pwm();
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) {
|
||||
g.rc_5.servo_out = g.channel_roll.servo_out;
|
||||
g.rc_5.calc_pwm();
|
||||
}
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) {
|
||||
g.rc_6.servo_out = g.channel_roll.servo_out;
|
||||
g.rc_6.calc_pwm();
|
||||
if (g_rc_function[RC_Channel_aux::k_aileron]) {
|
||||
g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out;
|
||||
g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm();
|
||||
}
|
||||
|
||||
}else{
|
||||
|
@ -320,8 +315,7 @@ static void set_servos(void)
|
|||
}
|
||||
|
||||
if(control_mode <= FLY_BY_WIRE_B) {
|
||||
if (g.rc_5_funct == RC_5_FUNCT_FLAP_AUTO) g.rc_5.radio_out = g.rc_5.radio_in;
|
||||
if (g.rc_6_funct == RC_6_FUNCT_FLAP_AUTO) g.rc_6.radio_out = g.rc_6.radio_in;
|
||||
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in;
|
||||
} else if (control_mode >= FLY_BY_WIRE_C) {
|
||||
if (g.airspeed_enabled == true) {
|
||||
flapSpeedSource = g.airspeed_cruise;
|
||||
|
@ -329,14 +323,11 @@ static void set_servos(void)
|
|||
flapSpeedSource = g.throttle_cruise;
|
||||
}
|
||||
if ( flapSpeedSource > g.flap_1_speed) {
|
||||
if(g.rc_5_funct == RC_5_FUNCT_FLAP_AUTO) g.rc_5.servo_out = 0;
|
||||
if(g.rc_6_funct == RC_6_FUNCT_FLAP_AUTO) g.rc_6.servo_out = 0;
|
||||
G_RC_AUX(k_flap_auto)->servo_out = 0;
|
||||
} else if (flapSpeedSource > g.flap_2_speed) {
|
||||
if(g.rc_5_funct == RC_5_FUNCT_FLAP_AUTO) g.rc_5.servo_out = g.flap_1_percent;
|
||||
if(g.rc_6_funct == RC_6_FUNCT_FLAP_AUTO) g.rc_6.servo_out = g.flap_1_percent;
|
||||
G_RC_AUX(k_flap_auto)->servo_out = g.flap_1_percent;
|
||||
} else {
|
||||
if(g.rc_5_funct == RC_5_FUNCT_FLAP_AUTO) g.rc_5.servo_out = g.flap_2_percent;
|
||||
if(g.rc_6_funct == RC_6_FUNCT_FLAP_AUTO) g.rc_6.servo_out = g.flap_2_percent;
|
||||
G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -347,8 +338,11 @@ static void set_servos(void)
|
|||
APM_RC.OutputCh(CH_2, g.channel_pitch.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_3, g.channel_throttle.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_4, g.channel_rudder.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_5, g.rc_5.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_6, g.rc_6.radio_out); // send to Servos
|
||||
// Route configurable aux. functions to their respective servos
|
||||
g.rc_5.output_ch(CH_5);
|
||||
g.rc_6.output_ch(CH_6);
|
||||
g.rc_7.output_ch(CH_7);
|
||||
g.rc_8.output_ch(CH_8);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -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 = 11;
|
||||
static const uint16_t k_format_version = 12;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
|
@ -134,11 +134,6 @@ public:
|
|||
k_param_long_fs_action,
|
||||
k_param_gcs_heartbeat_fs_enabled,
|
||||
k_param_throttle_slewrate,
|
||||
|
||||
k_param_rc_5_funct,
|
||||
k_param_rc_6_funct,
|
||||
k_param_rc_7_funct,
|
||||
k_param_rc_8_funct,
|
||||
|
||||
//
|
||||
// 200: Feed-forward gains
|
||||
|
@ -327,14 +322,10 @@ public:
|
|||
RC_Channel channel_pitch;
|
||||
RC_Channel channel_throttle;
|
||||
RC_Channel channel_rudder;
|
||||
RC_Channel rc_5;
|
||||
RC_Channel rc_6;
|
||||
RC_Channel rc_7;
|
||||
RC_Channel rc_8;
|
||||
AP_Int8 rc_5_funct;
|
||||
AP_Int8 rc_6_funct;
|
||||
AP_Int8 rc_7_funct;
|
||||
AP_Int8 rc_8_funct;
|
||||
RC_Channel_aux rc_5;
|
||||
RC_Channel_aux rc_6;
|
||||
RC_Channel_aux rc_7;
|
||||
RC_Channel_aux rc_8;
|
||||
|
||||
// PID controllers
|
||||
//
|
||||
|
@ -428,10 +419,6 @@ public:
|
|||
inverted_flight_ch (0, k_param_inverted_flight_ch, PSTR("INVERTEDFLT_CH")),
|
||||
sonar_enabled (SONAR_ENABLED, k_param_sonar_enabled, PSTR("SONAR_ENABLE")),
|
||||
airspeed_enabled (AIRSPEED_SENSOR, k_param_airspeed_enabled, PSTR("ARSPD_ENABLE")),
|
||||
rc_5_funct (RC_5_FUNCT, k_param_rc_5_funct, PSTR("RC5_FUNCT")),
|
||||
rc_6_funct (RC_6_FUNCT, k_param_rc_6_funct, PSTR("RC6_FUNCT")),
|
||||
rc_7_funct (RC_7_FUNCT, k_param_rc_7_funct, PSTR("RC7_FUNCT")),
|
||||
rc_8_funct (RC_8_FUNCT, k_param_rc_8_funct, PSTR("RC8_FUNCT")),
|
||||
|
||||
// Note - total parameter name length must be less than 14 characters for MAVLink compatibility!
|
||||
|
||||
|
|
|
@ -226,19 +226,6 @@
|
|||
# define CH8_MAX 2000
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
#ifndef RC_5_FUNCT
|
||||
# define RC_5_FUNCT RC_5_FUNCT_NONE
|
||||
#endif
|
||||
#ifndef RC_6_FUNCT
|
||||
# define RC_6_FUNCT RC_6_FUNCT_NONE
|
||||
#endif
|
||||
#ifndef RC_7_FUNCT
|
||||
# define RC_7_FUNCT RC_7_FUNCT_NONE
|
||||
#endif
|
||||
#ifndef RC_8_FUNCT
|
||||
# define RC_8_FUNCT RC_8_FUNCT_NONE
|
||||
#endif
|
||||
|
||||
#ifndef FLAP_1_PERCENT
|
||||
# define FLAP_1_PERCENT 0
|
||||
|
@ -313,7 +300,7 @@
|
|||
// AUTO_TRIM
|
||||
//
|
||||
#ifndef AUTO_TRIM
|
||||
# define AUTO_TRIM ENABLED
|
||||
# define AUTO_TRIM DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -41,39 +41,12 @@
|
|||
#define GPS_PROTOCOL_MTK16 6
|
||||
#define GPS_PROTOCOL_AUTO 7
|
||||
|
||||
// Radio channels
|
||||
// Note channels are from 0!
|
||||
//
|
||||
// XXX these should be CH_n defines from RC.h at some point.
|
||||
#define CH_1 0
|
||||
#define CH_2 1
|
||||
#define CH_3 2
|
||||
#define CH_4 3
|
||||
#define CH_5 4
|
||||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
|
||||
#define CH_ROLL CH_1
|
||||
#define CH_PITCH CH_2
|
||||
#define CH_THROTTLE CH_3
|
||||
#define CH_RUDDER CH_4
|
||||
#define CH_YAW CH_4
|
||||
|
||||
#define RC_5_FUNCT_NONE 0
|
||||
#define RC_5_FUNCT_AILERON 1
|
||||
#define RC_5_FUNCT_FLAP_AUTO 2
|
||||
#define RC_5_FUNCT_FLAPERON 3
|
||||
|
||||
#define RC_6_FUNCT_NONE 0
|
||||
#define RC_6_FUNCT_AILERON 1
|
||||
#define RC_6_FUNCT_FLAP_AUTO 2
|
||||
#define RC_6_FUNCT_FLAPERON 3
|
||||
|
||||
#define RC_7_FUNCT_NONE 0
|
||||
|
||||
#define RC_8_FUNCT_NONE 0
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_PROTOCOL_XPLANE 1
|
||||
#define HIL_PROTOCOL_MAVLINK 2
|
||||
|
|
|
@ -43,12 +43,12 @@ static void failsafe_long_on_event()
|
|||
case STABILIZE:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
case CIRCLE:
|
||||
set_mode(RTL);
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
case LOITER:
|
||||
case CIRCLE:
|
||||
if(g.long_fs_action == 1) {
|
||||
set_mode(RTL);
|
||||
}
|
||||
|
|
|
@ -23,24 +23,7 @@ static void init_rc_in()
|
|||
g.channel_throttle.dead_zone = 6;
|
||||
|
||||
//set auxiliary ranges
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) {
|
||||
g.rc_5.set_angle(SERVO_MAX);
|
||||
} else if (g.rc_5_funct == RC_5_FUNCT_FLAP_AUTO || g.rc_5_funct == RC_5_FUNCT_FLAPERON) {
|
||||
g.rc_5.set_range(0,100);
|
||||
} else {
|
||||
g.rc_5.set_range(0,1000); // Insert proper init for camera mount, etc., here
|
||||
}
|
||||
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) {
|
||||
g.rc_6.set_angle(SERVO_MAX);
|
||||
} else if (g.rc_6_funct == RC_6_FUNCT_FLAP_AUTO || g.rc_6_funct == RC_6_FUNCT_FLAPERON) {
|
||||
g.rc_6.set_range(0,100);
|
||||
} else {
|
||||
g.rc_6.set_range(0,1000); // Insert proper init for camera mount, etc., here
|
||||
}
|
||||
|
||||
g.rc_7.set_range(0,1000); // Insert proper init for camera mount, etc., here
|
||||
g.rc_8.set_range(0,1000);
|
||||
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
|
||||
}
|
||||
|
||||
static void init_rc_out()
|
||||
|
@ -53,7 +36,7 @@ static void init_rc_out()
|
|||
APM_RC.OutputCh(CH_5, g.rc_5.radio_trim);
|
||||
APM_RC.OutputCh(CH_6, g.rc_6.radio_trim);
|
||||
APM_RC.OutputCh(CH_7, g.rc_7.radio_trim);
|
||||
APM_RC.OutputCh(CH_8, g.rc_8.radio_trim);
|
||||
APM_RC.OutputCh(CH_8, g.rc_8.radio_trim);
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
|
@ -173,8 +156,7 @@ static void trim_control_surfaces()
|
|||
g.channel_roll.radio_trim = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) g.rc_5.radio_trim = g.rc_5.radio_in; // Second aileron channel
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) g.rc_6.radio_trim = g.rc_6.radio_in; // Second aileron channel
|
||||
G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel
|
||||
|
||||
}else{
|
||||
elevon1_trim = ch1_temp;
|
||||
|
@ -191,8 +173,7 @@ static void trim_control_surfaces()
|
|||
g.channel_pitch.save_eeprom();
|
||||
g.channel_throttle.save_eeprom();
|
||||
g.channel_rudder.save_eeprom();
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) g.rc_5.save_eeprom();
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) g.rc_6.save_eeprom();
|
||||
G_RC_AUX(k_aileron)->save_eeprom();
|
||||
}
|
||||
|
||||
static void trim_radio()
|
||||
|
@ -208,8 +189,7 @@ static void trim_radio()
|
|||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
//g.channel_throttle.radio_trim = g.channel_throttle.radio_in;
|
||||
g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) g.rc_5.radio_trim = g.rc_5.radio_in; // Second aileron channel
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) g.rc_6.radio_trim = g.rc_6.radio_in; // Second aileron channel
|
||||
G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel
|
||||
|
||||
} else {
|
||||
elevon1_trim = ch1_temp;
|
||||
|
@ -225,7 +205,5 @@ static void trim_radio()
|
|||
g.channel_pitch.save_eeprom();
|
||||
//g.channel_throttle.save_eeprom();
|
||||
g.channel_rudder.save_eeprom();
|
||||
if (g.rc_5_funct == RC_5_FUNCT_AILERON) g.rc_5.save_eeprom();
|
||||
if (g.rc_6_funct == RC_6_FUNCT_AILERON) g.rc_6.save_eeprom();
|
||||
G_RC_AUX(k_aileron)->save_eeprom();
|
||||
}
|
||||
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -586,27 +591,28 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
000001fc t setup_motors(unsigned char, Menu::arg const*)
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00002000 T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001fa2 T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -586,27 +591,28 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
000001fc t setup_motors(unsigned char, Menu::arg const*)
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001ffe T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001fa0 T loop
|
||||
|
|
|
@ -3,7 +3,9 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde: In function 'void read_AHRS()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1301: error: 'class AP_DCM_HIL' has no member named 'update_DCM_fast'
|
||||
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
|
||||
|
@ -34,8 +36,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
|
@ -49,169 +51,19 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:353: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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:354: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:374: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:379: warning: 'baro_alt' 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/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:24: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.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/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
|
||||
%% 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/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.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
|
||||
make: *** [/tmp/ArduCopter.build/ArduCopter.o] Error 1
|
||||
|
|
|
@ -1,600 +0,0 @@
|
|||
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 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 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
|
||||
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 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 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 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)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
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 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
|
||||
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
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
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 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b circle_angle
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
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 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 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 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 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
|
||||
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
|
||||
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 Log_Read_Mode()::__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 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 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 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 W AP_IMU_Shim::update()
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r 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 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__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 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 r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(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
|
||||
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 omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__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_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 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_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 print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
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 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
|
||||
00000012 B adc
|
||||
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 t startup_ground()
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__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 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000017 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 GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__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
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
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
|
||||
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
|
||||
00000028 B imu
|
||||
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 print_divider()
|
||||
0000002e t send_rate(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
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
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 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 verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, 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
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
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()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
0000005a t read_control_switch()
|
||||
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()
|
||||
00000060 t _mavlink_send_uart
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(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()
|
||||
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*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a0 t Log_Read_Mode()
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ab B compass
|
||||
000000ae t report_frame()
|
||||
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*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
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 test_tri(unsigned char, Menu::arg const*)
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(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()
|
||||
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
|
||||
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*)
|
||||
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()
|
||||
00000126 t arm_motors()
|
||||
00000128 t get_command_with_index(int)
|
||||
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()
|
||||
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()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000029e t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000568 t __static_initialization_and_destruction_0(int, int)
|
||||
000005ea T update_roll_pitch_mode()
|
||||
00000616 t init_ardupilot()
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
0000194a T loop
|
|
@ -3,7 +3,9 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde: In function 'void read_AHRS()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1301: error: 'class AP_DCM_HIL' has no member named 'update_DCM_fast'
|
||||
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
|
||||
|
@ -34,8 +36,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
|
@ -49,169 +51,19 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:353: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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:354: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:374: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:379: warning: 'baro_alt' 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/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:24: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.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/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
|
||||
%% 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/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.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
|
||||
make: *** [/tmp/ArduCopter.build/ArduCopter.o] Error 1
|
||||
|
|
|
@ -1,600 +0,0 @@
|
|||
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 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 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
|
||||
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 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 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 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)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
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 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
|
||||
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
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
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 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b circle_angle
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
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 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 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 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 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
|
||||
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
|
||||
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 Log_Read_Mode()::__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 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 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 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 W AP_IMU_Shim::update()
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r 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 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__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 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 r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(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
|
||||
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 omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__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_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 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_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 print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
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 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
|
||||
00000012 B adc
|
||||
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 t startup_ground()
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__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 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000017 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 GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__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
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
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
|
||||
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
|
||||
00000028 B imu
|
||||
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 print_divider()
|
||||
0000002e t send_rate(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
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
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 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 verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, 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
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 t report_version()
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
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()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
0000005a t read_control_switch()
|
||||
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()
|
||||
00000060 t print_switch(unsigned char, unsigned char)
|
||||
00000060 t _mavlink_send_uart
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(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()
|
||||
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 init_compass()
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Read_Mode()
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ab B compass
|
||||
000000ae t report_frame()
|
||||
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*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
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 test_tri(unsigned char, Menu::arg const*)
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(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()
|
||||
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
|
||||
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*)
|
||||
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()
|
||||
00000126 t arm_motors()
|
||||
00000128 t get_command_with_index(int)
|
||||
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()
|
||||
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()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
00000200 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000029e t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000568 t __static_initialization_and_destruction_0(int, int)
|
||||
000005ea T update_roll_pitch_mode()
|
||||
00000616 t init_ardupilot()
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001948 T loop
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001ece T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001e70 T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001ecc T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001e6e T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,13 +554,13 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t setup_motors(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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001e2e T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001dd0 T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,13 +554,13 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t setup_motors(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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001e2c T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001dce T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r report_frame()::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001f0e T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001eb0 T loop
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: warning: 'void tuning()' defined but not used
|
||||
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
|
||||
|
@ -31,8 +30,8 @@ autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'sta
|
|||
/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:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:212: warning: 'void trim_yaw()' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
|
@ -44,14 +43,14 @@ autogenerated:287: warning: 'void report_gyro()' declared 'static' but never def
|
|||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' 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: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
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -134,7 +134,6 @@
|
|||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
|
@ -166,6 +165,7 @@
|
|||
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
|
||||
|
@ -173,6 +173,7 @@
|
|||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__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
|
||||
|
@ -186,6 +187,7 @@
|
|||
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
|
||||
|
@ -222,6 +224,7 @@
|
|||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_tuning()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
|
@ -230,6 +233,7 @@
|
|||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
|
@ -256,7 +260,6 @@
|
|||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r report_frame()::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
|
@ -284,6 +287,7 @@
|
|||
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
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
|
@ -384,6 +388,7 @@
|
|||
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 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
|
@ -464,7 +469,6 @@
|
|||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
|
@ -485,7 +489,6 @@
|
|||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
|
@ -517,6 +520,8 @@
|
|||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
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)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
|
@ -549,12 +554,12 @@
|
|||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
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 r setup_menu_commands
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
|
@ -587,26 +592,27 @@
|
|||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
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()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000202 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
000002ea t tuning()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003be t read_battery()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000007a8 t __static_initialization_and_destruction_0(int, int)
|
||||
000007dc b g
|
||||
0000083c W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001f0c T loop
|
||||
000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001eae T loop
|
||||
|
|
|
@ -58,7 +58,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
|
||||
<name>ArduCopter 2.0.40 Beta Quad</name>
|
||||
<name>ArduCopter 2.0.42 Beta Quad</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -69,7 +69,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
|
||||
<name>ArduCopter 2.0.40 Beta Tri</name>
|
||||
<name>ArduCopter 2.0.42 Beta Tri</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG TRI_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -80,7 +80,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
|
||||
<name>ArduCopter 2.0.40 Beta Hexa</name>
|
||||
<name>ArduCopter 2.0.42 Beta Hexa</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG HEXA_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -91,7 +91,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
|
||||
<name>ArduCopter 2.0.40 Beta Y6</name>
|
||||
<name>ArduCopter 2.0.42 Beta Y6</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG Y6_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -102,7 +102,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 2.0.40 Beta Heli (2560 only)</name>
|
||||
<name>ArduCopter 2.0.42 Beta Heli (2560 only)</name>
|
||||
<desc>
|
||||
#define AUTO_RESET_LOITER 0
|
||||
#define FRAME_CONFIG HELI_FRAME
|
||||
|
@ -149,7 +149,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
|
||||
<name>ArduCopter 2.0.40 Beta Quad Hil</name>
|
||||
<name>ArduCopter 2.0.42 Beta Quad Hil</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION PLUS_FRAME
|
||||
|
|
|
@ -1 +1,6 @@
|
|||
Already up-to-date.
|
||||
From https://code.google.com/p/ardupilot-mega
|
||||
a543a5c..fe617ae master -> origin/master
|
||||
Updating a543a5c..fe617ae
|
||||
Fast-forward
|
||||
ArduCopter/config.h | 2 +-
|
||||
1 files changed, 1 insertions(+), 1 deletions(-)
|
||||
|
|
|
@ -5,6 +5,17 @@
|
|||
#define MIN_PULSEWIDTH 900
|
||||
#define MAX_PULSEWIDTH 2100
|
||||
|
||||
// Radio channels
|
||||
// Note channels are from 0!
|
||||
#define CH_1 0
|
||||
#define CH_2 1
|
||||
#define CH_3 2
|
||||
#define CH_4 3
|
||||
#define CH_5 4
|
||||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
class APM_RC_Class
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
#define ADC_DATAIN 50 // MISO
|
||||
#define ADC_SPICLOCK 52 // SCK
|
||||
#define ADC_CHIP_SELECT 33 // PC4 9 // PH6 Puerto:0x08 Bit mask : 0x40
|
||||
#define ADC_FILTER_SIZE 6
|
||||
#define ADC_FILTER_SIZE 3
|
||||
|
||||
#include "AP_ADC.h"
|
||||
#include <inttypes.h>
|
||||
|
|
|
@ -1,277 +0,0 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#include "Camera.h"
|
||||
#include "../RC_Channel/RC_Channel.h"
|
||||
|
||||
void
|
||||
Camera::move()
|
||||
{
|
||||
Vector3<float> target_vector(0,0,1); // x, y, z to target before rotating to planes axis, values are in meters
|
||||
|
||||
//decide what happens to camera depending on camera mode
|
||||
switch(mode)
|
||||
{
|
||||
case 0:
|
||||
//do nothing, i.e lock camera in place
|
||||
return;
|
||||
break;
|
||||
case 1:
|
||||
//stabilize
|
||||
target_vector.x=0; //east to west gives +tive value (i.e. longitude)
|
||||
target_vector.y=0; //south to north gives +tive value (i.e. latitude)
|
||||
target_vector.z=100; //downwards is +tive
|
||||
break;
|
||||
case 2:
|
||||
//track target
|
||||
if(g_gps->fix)
|
||||
{
|
||||
target_vector=get_location_vector(¤t_loc,&camera_target);
|
||||
}
|
||||
break;
|
||||
case 3: // radio manual control
|
||||
case 4: // test (level the camera and point north)
|
||||
break; // see code 25 lines bellow
|
||||
}
|
||||
|
||||
Matrix3f m = dcm.get_dcm_transposed();
|
||||
Vector3<float> targ = m*target_vector; //to do: find out notion of x y convention
|
||||
switch(gimbal_type)
|
||||
{
|
||||
case 0: // pitch & roll (tilt & roll)
|
||||
cam_pitch = degrees(atan2(-targ.x, targ.z)); //pitch
|
||||
cam_roll = degrees(atan2(targ.y, targ.z)); //roll
|
||||
break;
|
||||
|
||||
case 1: // yaw & pitch (pan & tilt)
|
||||
cam_pitch = atan2((sqrt(sq(targ.y) + sq(targ.x)) * .01113195), targ.z) * -1;
|
||||
cam_yaw = 9000 + atan2(-targ.y, targ.x) * 5729.57795;
|
||||
break;
|
||||
|
||||
/* case 2: // pitch, roll & yaw - not started
|
||||
cam_ritch = 0;
|
||||
cam_yoll = 0;
|
||||
cam_paw = 0;
|
||||
break; */
|
||||
|
||||
}
|
||||
|
||||
//some camera modes overwrite the gimbal_type calculations
|
||||
switch(mode)
|
||||
{
|
||||
case 3: // radio manual control
|
||||
if (rc_function[CAM_PITCH])
|
||||
cam_pitch = map(rc_function[CAM_PITCH]->radio_in,
|
||||
rc_function[CAM_PITCH]->radio_min,
|
||||
rc_function[CAM_PITCH]->radio_max,
|
||||
rc_function[CAM_PITCH]->angle_min,
|
||||
rc_function[CAM_PITCH]->radio_max);
|
||||
if (rc_function[CAM_ROLL])
|
||||
cam_roll = map(rc_function[CAM_ROLL]->radio_in,
|
||||
rc_function[CAM_ROLL]->radio_min,
|
||||
rc_function[CAM_ROLL]->radio_max,
|
||||
rc_function[CAM_ROLL]->angle_min,
|
||||
rc_function[CAM_ROLL]->radio_max);
|
||||
if (rc_function[CAM_YAW])
|
||||
cam_yaw = map(rc_function[CAM_YAW]->radio_in,
|
||||
rc_function[CAM_YAW]->radio_min,
|
||||
rc_function[CAM_YAW]->radio_max,
|
||||
rc_function[CAM_YAW]->angle_min,
|
||||
rc_function[CAM_YAW]->radio_max);
|
||||
break;
|
||||
case 4: // test (level the camera and point north)
|
||||
cam_pitch = -dcm.pitch_sensor;
|
||||
cam_yaw = dcm.yaw_sensor; // do not invert because the servo is mounted upside-down on my system
|
||||
// TODO: the "trunk" code can invert using parameters, but this branch still can't
|
||||
cam_roll = -dcm.roll_sensor;
|
||||
break;
|
||||
}
|
||||
|
||||
#if CAM_DEBUG == ENABLED
|
||||
//for debugging purposes
|
||||
Serial.println();
|
||||
Serial.print("current_loc: lat: ");
|
||||
Serial.print(current_loc.lat);
|
||||
Serial.print(", lng: ");
|
||||
Serial.print(current_loc.lng);
|
||||
Serial.print(", alt: ");
|
||||
Serial.print(current_loc.alt);
|
||||
Serial.println();
|
||||
Serial.print("target_loc: lat: ");
|
||||
Serial.print(camera_target.lat);
|
||||
Serial.print(", lng: ");
|
||||
Serial.print(camera_target.lng);
|
||||
Serial.print(", alt: ");
|
||||
Serial.print(camera_target.alt);
|
||||
Serial.print(", distance: ");
|
||||
Serial.print(get_distance(¤t_loc,&camera_target));
|
||||
Serial.print(", bearing: ");
|
||||
Serial.print(get_bearing(¤t_loc,&camera_target));
|
||||
Serial.println();
|
||||
Serial.print("dcm_angles: roll: ");
|
||||
Serial.print(degrees(dcm.roll));
|
||||
Serial.print(", pitch: ");
|
||||
Serial.print(degrees(dcm.pitch));
|
||||
Serial.print(", yaw: ");
|
||||
Serial.print(degrees(dcm.yaw));
|
||||
Serial.println();
|
||||
Serial.print("target_vector: x: ");
|
||||
Serial.print(target_vector.x,2);
|
||||
Serial.print(", y: ");
|
||||
Serial.print(target_vector.y,2);
|
||||
Serial.print(", z: ");
|
||||
Serial.print(target_vector.z,2);
|
||||
Serial.println();
|
||||
Serial.print("rotated_target_vector: x: ");
|
||||
Serial.print(targ.x,2);
|
||||
Serial.print(", y: ");
|
||||
Serial.print(targ.y,2);
|
||||
Serial.print(", z: ");
|
||||
Serial.print(targ.z,2);
|
||||
Serial.println();
|
||||
Serial.print("gimbal type 0: roll: ");
|
||||
Serial.print(roll);
|
||||
Serial.print(", pitch: ");
|
||||
Serial.print(pitch);
|
||||
Serial.println();
|
||||
/* Serial.print("gimbal type 1: pitch: ");
|
||||
Serial.print(pan);
|
||||
Serial.print(", roll: ");
|
||||
Serial.print(tilt);
|
||||
Serial.println(); */
|
||||
/* Serial.print("gimbal type 2: pitch: ");
|
||||
Serial.print(ritch);
|
||||
Serial.print(", roll: ");
|
||||
Serial.print(yoll);
|
||||
Serial.print(", yaw: ");
|
||||
Serial.print(paw);
|
||||
Serial.println(); */
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
Camera::set_target(struct Location target)
|
||||
{
|
||||
camera_target = target;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
Camera::update_camera_gimbal_type()
|
||||
{
|
||||
|
||||
// Auto detect the camera gimbal type depending on the functions assigned to the servos
|
||||
if ((rc_function[CAM_YAW] == NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] != NULL))
|
||||
{
|
||||
gimbal_type = 0;
|
||||
}
|
||||
if ((rc_function[CAM_YAW] != NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] == NULL))
|
||||
{
|
||||
gimbal_type = 1;
|
||||
}
|
||||
if ((rc_function[CAM_YAW] != NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] != NULL))
|
||||
{
|
||||
gimbal_type = 2;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Camera::servo_pic() // Servo operated camera
|
||||
{
|
||||
if (rc_function[CAM_TRIGGER])
|
||||
{
|
||||
cam_trigger = rc_function[CAM_TRIGGER]->radio_max;
|
||||
keep_cam_trigg_active_cycles = 2; // leave a message that it should be active for two event loop cycles
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Camera::relay_pic() // basic relay activation
|
||||
{
|
||||
relay_on();
|
||||
keep_cam_trigg_active_cycles = 2; // leave a message that it should be active for two event loop cycles
|
||||
}
|
||||
|
||||
void
|
||||
Camera::throttle_pic() // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
|
||||
{
|
||||
g.channel_throttle.radio_out = g.throttle_min;
|
||||
if (thr_pic == 10){
|
||||
servo_pic(); // triggering method
|
||||
thr_pic = 0;
|
||||
g.channel_throttle.radio_out = g.throttle_cruise;
|
||||
}
|
||||
thr_pic++;
|
||||
}
|
||||
|
||||
void
|
||||
Camera::distance_pic() // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
|
||||
{
|
||||
g.channel_throttle.radio_out = g.throttle_min;
|
||||
if (wp_distance < 3){
|
||||
servo_pic(); // triggering method
|
||||
g.channel_throttle.radio_out = g.throttle_cruise;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Camera::NPN_pic() // hacked the circuit to run a transistor? use this trigger to send output.
|
||||
{
|
||||
// To Do: Assign pin spare pin for output
|
||||
digitalWrite(camtrig, HIGH);
|
||||
keep_cam_trigg_active_cycles = 1; // leave a message that it should be active for two event loop cycles
|
||||
}
|
||||
|
||||
// single entry point to take pictures
|
||||
void
|
||||
Camera::trigger_pic()
|
||||
{
|
||||
switch (trigger_type)
|
||||
{
|
||||
case 0:
|
||||
servo_pic(); // Servo operated camera
|
||||
break;
|
||||
case 1:
|
||||
relay_pic(); // basic relay activation
|
||||
break;
|
||||
case 2:
|
||||
throttle_pic(); // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
|
||||
break;
|
||||
case 3:
|
||||
distance_pic(); // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
|
||||
break;
|
||||
case 4:
|
||||
NPN_pic(); // hacked the circuit to run a transistor? use this trigger to send output.
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// de-activate the trigger after some delay, but without using a delay() function
|
||||
void
|
||||
Camera::trigger_pic_cleanup()
|
||||
{
|
||||
if (keep_cam_trigg_active_cycles)
|
||||
{
|
||||
keep_cam_trigg_active_cycles --;
|
||||
}
|
||||
else
|
||||
{
|
||||
switch (trigger_type)
|
||||
{
|
||||
case 0:
|
||||
case 2:
|
||||
case 3:
|
||||
if (rc_function[CAM_TRIGGER])
|
||||
{
|
||||
cam_trigger = rc_function[CAM_TRIGGER]->radio_min;
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
relay_off();
|
||||
break;
|
||||
case 4:
|
||||
digitalWrite(camtrig, LOW);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -1,71 +0,0 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file Camera.h
|
||||
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
|
||||
|
||||
#ifndef CAMERA_H
|
||||
#define CAMERA_H
|
||||
|
||||
#include <AP_Common.h>
|
||||
|
||||
/// @class Camera
|
||||
/// @brief Object managing a Photo or video camera
|
||||
class Camera{
|
||||
protected:
|
||||
AP_Var_group _group; // must be before all vars to keep ctor init order correct
|
||||
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key EEPROM storage key for the camera configuration parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
Camera(AP_Var::Key key, const prog_char_t *name) :
|
||||
_group(key, name),
|
||||
mode (&_group, 0, 0, name ? PSTR("MODE") : 0), // suppress name if group has no name
|
||||
trigger_type(&_group, 1, 0, name ? PSTR("TRIGGER_MODE") : 0),
|
||||
picture_time (0), // waypoint trigger variable
|
||||
thr_pic (0), // timer variable for throttle_pic
|
||||
camtrig (83), // PK6 chosen as it not near anything so safer for soldering
|
||||
// camera_target (home), // use test target for now
|
||||
gimbal_type (1),
|
||||
keep_cam_trigg_active_cycles (0)
|
||||
{}
|
||||
|
||||
// move the camera depending on the camera mode
|
||||
void move();
|
||||
|
||||
// single entry point to take pictures
|
||||
void trigger_pic();
|
||||
|
||||
// de-activate the trigger after some delay, but without using a delay() function
|
||||
void trigger_pic_cleanup();
|
||||
|
||||
// call this from time to time to make sure the correct gimbal type gets choosen
|
||||
void update_camera_gimbal_type();
|
||||
|
||||
// set camera orientation target
|
||||
void set_target(struct Location target);
|
||||
|
||||
int picture_time; // waypoint trigger variable
|
||||
|
||||
private:
|
||||
uint8_t keep_cam_trigg_active_cycles; // event loop cycles to keep trigger active
|
||||
struct Location camera_target; // point of interest for the camera to track
|
||||
// struct Location GPS_mark; // GPS POI for position based triggering
|
||||
int thr_pic; // timer variable for throttle_pic
|
||||
int camtrig; // PK6 chosen as it not near anything so safer for soldering
|
||||
|
||||
AP_Int8 mode; // 0=do nothing, 1=stabilize, 2=track target, 3=manual, 4=simple stabilize test
|
||||
AP_Int8 trigger_type; // 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint 4=transistor
|
||||
uint8_t gimbal_type; // 0=pitch & roll (tilt & roll), 1=yaw & pitch(pan & tilt), 2=pitch, roll & yaw (to be added)
|
||||
|
||||
void servo_pic(); // Servo operated camera
|
||||
void relay_pic(); // basic relay activation
|
||||
void throttle_pic(); // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
|
||||
void distance_pic(); // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
|
||||
void NPN_pic(); // hacked the circuit to run a transistor? use this trigger to send output.
|
||||
|
||||
};
|
||||
|
||||
#endif /* CAMERA_H */
|
|
@ -259,7 +259,11 @@ SKETCHCPP_SRC := $(SKETCHPDE) $(sort $(filter-out $(SKETCHPDE),$(SKETCHPDESRCS)
|
|||
# make.
|
||||
#
|
||||
SEXPR = 's/^[[:space:]]*\#include[[:space:]][<\"]([^>\"./]+).*$$/\1/p'
|
||||
LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR)))
|
||||
ifeq ($(SYSTYPE),Darwin)
|
||||
LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nEe $(SEXPR)))
|
||||
else
|
||||
LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR)))
|
||||
endif
|
||||
|
||||
#
|
||||
# Find sketchbook libraries referenced by the sketch.
|
||||
|
|
|
@ -41,7 +41,7 @@ AP_DCM::set_compass(Compass *compass)
|
|||
|
||||
/**************************************************/
|
||||
void
|
||||
AP_DCM::update_DCM(float _G_Dt)
|
||||
AP_DCM::update_DCM_fast(float _G_Dt)
|
||||
{
|
||||
_imu->update();
|
||||
_gyro_vector = _imu->get_gyro(); // Get current values for IMU sensors
|
||||
|
@ -49,13 +49,48 @@ AP_DCM::update_DCM(float _G_Dt)
|
|||
|
||||
matrix_update(_G_Dt); // Integrate the DCM matrix
|
||||
|
||||
//if(_toggle){
|
||||
normalize(); // Normalize the DCM matrix
|
||||
//}else{
|
||||
drift_correction(); // Perform drift correction
|
||||
//}
|
||||
//_toggle = !_toggle;
|
||||
switch(_toggle++){
|
||||
case 0:
|
||||
normalize(); // Normalize the DCM matrix
|
||||
break;
|
||||
|
||||
case 1:
|
||||
//drift_correction(); // Normalize the DCM matrix
|
||||
euler_rp(); // Calculate pitch, roll, yaw for stabilization and navigation
|
||||
break;
|
||||
|
||||
case 2:
|
||||
drift_correction(); // Normalize the DCM matrix
|
||||
break;
|
||||
|
||||
case 3:
|
||||
//drift_correction(); // Normalize the DCM matrix
|
||||
euler_rp(); // Calculate pitch, roll, yaw for stabilization and navigation
|
||||
break;
|
||||
|
||||
case 4:
|
||||
euler_yaw();
|
||||
break;
|
||||
|
||||
default:
|
||||
euler_rp(); // Calculate pitch, roll, yaw for stabilization and navigation
|
||||
_toggle = 0;
|
||||
//drift_correction(); // Normalize the DCM matrix
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
void
|
||||
AP_DCM::update_DCM(float _G_Dt)
|
||||
{
|
||||
_imu->update();
|
||||
_gyro_vector = _imu->get_gyro(); // Get current values for IMU sensors
|
||||
_accel_vector = _imu->get_accel(); // Get current values for IMU sensors
|
||||
|
||||
matrix_update(_G_Dt); // Integrate the DCM matrix
|
||||
normalize(); // Normalize the DCM matrix
|
||||
drift_correction(); // Perform drift correction
|
||||
euler_angles(); // Calculate pitch, roll, yaw for stabilization and navigation
|
||||
}
|
||||
|
||||
|
@ -83,11 +118,12 @@ AP_DCM::matrix_update(float _G_Dt)
|
|||
Matrix3f temp_matrix;
|
||||
|
||||
//Record when you saturate any of the gyros.
|
||||
/*
|
||||
if( (fabs(_gyro_vector.x) >= radians(300)) ||
|
||||
(fabs(_gyro_vector.y) >= radians(300)) ||
|
||||
(fabs(_gyro_vector.z) >= radians(300))){
|
||||
gyro_sat_count++;
|
||||
}
|
||||
}*/
|
||||
|
||||
_omega_integ_corr = _gyro_vector + _omega_I; // Used for _centripetal correction (theoretically better than _omega)
|
||||
_omega = _omega_integ_corr + _omega_P; // Equation 16, adding proportional and integral correction terms
|
||||
|
@ -335,6 +371,25 @@ AP_DCM::euler_angles(void)
|
|||
yaw_sensor += 36000;
|
||||
}
|
||||
|
||||
void
|
||||
AP_DCM::euler_rp(void)
|
||||
{
|
||||
pitch = -asin(_dcm_matrix.c.x);
|
||||
roll = atan2(_dcm_matrix.c.y, _dcm_matrix.c.z);
|
||||
roll_sensor = degrees(roll) * 100;
|
||||
pitch_sensor = degrees(pitch) * 100;
|
||||
}
|
||||
|
||||
void
|
||||
AP_DCM::euler_yaw(void)
|
||||
{
|
||||
yaw = atan2(_dcm_matrix.b.x, _dcm_matrix.a.x);
|
||||
yaw_sensor = degrees(yaw) * 100;
|
||||
|
||||
if (yaw_sensor < 0)
|
||||
yaw_sensor += 36000;
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
|
||||
float
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#ifndef AP_DCM_h
|
||||
#define AP_DCM_h
|
||||
|
||||
// teporarily include all other classes here
|
||||
// temporarily include all other classes here
|
||||
// since this naming is a bit off from the
|
||||
// convention and the AP_DCM should be the top
|
||||
// header file
|
||||
|
@ -50,6 +50,7 @@ public:
|
|||
|
||||
// Methods
|
||||
void update_DCM(float _G_Dt);
|
||||
void update_DCM_fast(float _G_Dt);
|
||||
|
||||
float get_health(void);
|
||||
|
||||
|
@ -98,6 +99,10 @@ private:
|
|||
void drift_correction(void);
|
||||
void euler_angles(void);
|
||||
|
||||
void euler_rp(void);
|
||||
void euler_yaw(void);
|
||||
|
||||
|
||||
// members
|
||||
Compass * _compass;
|
||||
|
||||
|
@ -122,7 +127,7 @@ private:
|
|||
float _course_over_ground_y; // Course overground Y axis
|
||||
float _health;
|
||||
bool _centripetal;
|
||||
bool _toggle;
|
||||
uint8_t _toggle;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1,9 +0,0 @@
|
|||
AP_Mount KEYWORD1
|
||||
SetGPSTarget KEYWORD2
|
||||
SetAssisted KEYWORD2
|
||||
SetAntenna KEYWORD2
|
||||
SetMountFPV KEYWORD2
|
||||
SetMountLanding KEYWORD2
|
||||
UpDateMount KEYWORD2
|
||||
SetMode KEYWORD2
|
||||
|
|
@ -120,7 +120,7 @@ RC_Channel::calc_pwm(void)
|
|||
{
|
||||
if(_type == RC_CHANNEL_RANGE){
|
||||
pwm_out = range_to_pwm();
|
||||
radio_out = pwm_out + radio_min;
|
||||
radio_out = (_reverse >=0 ? pwm_out + radio_min : radio_max - pwm_out);
|
||||
|
||||
}else if(_type == RC_CHANNEL_ANGLE_RAW){
|
||||
pwm_out = (float)servo_out * .1;
|
||||
|
|
|
@ -7,12 +7,11 @@
|
|||
#define RC_Channel_h
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/// @class RC_Channel
|
||||
/// @brief Object managing one RC channel
|
||||
class RC_Channel{
|
||||
private:
|
||||
protected:
|
||||
AP_Var_group _group; // must be before all vars to keep ctor init order correct
|
||||
|
||||
public:
|
||||
|
@ -103,8 +102,7 @@ class RC_Channel{
|
|||
int16_t _low;
|
||||
};
|
||||
|
||||
// This is ugly, but it fixes compilation on arduino
|
||||
#include "RC_Channel_aux.h"
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,55 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#include <APM_RC.h>
|
||||
#include "RC_Channel_aux.h"
|
||||
|
||||
extern RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
|
||||
|
||||
// map a function to a servo channel and output it
|
||||
void
|
||||
RC_Channel_aux::output_ch(unsigned char ch_nr)
|
||||
{
|
||||
// take care or two corner cases
|
||||
switch(function)
|
||||
{
|
||||
case k_none: // disabled
|
||||
return;
|
||||
break;
|
||||
case k_manual: // manual
|
||||
radio_out = radio_in;
|
||||
break;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(ch_nr, radio_out);
|
||||
}
|
||||
|
||||
// Update the g_rc_function array of pointers to rc_x channels
|
||||
// This is to be done before rc_init so that the channels get correctly initialized.
|
||||
// It also should be called periodically because the user might change the configuration and
|
||||
// expects the changes to take effect instantly
|
||||
void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Channel_aux* rc_7, RC_Channel_aux* rc_8)
|
||||
{
|
||||
// positions 0..3 of this array never get used, but this is a stack array, so the entire array gets freed at the end of the function
|
||||
RC_Channel_aux::Aux_servo_function_t aux_servo_function[NUM_CHANNELS]; // the function of the aux. servos
|
||||
aux_servo_function[CH_5] = (RC_Channel_aux::Aux_servo_function_t)rc_5->function.get();
|
||||
aux_servo_function[CH_6] = (RC_Channel_aux::Aux_servo_function_t)rc_6->function.get();
|
||||
aux_servo_function[CH_7] = (RC_Channel_aux::Aux_servo_function_t)rc_7->function.get();
|
||||
aux_servo_function[CH_8] = (RC_Channel_aux::Aux_servo_function_t)rc_8->function.get();
|
||||
|
||||
// Assume that no auxiliary function is used
|
||||
for (int i = 0; i < RC_Channel_aux::k_nr_aux_servo_functions ; i++)
|
||||
{
|
||||
g_rc_function[i] = NULL;
|
||||
}
|
||||
|
||||
// assign the RC channel to each function
|
||||
g_rc_function[aux_servo_function[CH_5]] = rc_5;
|
||||
g_rc_function[aux_servo_function[CH_6]] = rc_6;
|
||||
g_rc_function[aux_servo_function[CH_7]] = rc_7;
|
||||
g_rc_function[aux_servo_function[CH_8]] = rc_8;
|
||||
|
||||
G_RC_AUX(k_flap)->set_range(0,100);
|
||||
G_RC_AUX(k_flap_auto)->set_range(0,100);
|
||||
G_RC_AUX(k_aileron)->set_angle(4500);
|
||||
G_RC_AUX(k_flaperon)->set_range(0,100);
|
||||
}
|
|
@ -0,0 +1,48 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file RC_Channel_aux.h
|
||||
/// @brief RC_Channel manager for Channels 5..8, with EEPROM-backed storage of constants.
|
||||
/// @author Amilcar Lucas
|
||||
|
||||
#ifndef RC_CHANNEL_AUX_H_
|
||||
#define RC_CHANNEL_AUX_H_
|
||||
|
||||
#include "RC_Channel.h"
|
||||
|
||||
// Macro to simplify accessing the auxiliary servos
|
||||
#define G_RC_AUX(_t) if (g_rc_function[RC_Channel_aux::_t]) g_rc_function[RC_Channel_aux::_t]
|
||||
|
||||
/// @class RC_Channel_aux
|
||||
/// @brief Object managing one aux. RC channel (CH5-8), with information about its function
|
||||
class RC_Channel_aux : public RC_Channel{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key EEPROM storage key for the channel trim parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
RC_Channel_aux(AP_Var::Key key, const prog_char_t *name) :
|
||||
RC_Channel(key, name),
|
||||
function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0) // suppress name if group has no name
|
||||
{}
|
||||
|
||||
typedef enum
|
||||
{
|
||||
k_none = 0, // disabled
|
||||
k_manual = 1, // manual, just pass-thru the RC in signal
|
||||
k_flap = 2, // flap
|
||||
k_flap_auto = 3, // flap automated
|
||||
k_aileron = 4, // aileron
|
||||
k_flaperon = 5, // flaperon (flaps and aileron combined, needs two independent servos one for each wing)
|
||||
k_nr_aux_servo_functions // This must be the last enum value (only add new values _before_ this one)
|
||||
} Aux_servo_function_t;
|
||||
|
||||
AP_Int8 function; // 0=disabled, 1=manual, 2=flap, 3=flap auto, 4=aileron, 5=flaperon, 6=mount yaw (pan), 7=mount pitch (tilt), 8=mount roll, 9=camera trigger, 10=camera open, 11=egg drop
|
||||
|
||||
void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it
|
||||
|
||||
};
|
||||
|
||||
void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Channel_aux* rc_7, RC_Channel_aux* rc_8);
|
||||
|
||||
#endif /* RC_CHANNEL_AUX_H_ */
|
Loading…
Reference in New Issue