diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 31d427146a..37331f0ce3 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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 // ---------- @@ -507,7 +508,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; @@ -530,7 +531,7 @@ void loop() //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++; @@ -907,16 +908,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--; @@ -1301,7 +1301,7 @@ static void read_AHRS(void) hil.update(); #endif - dcm.update_DCM(G_Dt); + dcm.update_DCM(G_Dt);//, _tog); omega = dcm.get_gyro(); } @@ -1396,63 +1396,71 @@ 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() diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index effcf76bc2..8a9512664d 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -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; } diff --git a/ArduCopter/Mavlink_Common.h b/ArduCopter/Mavlink_Common.h index f401d048ef..7d54f4ef80 100644 --- a/ArduCopter/Mavlink_Common.h +++ b/ArduCopter/Mavlink_Common.h @@ -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); @@ -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; } diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index c8b8037991..c2680f856e 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -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")), diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 664ab801c9..1b3423e4ca 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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 diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 6b485b146a..5a0dcbfd91 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -138,13 +138,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 +145,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 +313,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 /* ************************************************************** */ diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 21e6758962..4025730e8c 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -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() diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 9b618dcadb..529297aa2d 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -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); +} diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index c2cf31502e..3b8ef34edd 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -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.41 Beta", main_menu_commands); #endif // CLI_ENABLED diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 3baaf3cc08..6dcd5614f4 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -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() { diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index c1546d95a4..db34c15389 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -131,7 +131,8 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax) } if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){ - send_message(MSG_RAW_ADC); + // Available datastream + //Serial.printf("mav8 %d\n", (int)streamRateExtra3.get()); } } } diff --git a/ArduPlane/Mavlink_Common.h b/ArduPlane/Mavlink_Common.h index 4c2147b2c4..3de4438cc2 100644 --- a/ArduPlane/Mavlink_Common.h +++ b/ArduPlane/Mavlink_Common.h @@ -344,20 +344,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_ break; } - - case MSG_RAW_ADC: - { - CHECK_PAYLOAD_SIZE(AP_ADC); - mavlink_msg_ap_adc_send(chan, - analogRead(BATTERY_PIN1), - analogRead(BATTERY_PIN2), - analogRead(BATTERY_PIN3), - analogRead(BATTERY_PIN4), - analogRead(AN4), - analogRead(AN5)); - break; - } - default: break; } @@ -365,7 +351,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_ } -#define MAX_DEFERRED_MESSAGES 18 // should be at least equal to number of +#define MAX_DEFERRED_MESSAGES 17 // should be at least equal to number of // switch types in mavlink_try_send_message() static struct mavlink_queue { uint8_t deferred_messages[MAX_DEFERRED_MESSAGES]; diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 3929123647..b48deed2da 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -176,7 +176,6 @@ #define MSG_GPS_RAW 0x64 #define MSG_SERVO_OUT 0x70 -#define MSG_RAW_ADC 0x71 #define MSG_PIN_REQUEST 0x80 #define MSG_PIN_SET 0x81 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt index d8f061f4bc..ee9cf57691 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001fb8 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt index d6992b33c3..84dec1b6a0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001fb6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log index f9ac117a10..b1aee4e1a4 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log @@ -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 @@ -34,8 +33,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,19 +48,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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt index 49251a6ae6..300eeeb23c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt @@ -132,7 +132,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 @@ -163,6 +162,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 @@ -170,6 +170,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 @@ -182,6 +183,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 @@ -219,6 +221,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 @@ -227,6 +230,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 @@ -253,7 +257,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 @@ -282,6 +285,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 @@ -383,6 +387,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 W AP_VarT::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status 00000019 r GCS_MAVLINK::update()::__c @@ -480,7 +485,6 @@ 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*) @@ -510,6 +514,8 @@ 0000008c t setup_frame(unsigned char, Menu::arg const*) 00000090 t init_compass() 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) @@ -539,10 +545,10 @@ 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 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() @@ -583,18 +589,19 @@ 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() +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 -00000568 t __static_initialization_and_destruction_0(int, int) +00000578 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() +000007dc b g +0000083c W Parameters::Parameters() 000008e4 t process_next_command() -000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) +00001196 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*) -0000194a T loop +00001902 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log index f9ac117a10..b1aee4e1a4 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log @@ -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 @@ -34,8 +33,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,19 +48,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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt index 77b38118ab..9781e6a0e6 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt @@ -132,7 +132,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 @@ -163,6 +162,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 @@ -170,6 +170,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 @@ -182,6 +183,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 @@ -219,6 +221,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 @@ -227,6 +230,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 @@ -253,7 +257,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 @@ -282,6 +285,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 @@ -383,6 +387,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 W AP_VarT::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status 00000019 r GCS_MAVLINK::update()::__c @@ -480,7 +485,6 @@ 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*) @@ -510,6 +514,8 @@ 0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*) 00000090 t init_compass() +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) @@ -539,10 +545,10 @@ 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 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() @@ -583,18 +589,19 @@ 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() +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 -00000568 t __static_initialization_and_destruction_0(int, int) +00000578 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() +000007dc b g +0000083c W Parameters::Parameters() 000008e4 t process_next_command() -000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) +00001196 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001948 T loop +00001900 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt index d880bfc7ae..a48a9b82be 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001e86 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt index d06cc7853f..b8ece535cd 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001e84 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt index 0ab5cc71b9..02d799cbcd 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001de6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt index 28a12d499f..e093161912 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001de4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt index b765d03870..5d308cf013 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001ec6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log index 6d390dc9bd..ff07e834d3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt index a70917bb1a..98b0c692ae 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt @@ -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::serialize(void*, unsigned int) const 00000018 b mavlink_get_channel_status::m_mavlink_status @@ -485,7 +490,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 +521,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 +555,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() @@ -595,18 +601,19 @@ 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) +00001ec4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 4f556adf34..b285a250b5 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -58,7 +58,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex - ArduCopter 2.0.40 Beta Quad + ArduCopter 2.0.41 Beta Quad #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION X_FRAME @@ -69,7 +69,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex - ArduCopter 2.0.40 Beta Tri + ArduCopter 2.0.41 Beta Tri #define FRAME_CONFIG TRI_FRAME #define FRAME_ORIENTATION X_FRAME @@ -80,7 +80,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex - ArduCopter 2.0.40 Beta Hexa + ArduCopter 2.0.41 Beta Hexa #define FRAME_CONFIG HEXA_FRAME #define FRAME_ORIENTATION X_FRAME @@ -91,7 +91,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex - ArduCopter 2.0.40 Beta Y6 + ArduCopter 2.0.41 Beta Y6 #define FRAME_CONFIG Y6_FRAME #define FRAME_ORIENTATION X_FRAME @@ -102,7 +102,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex - ArduCopter 2.0.40 Beta Heli (2560 only) + ArduCopter 2.0.41 Beta Heli (2560 only) #define AUTO_RESET_LOITER 0 #define FRAME_CONFIG HELI_FRAME @@ -149,7 +149,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex - ArduCopter 2.0.40 Beta Quad Hil + ArduCopter 2.0.41 Beta Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 2a7bfed917..d43656d340 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1 +1,9 @@ -Already up-to-date. +From https://code.google.com/p/ardupilot-mega + 22593cc..5e95582 APM_Camera -> origin/APM_Camera + 0448983..dc0031c master -> origin/master +Updating 0448983..dc0031c +Fast-forward + ArduCopter/ArduCopter.pde | 6 ++++++ + ArduCopter/Parameters.h | 3 +++ + ArduCopter/defines.h | 6 ++++-- + 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h index e650159666..1272728607 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} +#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} +#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} #endif #include "../protocol.h" @@ -48,7 +48,6 @@ extern "C" { #include "./mavlink_msg_sensor_offsets.h" #include "./mavlink_msg_set_mag_offsets.h" #include "./mavlink_msg_meminfo.h" -#include "./mavlink_msg_ap_adc.h" #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h deleted file mode 100644 index d42edb15d3..0000000000 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h +++ /dev/null @@ -1,254 +0,0 @@ -// MESSAGE AP_ADC PACKING - -#define MAVLINK_MSG_ID_AP_ADC 153 - -typedef struct __mavlink_ap_adc_t -{ - uint16_t adc1; ///< ADC output 1 - uint16_t adc2; ///< ADC output 2 - uint16_t adc3; ///< ADC output 3 - uint16_t adc4; ///< ADC output 4 - uint16_t adc5; ///< ADC output 5 - uint16_t adc6; ///< ADC output 6 -} mavlink_ap_adc_t; - -#define MAVLINK_MSG_ID_AP_ADC_LEN 12 -#define MAVLINK_MSG_ID_153_LEN 12 - - - -#define MAVLINK_MESSAGE_INFO_AP_ADC { \ - "AP_ADC", \ - 6, \ - { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \ - { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \ - { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \ - { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \ - { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \ - { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \ - } \ -} - - -/** - * @brief Pack a ap_adc message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - - memcpy(_MAV_PAYLOAD(msg), buf, 12); -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - - memcpy(_MAV_PAYLOAD(msg), &packet, 12); -#endif - - msg->msgid = MAVLINK_MSG_ID_AP_ADC; - return mavlink_finalize_message(msg, system_id, component_id, 12); -} - -/** - * @brief Pack a ap_adc message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message was sent over - * @param msg The MAVLink message to compress the data into - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - - memcpy(_MAV_PAYLOAD(msg), buf, 12); -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - - memcpy(_MAV_PAYLOAD(msg), &packet, 12); -#endif - - msg->msgid = MAVLINK_MSG_ID_AP_ADC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12); -} - -/** - * @brief Encode a ap_adc struct into a message - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ap_adc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) -{ - return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); -} - -/** - * @brief Send a ap_adc message - * @param chan MAVLink channel to send the message - * - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12); -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12); -#endif -} - -#endif - -// MESSAGE AP_ADC UNPACKING - - -/** - * @brief Get field adc1 from ap_adc message - * - * @return ADC output 1 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field adc2 from ap_adc message - * - * @return ADC output 2 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field adc3 from ap_adc message - * - * @return ADC output 3 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field adc4 from ap_adc message - * - * @return ADC output 4 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field adc5 from ap_adc message - * - * @return ADC output 5 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field adc6 from ap_adc message - * - * @return ADC output 6 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Decode a ap_adc message into a struct - * - * @param msg The message to decode - * @param ap_adc C-struct to decode the message contents into - */ -static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc) -{ -#if MAVLINK_NEED_BYTE_SWAP - ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg); - ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg); - ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg); - ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg); - ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); - ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); -#else - memcpy(ap_adc, _MAV_PAYLOAD(msg), 12); -#endif -} diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h index 6a2e90cae5..cd59317f8f 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h @@ -185,65 +185,11 @@ static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlin MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } -static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_ap_adc_t packet_in = { - 17235, - 17339, - 17443, - 17547, - 17651, - 17755, - }; - mavlink_ap_adc_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.adc1 = packet_in.adc1; - packet1.adc2 = packet_in.adc2; - packet1.adc3 = packet_in.adc3; - packet1.adc4 = packet_in.adc4; - packet1.adc5 = packet_in.adc5; - packet1.adc6 = packet_in.adc6; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_ap_adc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 ); - mavlink_msg_ap_adc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 ); - mavlink_msg_ap_adc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; ifree memory - - raw ADC output - ADC output 1 - ADC output 2 - ADC output 3 - ADC output 4 - ADC output 5 - ADC output 6 - - diff --git a/libraries/GCS_MAVLink/message_definitions/test.xml b/libraries/GCS_MAVLink/message_definitions/test.xml deleted file mode 100644 index 43a11e3d13..0000000000 --- a/libraries/GCS_MAVLink/message_definitions/test.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - 3 - - - Test all field types - char - string - uint8_t - uint16_t - uint32_t - uint64_t - int8_t - int16_t - int32_t - int64_t - float - double - uint8_t_array - uint16_t_array - uint32_t_array - uint64_t_array - int8_t_array - int16_t_array - int32_t_array - int64_t_array - float_array - double_array - - -