mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
9dc42122f8
|
@ -284,7 +284,8 @@ static bool do_simple = false;
|
|||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static float heli_rollFactor[3], heli_pitchFactor[3]; // only required for 3 swashplate servos
|
||||
static int heli_servo_min[3], heli_servo_max[3]; // same here. for yaw servo we use heli_servo4_min/max parameter directly
|
||||
static int heli_servo_out[4];
|
||||
static long heli_servo_out[4]; // used for servo averaging for analog servos
|
||||
static int heli_servo_out_count = 0; // use for servo averaging
|
||||
#endif
|
||||
|
||||
// Failsafe
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
// The increment will prevent old parameters from being used incorrectly
|
||||
// by newer code.
|
||||
//
|
||||
static const uint16_t k_format_version = 108;
|
||||
static const uint16_t k_format_version = 109;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
|
@ -57,6 +57,27 @@ public:
|
|||
//
|
||||
k_param_log_bitmask,
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
//
|
||||
// 80: Heli
|
||||
//
|
||||
k_param_heli_servo_1 = 80,
|
||||
k_param_heli_servo_2,
|
||||
k_param_heli_servo_3,
|
||||
k_param_heli_servo_4,
|
||||
k_param_heli_servo1_pos ,
|
||||
k_param_heli_servo2_pos,
|
||||
k_param_heli_servo3_pos,
|
||||
k_param_heli_roll_max,
|
||||
k_param_heli_pitch_max,
|
||||
k_param_heli_collective_min,
|
||||
k_param_heli_collective_max,
|
||||
k_param_heli_collective_mid,
|
||||
k_param_heli_ext_gyro_enabled,
|
||||
k_param_heli_ext_gyro_gain,
|
||||
k_param_heli_servo_averaging, // 94
|
||||
#endif
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
k_param_streamrates_port0 = 110,
|
||||
|
@ -108,28 +129,6 @@ public:
|
|||
k_param_esc_calibrate,
|
||||
k_param_radio_tuning,
|
||||
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
//
|
||||
// 200: Heli
|
||||
//
|
||||
k_param_heli_servo_1 = 200,
|
||||
k_param_heli_servo_2,
|
||||
k_param_heli_servo_3,
|
||||
k_param_heli_servo_4,
|
||||
k_param_heli_servo1_pos ,
|
||||
k_param_heli_servo2_pos,
|
||||
k_param_heli_servo3_pos,
|
||||
k_param_heli_roll_max,
|
||||
k_param_heli_pitch_max,
|
||||
k_param_heli_collective_min,
|
||||
k_param_heli_collective_max,
|
||||
k_param_heli_collective_mid,
|
||||
k_param_heli_ext_gyro_enabled,
|
||||
k_param_heli_ext_gyro_gain, // 213
|
||||
#endif
|
||||
|
||||
|
||||
//
|
||||
// 210: flight modes
|
||||
//
|
||||
|
@ -247,7 +246,8 @@ public:
|
|||
AP_Int16 heli_roll_max, heli_pitch_max; // maximum allowed roll and pitch of swashplate
|
||||
AP_Int16 heli_coll_min, heli_coll_max, heli_coll_mid; // min and max collective. mid = main blades at zero pitch
|
||||
AP_Int8 heli_ext_gyro_enabled; // 0 = no external tail gyro, 1 = external tail gyro
|
||||
AP_Int16 heli_ext_gyro_gain; // radio output 1000~2000 (value output on CH_7)
|
||||
AP_Int16 heli_ext_gyro_gain; // radio output 1000~2000 (value output on CH_7)
|
||||
AP_Int8 heli_servo_averaging; // 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
|
||||
#endif
|
||||
|
||||
// RC channels
|
||||
|
@ -349,6 +349,7 @@ public:
|
|||
heli_coll_mid (1500, k_param_heli_collective_mid, PSTR("COL_MID_")),
|
||||
heli_ext_gyro_enabled (0, k_param_heli_ext_gyro_enabled, PSTR("GYR_ENABLE_")),
|
||||
heli_ext_gyro_gain (1000, k_param_heli_ext_gyro_gain, PSTR("GYR_GAIN_")),
|
||||
heli_servo_averaging (0, k_param_heli_servo_averaging, PSTR("SV_AVG")),
|
||||
#endif
|
||||
|
||||
// RC channel group key name
|
||||
|
|
|
@ -2,8 +2,18 @@
|
|||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz
|
||||
#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz
|
||||
|
||||
static int heli_manual_override = false;
|
||||
static float rollPitch_impact_on_collective = 0;
|
||||
|
||||
// heli_servo_averaging:
|
||||
// 0 or 1 = no averaging, 250hz
|
||||
// 2 = average two samples, 125hz
|
||||
// 3 = averaging three samples = 83.3 hz
|
||||
// 4 = averaging four samples = 62.5 hz
|
||||
// 5 = averaging 5 samples = 50hz
|
||||
// digital = 0 / 250hz, analog = 2 / 83.3
|
||||
|
||||
static void heli_init_swash()
|
||||
{
|
||||
|
@ -16,8 +26,6 @@ static void heli_init_swash()
|
|||
g.heli_servo_2.set_range(0,1000);
|
||||
g.heli_servo_3.set_range(0,1000);
|
||||
g.heli_servo_4.set_angle(4500);
|
||||
//g.heli_servo_4.radio_min = 1000; // required?
|
||||
//g.heli_servo_4.radio_max = 2000;
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos));
|
||||
|
@ -36,11 +44,6 @@ static void heli_init_swash()
|
|||
total_tilt_max = max(total_tilt_max,tilt_max[i]);
|
||||
}
|
||||
|
||||
//if( reset_collective == false ) {
|
||||
// g.heli_coll_min = total_tilt_max;
|
||||
// g.heli_coll_max = 1000 - total_tilt_max;
|
||||
//}
|
||||
|
||||
// servo min/max values - or should I use set_range?
|
||||
g.heli_servo_1.radio_min = g.heli_coll_min - tilt_max[CH_1];
|
||||
g.heli_servo_1.radio_max = g.heli_coll_max + tilt_max[CH_1];
|
||||
|
@ -48,6 +51,16 @@ static void heli_init_swash()
|
|||
g.heli_servo_2.radio_max = g.heli_coll_max + tilt_max[CH_2];
|
||||
g.heli_servo_3.radio_min = g.heli_coll_min - tilt_max[CH_3];
|
||||
g.heli_servo_3.radio_max = g.heli_coll_max + tilt_max[CH_3];
|
||||
|
||||
// reset the servo averaging
|
||||
for( i=0; i<=3; i++ )
|
||||
heli_servo_out[i] = 0;
|
||||
|
||||
// double check heli_servo_averaging is reasonable
|
||||
if( g.heli_servo_averaging < 0 || g.heli_servo_averaging < 0 > 5 ) {
|
||||
g.heli_servo_averaging = 0;
|
||||
g.heli_servo_averaging.save();
|
||||
}
|
||||
}
|
||||
|
||||
static void heli_move_servos_to_mid()
|
||||
|
@ -58,10 +71,10 @@ static void heli_move_servos_to_mid()
|
|||
//
|
||||
// heli_move_swash - moves swash plate to attitude of parameters passed in
|
||||
// - expected ranges:
|
||||
// roll : -4500 ~ 4500 // should be -500 to 500?
|
||||
// roll : -4500 ~ 4500
|
||||
// pitch: -4500 ~ 4500
|
||||
// collective: 1000 ~ 2000
|
||||
// yaw: -4500 ~ 4500??
|
||||
// yaw: -4500 ~ 4500
|
||||
//
|
||||
static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
|
||||
{
|
||||
|
@ -94,26 +107,46 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
|||
g.heli_servo_3.calc_pwm();
|
||||
g.heli_servo_4.calc_pwm();
|
||||
|
||||
// actually move the servos
|
||||
APM_RC.OutputCh(CH_1, g.heli_servo_1.servo_out);
|
||||
APM_RC.OutputCh(CH_2, g.heli_servo_2.servo_out);
|
||||
APM_RC.OutputCh(CH_3, g.heli_servo_3.servo_out);
|
||||
//APM_RC.OutputCh(CH_4, g.heli_servo_4.servo_out);
|
||||
APM_RC.OutputCh(CH_4, g.heli_servo_4.radio_out);
|
||||
// add the servo values to the averaging
|
||||
heli_servo_out[0] += g.heli_servo_1.servo_out;
|
||||
heli_servo_out[1] += g.heli_servo_2.servo_out;
|
||||
heli_servo_out[2] += g.heli_servo_3.servo_out;
|
||||
heli_servo_out[3] += g.heli_servo_4.radio_out;
|
||||
heli_servo_out_count++;
|
||||
|
||||
// output gyro value
|
||||
if( g.heli_ext_gyro_enabled ) {
|
||||
APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
|
||||
}
|
||||
// is it time to move the servos?
|
||||
if( heli_servo_out_count >= g.heli_servo_averaging ) {
|
||||
|
||||
// average the values if necessary
|
||||
if( g.heli_servo_averaging >= 2 ) {
|
||||
heli_servo_out[0] /= g.heli_servo_averaging;
|
||||
heli_servo_out[1] /= g.heli_servo_averaging;
|
||||
heli_servo_out[2] /= g.heli_servo_averaging;
|
||||
heli_servo_out[3] /= g.heli_servo_averaging;
|
||||
}
|
||||
|
||||
// actually move the servos
|
||||
APM_RC.OutputCh(CH_1, heli_servo_out[0]);
|
||||
APM_RC.OutputCh(CH_2, heli_servo_out[1]);
|
||||
APM_RC.OutputCh(CH_3, heli_servo_out[2]);
|
||||
APM_RC.OutputCh(CH_4, heli_servo_out[3]);
|
||||
|
||||
// output gyro value
|
||||
if( g.heli_ext_gyro_enabled ) {
|
||||
APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
|
||||
}
|
||||
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
|
||||
// debug
|
||||
//Serial.printf_P(PSTR("4: r%d \tcp:%d \tcol:%d \ty:%d \tout:%d \tpwm:%d \trOut:%d \ttrim:%d\n"), roll_out, pitch_out, coll_out, yaw_out, (int)g.heli_servo_4.servo_out, (int)g.heli_servo_4.pwm_out, (int)g.heli_servo_4.radio_out, (int)g.heli_servo_4.radio_trim);
|
||||
//Serial.printf_P(PSTR("4: y:%d \tout:%d \tpwm:%d \trOut:%d \ttrim:%d\n"), yaw_out, (int)g.heli_servo_4.servo_out, (int)g.heli_servo_4.pwm_out, (int)g.heli_servo_4.radio_out, (int)g.heli_servo_4.radio_trim);
|
||||
//Serial.printf_P(PSTR("4: y:%d \tro:%d\n"), yaw_out, (int)g.heli_servo_4.radio_out);
|
||||
// InstantPWM - force message to the servos
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
|
||||
// reset the averaging
|
||||
heli_servo_out_count = 0;
|
||||
heli_servo_out[0] = 0;
|
||||
heli_servo_out[1] = 0;
|
||||
heli_servo_out[2] = 0;
|
||||
heli_servo_out[3] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
|
||||
|
@ -128,31 +161,9 @@ static void output_motors_armed()
|
|||
if( heli_manual_override ) {
|
||||
// straight pass through from radio inputs to swash plate
|
||||
heli_move_swash( g.rc_1.control_in, g.rc_2.control_in, g.rc_3.radio_in, g.rc_4.control_in );
|
||||
|
||||
/*Serial.printf_P( PSTR("1: %d/%d \t2:%d/%d \t3:%d/%d \t4:%d/%d\n"),
|
||||
(int)g.rc_1.control_in, (int)g.rc_1.servo_out,
|
||||
(int)g.rc_2.control_in, (int)g.rc_2.servo_out,
|
||||
(int)g.rc_3.radio_in, (int)g.rc_3.servo_out,
|
||||
(int)g.rc_4.control_in, (int)g.rc_4.servo_out );*/
|
||||
}else{
|
||||
// collective pitch compensation for yaw/roll. This probably belongs somewhere else
|
||||
//Matrix3f temp = dcm.get_dcm_matrix();
|
||||
//rollPitch_impact_on_collective = 1.0 * (g.rc_3.radio_in-g.heli_coll_mid) * (1.0 - temp.c.z);
|
||||
//rollPitch_impact_on_collective = constrain(rollPitch_impact_on_collective,0,100);
|
||||
|
||||
/*counter++;
|
||||
if( counter > 20 ) {
|
||||
counter = 0;
|
||||
Serial.printf_P( PSTR("dcm:%f4.1\t rc3:%d\t cm:%d\t imp:%d\n"),
|
||||
temp.c.z,
|
||||
(int)g.rc_3.radio_in,
|
||||
(int)g.heli_coll_mid,
|
||||
(int)rollPitch_impact_on_collective );
|
||||
}*/
|
||||
|
||||
// source inputs from attitude controller (except for collective pitch)
|
||||
//heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_in + rollPitch_impact_on_collective, g.rc_4.servo_out ); // to allow control by PIDs except for collective
|
||||
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out ); // to allow control by PIDs except for collective
|
||||
// source inputs from attitude controller
|
||||
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out );
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -160,8 +171,7 @@ static void output_motors_armed()
|
|||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
// we have pushed up the throttle, remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
|
|
|
@ -485,6 +485,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|||
Serial.printf_P(PSTR("\tm\t\tset roll, pitch, coll min/max\n"));
|
||||
Serial.printf_P(PSTR("\tp<angle>\tset pos (i.e. p0 = front, p90 = right)\n"));
|
||||
Serial.printf_P(PSTR("\tr\t\treverse servo\n"));
|
||||
Serial.printf_P(PSTR("\tu a|d\t\tupdate rate (a=analog servo, d=digital)\n"));
|
||||
Serial.printf_P(PSTR("\tt<angle>\tset trim (-500 ~ 500)\n"));
|
||||
Serial.printf_P(PSTR("\tx\t\texit & save\n"));
|
||||
|
||||
|
@ -546,7 +547,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|||
case 'M':
|
||||
if( state == 0 ) {
|
||||
state = 1; // switch to capture min/max mode
|
||||
Serial.printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n"),active_servo+1, temp);
|
||||
Serial.printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n"));
|
||||
|
||||
// reset servo ranges
|
||||
g.heli_roll_max = g.heli_pitch_max = 4500;
|
||||
|
@ -611,6 +612,26 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|||
Serial.printf_P(PSTR("Servo %d\t\ttrim:%d\n"),active_servo+1, 1500 + temp);
|
||||
}
|
||||
break;
|
||||
case 'u':
|
||||
case 'U':
|
||||
temp = 0;
|
||||
// delay up to 2 seconds for servo type from user
|
||||
while( !Serial.available() && temp < 20 ) {
|
||||
temp++;
|
||||
delay(100);
|
||||
}
|
||||
if( Serial.available() ) {
|
||||
value = Serial.read();
|
||||
if( value == 'a' || value == 'A' ) {
|
||||
g.heli_servo_averaging = HELI_SERVO_AVERAGING_ANALOG;
|
||||
Serial.printf_P(PSTR("Analog Servo %dhz\n"),250 / HELI_SERVO_AVERAGING_ANALOG);
|
||||
}
|
||||
if( value == 'd' || value == 'D' ) {
|
||||
g.heli_servo_averaging = HELI_SERVO_AVERAGING_DIGITAL;
|
||||
Serial.printf_P(PSTR("Digital Servo 250hz\n"));
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 'z':
|
||||
case 'Z':
|
||||
heli_get_servo(active_servo)->radio_trim -= 10;
|
||||
|
@ -640,6 +661,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|||
g.heli_coll_min.save();
|
||||
g.heli_coll_max.save();
|
||||
g.heli_coll_mid.save();
|
||||
g.heli_servo_averaging.save();
|
||||
|
||||
// return swash plate movements to attitude controller
|
||||
heli_manual_override = false;
|
||||
|
@ -913,6 +935,8 @@ void report_optflow()
|
|||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static void report_heli()
|
||||
{
|
||||
int servo_rate;
|
||||
|
||||
Serial.printf_P(PSTR("Heli\n"));
|
||||
print_divider();
|
||||
|
||||
|
@ -926,6 +950,14 @@ static void report_heli()
|
|||
Serial.printf_P(PSTR("roll max: \t%d\n"), (int)g.heli_roll_max);
|
||||
Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)g.heli_pitch_max);
|
||||
Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_coll_min, (int)g.heli_coll_mid, (int)g.heli_coll_max);
|
||||
|
||||
// calculate and print servo rate
|
||||
if( g.heli_servo_averaging <= 1 ) {
|
||||
servo_rate = 250;
|
||||
} else {
|
||||
servo_rate = 250 / g.heli_servo_averaging;
|
||||
}
|
||||
Serial.printf_P(PSTR("servo rate:\t%d hz\n"),servo_rate);
|
||||
|
||||
print_blanks(2);
|
||||
}
|
||||
|
|
|
@ -73,7 +73,7 @@ static void read_radio()
|
|||
|
||||
// TO DO - go through and patch throttle reverse for RC_Channel library compatibility
|
||||
#if THROTTLE_REVERSE == 1
|
||||
radio_in[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_in[CH_THROTTLE];
|
||||
g.channel_throttle.radio_in = g.channel_throttle.radio_max + g.channel_throttle.radio_min - g.channel_throttle.radio_in;
|
||||
#endif
|
||||
|
||||
control_failsafe(g.channel_throttle.radio_in);
|
||||
|
|
|
@ -495,6 +495,10 @@
|
|||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Content Include="apm2.ico" />
|
||||
<Content Include="hud.html">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
<SubType>Designer</SubType>
|
||||
</Content>
|
||||
<Content Include="Resources\MAVCmd.zh-Hans.txt" />
|
||||
<Content Include="Resources\MAVParam.zh-Hans.txt" />
|
||||
<None Include="Resources\MAVCmd.txt" />
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000384 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001ba2 T loop
|
||||
00001c42 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000382 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001ba0 T loop
|
||||
00001c40 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -31,50 +33,49 @@ autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static'
|
|||
/root/apm/ardupilot-mega/ArduCopter/Log.pde:741: warning: 'void Log_Write_Attitude()' defined but not used
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:276: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:277: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:351: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:352: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -550,6 +551,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -595,13 +597,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000384 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
00000580 t __static_initialization_and_destruction_0(int, int)
|
||||
000005d6 t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000014fa T loop
|
||||
00001598 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -31,50 +33,49 @@ autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static'
|
|||
/root/apm/ardupilot-mega/ArduCopter/Log.pde:741: warning: 'void Log_Write_Attitude()' defined but not used
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:276: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:277: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:351: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:352: warning: 'old_altitude' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:370: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'baro_alt' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' 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
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -550,6 +551,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -595,13 +597,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000382 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
00000580 t __static_initialization_and_destruction_0(int, int)
|
||||
000005d6 t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000014f8 T loop
|
||||
00001596 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000384 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001a70 T loop
|
||||
00001b10 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000382 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001a6e T loop
|
||||
00001b0e T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -563,12 +564,13 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
0000010e t send_servo_out(mavlink_channel_t)
|
||||
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||
0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000384 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000019d0 T loop
|
||||
00001a70 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -563,12 +564,13 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
0000010e t send_servo_out(mavlink_channel_t)
|
||||
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||
0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000382 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000019ce T loop
|
||||
00001a6e T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000384 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001ab0 T loop
|
||||
00001b50 T loop
|
||||
|
|
|
@ -9,9 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:76:
|
|||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: statement has no effect
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:406: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:412: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:439: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:652: warning: unused variable 'temp'
|
||||
autogenerated: At global scope:
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
|
@ -28,40 +30,39 @@ autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' bu
|
|||
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:299: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:425: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:431: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:211: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:213: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:236: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:152: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:254: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:255: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:256: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:238: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
autogenerated:252: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:208: warning: 'int get_loiter_angle()' defined but not used
|
||||
autogenerated:256: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
|
||||
autogenerated:257: warning: 'long int cross_track_test()' declared 'static' but never defined
|
||||
autogenerated:258: warning: 'void reset_crosstrack()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:273: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:294: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:294: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
autogenerated:288: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:289: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:297: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/system.pde:448: 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:992: 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: 'new_location' defined but not used
|
||||
autogenerated:312: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:320: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:444: warning: 'undo_event' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'condition_rate' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:464: warning: 'simple_WP' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used
|
||||
/root/apm/ardupilot-mega/ArduCopter/control_modes.pde:48: warning: 'trim_flag' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 d jump
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
|
@ -562,6 +563,7 @@
|
|||
000000ea t Log_Read_Control_Tuning()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c t test_current(unsigned char, Menu::arg const*)
|
||||
|
@ -610,13 +612,13 @@
|
|||
00000354 t calc_nav_rate(int, int, int, int)
|
||||
00000382 t print_log_menu()
|
||||
000003a0 t read_battery()
|
||||
000003d2 T update_throttle_mode()
|
||||
00000410 T update_yaw_mode()
|
||||
0000049a t update_nav_wp()
|
||||
0000042c T update_throttle_mode()
|
||||
000005ee t init_ardupilot()
|
||||
000006e6 t update_nav_wp()
|
||||
000007b0 t __static_initialization_and_destruction_0(int, int)
|
||||
000007ea b g
|
||||
0000085a t process_next_command()
|
||||
0000089c W Parameters::Parameters()
|
||||
00000874 t process_next_command()
|
||||
00000894 W Parameters::Parameters()
|
||||
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001aae T loop
|
||||
00001b4e T loop
|
||||
|
|
|
@ -58,7 +58,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.44 Beta Quad</name>
|
||||
<name>ArduCopter V2.0.45 Beta Quad</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -69,7 +69,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.44 Beta Tri</name>
|
||||
<name>ArduCopter V2.0.45 Beta Tri</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG TRI_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -80,7 +80,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.44 Beta Hexa</name>
|
||||
<name>ArduCopter V2.0.45 Beta Hexa</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG HEXA_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -91,7 +91,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.44 Beta Y6</name>
|
||||
<name>ArduCopter V2.0.45 Beta Y6</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG Y6_FRAME
|
||||
#define FRAME_ORIENTATION X_FRAME
|
||||
|
@ -148,7 +148,7 @@
|
|||
<Firmware>
|
||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
|
||||
<name>ArduCopter V2.0.44 Beta Quad Hil</name>
|
||||
<name>ArduCopter V2.0.45 Beta Quad Hil</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION PLUS_FRAME
|
||||
|
|
|
@ -1,12 +1,14 @@
|
|||
From https://code.google.com/p/ardupilot-mega
|
||||
35e16dd..27704d4 APM_Camera -> origin/APM_Camera
|
||||
8b96023..787dacf master -> origin/master
|
||||
Updating 8b96023..787dacf
|
||||
27704d4..61a4415 APM_Camera -> origin/APM_Camera
|
||||
f7f1c0b..43c6a23 master -> origin/master
|
||||
Updating f7f1c0b..43c6a23
|
||||
Fast-forward
|
||||
ArduCopter/Mavlink_Common.h | 17 -----------------
|
||||
ArduCopter/commands_logic.pde | 18 ++++++++++++------
|
||||
ArduCopter/config.h | 4 ++--
|
||||
ArduPlane/GCS_Mavlink.pde | 10 ----------
|
||||
libraries/GCS_MAVLink/GCS_MAVLink.cpp | 9 +++++++++
|
||||
libraries/GCS_MAVLink/GCS_MAVLink.h | 2 ++
|
||||
6 files changed, 25 insertions(+), 35 deletions(-)
|
||||
ArduCopter/APM_Config.h | 5 +++-
|
||||
ArduCopter/ArduCopter.pde | 50 +++++++++++++++++++-----------------
|
||||
ArduCopter/Attitude.pde | 2 +-
|
||||
ArduCopter/commands_logic.pde | 44 ++++++++++++++++++++++++--------
|
||||
ArduCopter/config.h | 10 +++---
|
||||
ArduCopter/heli.pde | 7 ++++-
|
||||
ArduCopter/navigation.pde | 56 +++++++++++++++++++++++++++++++++++++++++
|
||||
ArduCopter/test.pde | 36 ++++++++++++++++++++++++++
|
||||
8 files changed, 167 insertions(+), 43 deletions(-)
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -6506,22 +6506,25 @@ GDI+ = Enabled</value>
|
|||
<data name="ConfigTabs.ItemSize" type="System.Drawing.Size, System.Drawing">
|
||||
<value>52, 18</value>
|
||||
</data>
|
||||
<metadata name="Default.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<data name="Default.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="$this.Localizable" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
</data>
|
||||
<data name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<metadata name="Value.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Value.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Command.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
</data>
|
||||
<data name="MAVParam" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
|
||||
</data>
|
||||
</root>
|
|
@ -131,7 +131,6 @@ namespace ArdupilotMega.GCSViews
|
|||
}
|
||||
}
|
||||
catch { }
|
||||
|
||||
}
|
||||
|
||||
void tabControl1_DrawItem(object sender, DrawItemEventArgs e)
|
||||
|
|
|
@ -132,7 +132,6 @@
|
|||
//
|
||||
resources.ApplyResources(this.CHK_altmode, "CHK_altmode");
|
||||
this.CHK_altmode.Name = "CHK_altmode";
|
||||
this.toolTip1.SetToolTip(this.CHK_altmode, resources.GetString("CHK_altmode.ToolTip"));
|
||||
this.CHK_altmode.UseVisualStyleBackColor = true;
|
||||
this.CHK_altmode.CheckedChanged += new System.EventHandler(this.CHK_altmode_CheckedChanged);
|
||||
//
|
||||
|
@ -142,13 +141,12 @@
|
|||
this.CHK_holdalt.Checked = true;
|
||||
this.CHK_holdalt.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHK_holdalt.Name = "CHK_holdalt";
|
||||
this.toolTip1.SetToolTip(this.CHK_holdalt, resources.GetString("CHK_holdalt.ToolTip"));
|
||||
this.CHK_holdalt.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// Commands
|
||||
//
|
||||
resources.ApplyResources(this.Commands, "Commands");
|
||||
this.Commands.AllowUserToAddRows = false;
|
||||
resources.ApplyResources(this.Commands, "Commands");
|
||||
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||
dataGridViewCellStyle1.BackColor = System.Drawing.SystemColors.Control;
|
||||
dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
|
@ -178,7 +176,6 @@
|
|||
this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle5;
|
||||
dataGridViewCellStyle6.ForeColor = System.Drawing.Color.Black;
|
||||
this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle6;
|
||||
this.toolTip1.SetToolTip(this.Commands, resources.GetString("Commands.ToolTip"));
|
||||
this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick);
|
||||
this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit);
|
||||
this.Commands.DefaultValuesNeeded += new System.Windows.Forms.DataGridViewRowEventHandler(this.Commands_DefaultValuesNeeded);
|
||||
|
@ -250,14 +247,12 @@
|
|||
//
|
||||
resources.ApplyResources(this.CHK_geheight, "CHK_geheight");
|
||||
this.CHK_geheight.Name = "CHK_geheight";
|
||||
this.toolTip1.SetToolTip(this.CHK_geheight, resources.GetString("CHK_geheight.ToolTip"));
|
||||
this.CHK_geheight.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// TXT_WPRad
|
||||
//
|
||||
resources.ApplyResources(this.TXT_WPRad, "TXT_WPRad");
|
||||
this.TXT_WPRad.Name = "TXT_WPRad";
|
||||
this.toolTip1.SetToolTip(this.TXT_WPRad, resources.GetString("TXT_WPRad.ToolTip"));
|
||||
this.TXT_WPRad.KeyPress += new System.Windows.Forms.KeyPressEventHandler(this.TXT_WPRad_KeyPress);
|
||||
this.TXT_WPRad.Leave += new System.EventHandler(this.TXT_WPRad_Leave);
|
||||
//
|
||||
|
@ -265,7 +260,6 @@
|
|||
//
|
||||
resources.ApplyResources(this.TXT_DefaultAlt, "TXT_DefaultAlt");
|
||||
this.TXT_DefaultAlt.Name = "TXT_DefaultAlt";
|
||||
this.toolTip1.SetToolTip(this.TXT_DefaultAlt, resources.GetString("TXT_DefaultAlt.ToolTip"));
|
||||
this.TXT_DefaultAlt.KeyPress += new System.Windows.Forms.KeyPressEventHandler(this.TXT_DefaultAlt_KeyPress);
|
||||
this.TXT_DefaultAlt.Leave += new System.EventHandler(this.TXT_DefaultAlt_Leave);
|
||||
//
|
||||
|
@ -273,19 +267,16 @@
|
|||
//
|
||||
resources.ApplyResources(this.LBL_WPRad, "LBL_WPRad");
|
||||
this.LBL_WPRad.Name = "LBL_WPRad";
|
||||
this.toolTip1.SetToolTip(this.LBL_WPRad, resources.GetString("LBL_WPRad.ToolTip"));
|
||||
//
|
||||
// LBL_defalutalt
|
||||
//
|
||||
resources.ApplyResources(this.LBL_defalutalt, "LBL_defalutalt");
|
||||
this.LBL_defalutalt.Name = "LBL_defalutalt";
|
||||
this.toolTip1.SetToolTip(this.LBL_defalutalt, resources.GetString("LBL_defalutalt.ToolTip"));
|
||||
//
|
||||
// TXT_loiterrad
|
||||
//
|
||||
resources.ApplyResources(this.TXT_loiterrad, "TXT_loiterrad");
|
||||
this.TXT_loiterrad.Name = "TXT_loiterrad";
|
||||
this.toolTip1.SetToolTip(this.TXT_loiterrad, resources.GetString("TXT_loiterrad.ToolTip"));
|
||||
this.TXT_loiterrad.KeyPress += new System.Windows.Forms.KeyPressEventHandler(this.TXT_loiterrad_KeyPress);
|
||||
this.TXT_loiterrad.Leave += new System.EventHandler(this.TXT_loiterrad_Leave);
|
||||
//
|
||||
|
@ -293,7 +284,6 @@
|
|||
//
|
||||
resources.ApplyResources(this.label5, "label5");
|
||||
this.label5.Name = "label5";
|
||||
this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip"));
|
||||
//
|
||||
// panel5
|
||||
//
|
||||
|
@ -303,41 +293,36 @@
|
|||
this.panel5.Controls.Add(this.SaveFile);
|
||||
this.panel5.Controls.Add(this.BUT_loadwpfile);
|
||||
this.panel5.Name = "panel5";
|
||||
this.toolTip1.SetToolTip(this.panel5, resources.GetString("panel5.ToolTip"));
|
||||
//
|
||||
// BUT_write
|
||||
//
|
||||
resources.ApplyResources(this.BUT_write, "BUT_write");
|
||||
this.BUT_write.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.BUT_write, "BUT_write");
|
||||
this.BUT_write.Name = "BUT_write";
|
||||
this.toolTip1.SetToolTip(this.BUT_write, resources.GetString("BUT_write.ToolTip"));
|
||||
this.BUT_write.UseVisualStyleBackColor = true;
|
||||
this.BUT_write.Click += new System.EventHandler(this.BUT_write_Click);
|
||||
//
|
||||
// BUT_read
|
||||
//
|
||||
resources.ApplyResources(this.BUT_read, "BUT_read");
|
||||
this.BUT_read.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.BUT_read, "BUT_read");
|
||||
this.BUT_read.Name = "BUT_read";
|
||||
this.toolTip1.SetToolTip(this.BUT_read, resources.GetString("BUT_read.ToolTip"));
|
||||
this.BUT_read.UseVisualStyleBackColor = true;
|
||||
this.BUT_read.Click += new System.EventHandler(this.BUT_read_Click);
|
||||
//
|
||||
// SaveFile
|
||||
//
|
||||
resources.ApplyResources(this.SaveFile, "SaveFile");
|
||||
this.SaveFile.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.SaveFile, "SaveFile");
|
||||
this.SaveFile.Name = "SaveFile";
|
||||
this.toolTip1.SetToolTip(this.SaveFile, resources.GetString("SaveFile.ToolTip"));
|
||||
this.SaveFile.UseVisualStyleBackColor = true;
|
||||
this.SaveFile.Click += new System.EventHandler(this.SaveFile_Click);
|
||||
//
|
||||
// BUT_loadwpfile
|
||||
//
|
||||
resources.ApplyResources(this.BUT_loadwpfile, "BUT_loadwpfile");
|
||||
this.BUT_loadwpfile.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.BUT_loadwpfile, "BUT_loadwpfile");
|
||||
this.BUT_loadwpfile.Name = "BUT_loadwpfile";
|
||||
this.toolTip1.SetToolTip(this.BUT_loadwpfile, resources.GetString("BUT_loadwpfile.ToolTip"));
|
||||
this.BUT_loadwpfile.UseVisualStyleBackColor = true;
|
||||
this.BUT_loadwpfile.Click += new System.EventHandler(this.BUT_loadwpfile_Click);
|
||||
//
|
||||
|
@ -352,53 +337,45 @@
|
|||
this.panel1.Controls.Add(this.TXT_homelng);
|
||||
this.panel1.Controls.Add(this.TXT_homelat);
|
||||
this.panel1.Name = "panel1";
|
||||
this.toolTip1.SetToolTip(this.panel1, resources.GetString("panel1.ToolTip"));
|
||||
//
|
||||
// label4
|
||||
//
|
||||
resources.ApplyResources(this.label4, "label4");
|
||||
this.label4.Name = "label4";
|
||||
this.label4.TabStop = true;
|
||||
this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip"));
|
||||
this.label4.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.label4_LinkClicked);
|
||||
//
|
||||
// label3
|
||||
//
|
||||
resources.ApplyResources(this.label3, "label3");
|
||||
this.label3.Name = "label3";
|
||||
this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip"));
|
||||
//
|
||||
// label2
|
||||
//
|
||||
resources.ApplyResources(this.label2, "label2");
|
||||
this.label2.Name = "label2";
|
||||
this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip"));
|
||||
//
|
||||
// Label1
|
||||
//
|
||||
resources.ApplyResources(this.Label1, "Label1");
|
||||
this.Label1.Name = "Label1";
|
||||
this.toolTip1.SetToolTip(this.Label1, resources.GetString("Label1.ToolTip"));
|
||||
//
|
||||
// TXT_homealt
|
||||
//
|
||||
resources.ApplyResources(this.TXT_homealt, "TXT_homealt");
|
||||
this.TXT_homealt.Name = "TXT_homealt";
|
||||
this.toolTip1.SetToolTip(this.TXT_homealt, resources.GetString("TXT_homealt.ToolTip"));
|
||||
this.TXT_homealt.TextChanged += new System.EventHandler(this.TXT_homealt_TextChanged);
|
||||
//
|
||||
// TXT_homelng
|
||||
//
|
||||
resources.ApplyResources(this.TXT_homelng, "TXT_homelng");
|
||||
this.TXT_homelng.Name = "TXT_homelng";
|
||||
this.toolTip1.SetToolTip(this.TXT_homelng, resources.GetString("TXT_homelng.ToolTip"));
|
||||
this.TXT_homelng.TextChanged += new System.EventHandler(this.TXT_homelng_TextChanged);
|
||||
//
|
||||
// TXT_homelat
|
||||
//
|
||||
resources.ApplyResources(this.TXT_homelat, "TXT_homelat");
|
||||
this.TXT_homelat.Name = "TXT_homelat";
|
||||
this.toolTip1.SetToolTip(this.TXT_homelat, resources.GetString("TXT_homelat.ToolTip"));
|
||||
this.TXT_homelat.TextChanged += new System.EventHandler(this.TXT_homelat_TextChanged);
|
||||
this.TXT_homelat.Enter += new System.EventHandler(this.TXT_homelat_Enter);
|
||||
//
|
||||
|
@ -424,7 +401,6 @@
|
|||
//
|
||||
resources.ApplyResources(this.label6, "label6");
|
||||
this.label6.Name = "label6";
|
||||
this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip"));
|
||||
//
|
||||
// panel2
|
||||
//
|
||||
|
@ -437,49 +413,41 @@
|
|||
this.panel2.Controls.Add(this.TXT_mouselong);
|
||||
this.panel2.Controls.Add(this.TXT_mouselat);
|
||||
this.panel2.Name = "panel2";
|
||||
this.toolTip1.SetToolTip(this.panel2, resources.GetString("panel2.ToolTip"));
|
||||
//
|
||||
// label7
|
||||
//
|
||||
resources.ApplyResources(this.label7, "label7");
|
||||
this.label7.Name = "label7";
|
||||
this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip"));
|
||||
//
|
||||
// label8
|
||||
//
|
||||
resources.ApplyResources(this.label8, "label8");
|
||||
this.label8.Name = "label8";
|
||||
this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip"));
|
||||
//
|
||||
// label9
|
||||
//
|
||||
resources.ApplyResources(this.label9, "label9");
|
||||
this.label9.Name = "label9";
|
||||
this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip"));
|
||||
//
|
||||
// label10
|
||||
//
|
||||
resources.ApplyResources(this.label10, "label10");
|
||||
this.label10.Name = "label10";
|
||||
this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip"));
|
||||
//
|
||||
// TXT_mousealt
|
||||
//
|
||||
resources.ApplyResources(this.TXT_mousealt, "TXT_mousealt");
|
||||
this.TXT_mousealt.Name = "TXT_mousealt";
|
||||
this.toolTip1.SetToolTip(this.TXT_mousealt, resources.GetString("TXT_mousealt.ToolTip"));
|
||||
//
|
||||
// TXT_mouselong
|
||||
//
|
||||
resources.ApplyResources(this.TXT_mouselong, "TXT_mouselong");
|
||||
this.TXT_mouselong.Name = "TXT_mouselong";
|
||||
this.toolTip1.SetToolTip(this.TXT_mouselong, resources.GetString("TXT_mouselong.ToolTip"));
|
||||
//
|
||||
// TXT_mouselat
|
||||
//
|
||||
resources.ApplyResources(this.TXT_mouselat, "TXT_mouselat");
|
||||
this.TXT_mouselat.Name = "TXT_mouselat";
|
||||
this.toolTip1.SetToolTip(this.TXT_mouselat, resources.GetString("TXT_mouselat.ToolTip"));
|
||||
//
|
||||
// comboBoxMapType
|
||||
//
|
||||
|
@ -493,17 +461,14 @@
|
|||
//
|
||||
resources.ApplyResources(this.lbl_status, "lbl_status");
|
||||
this.lbl_status.Name = "lbl_status";
|
||||
this.toolTip1.SetToolTip(this.lbl_status, resources.GetString("lbl_status.ToolTip"));
|
||||
//
|
||||
// textBox1
|
||||
//
|
||||
resources.ApplyResources(this.textBox1, "textBox1");
|
||||
this.textBox1.Name = "textBox1";
|
||||
this.toolTip1.SetToolTip(this.textBox1, resources.GetString("textBox1.ToolTip"));
|
||||
//
|
||||
// panelWaypoints
|
||||
//
|
||||
resources.ApplyResources(this.panelWaypoints, "panelWaypoints");
|
||||
this.panelWaypoints.AssociatedSplitter = this.splitter1;
|
||||
this.panelWaypoints.BackColor = System.Drawing.Color.Transparent;
|
||||
this.panelWaypoints.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold);
|
||||
|
@ -536,6 +501,7 @@
|
|||
this.panelWaypoints.CustomColors.ContentGradientBegin = System.Drawing.SystemColors.ButtonFace;
|
||||
this.panelWaypoints.CustomColors.ContentGradientEnd = System.Drawing.Color.FromArgb(((int)(((byte)(252)))), ((int)(((byte)(252)))), ((int)(((byte)(252)))));
|
||||
this.panelWaypoints.CustomColors.InnerBorderColor = System.Drawing.SystemColors.Window;
|
||||
resources.ApplyResources(this.panelWaypoints, "panelWaypoints");
|
||||
this.panelWaypoints.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
this.panelWaypoints.Image = null;
|
||||
this.panelWaypoints.LinearGradientMode = System.Drawing.Drawing2D.LinearGradientMode.Vertical;
|
||||
|
@ -543,18 +509,16 @@
|
|||
this.panelWaypoints.Name = "panelWaypoints";
|
||||
this.panelWaypoints.PanelStyle = BSE.Windows.Forms.PanelStyle.Default;
|
||||
this.panelWaypoints.ShowExpandIcon = true;
|
||||
this.toolTip1.SetToolTip(this.panelWaypoints, resources.GetString("panelWaypoints.ToolTip"));
|
||||
this.panelWaypoints.ToolTipTextCloseIcon = null;
|
||||
this.panelWaypoints.ToolTipTextExpandIconPanelCollapsed = null;
|
||||
this.panelWaypoints.ToolTipTextExpandIconPanelExpanded = null;
|
||||
//
|
||||
// splitter1
|
||||
//
|
||||
resources.ApplyResources(this.splitter1, "splitter1");
|
||||
this.splitter1.BackColor = System.Drawing.Color.Transparent;
|
||||
resources.ApplyResources(this.splitter1, "splitter1");
|
||||
this.splitter1.Name = "splitter1";
|
||||
this.splitter1.TabStop = false;
|
||||
this.toolTip1.SetToolTip(this.splitter1, resources.GetString("splitter1.ToolTip"));
|
||||
//
|
||||
// BUT_grid
|
||||
//
|
||||
|
@ -574,8 +538,8 @@
|
|||
//
|
||||
// button1
|
||||
//
|
||||
resources.ApplyResources(this.button1, "button1");
|
||||
this.button1.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.button1, "button1");
|
||||
this.button1.Name = "button1";
|
||||
this.toolTip1.SetToolTip(this.button1, resources.GetString("button1.ToolTip"));
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
|
@ -583,8 +547,8 @@
|
|||
//
|
||||
// BUT_Add
|
||||
//
|
||||
resources.ApplyResources(this.BUT_Add, "BUT_Add");
|
||||
this.BUT_Add.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
resources.ApplyResources(this.BUT_Add, "BUT_Add");
|
||||
this.BUT_Add.Name = "BUT_Add";
|
||||
this.toolTip1.SetToolTip(this.BUT_Add, resources.GetString("BUT_Add.ToolTip"));
|
||||
this.BUT_Add.UseVisualStyleBackColor = true;
|
||||
|
@ -592,7 +556,6 @@
|
|||
//
|
||||
// panelAction
|
||||
//
|
||||
resources.ApplyResources(this.panelAction, "panelAction");
|
||||
this.panelAction.AssociatedSplitter = null;
|
||||
this.panelAction.BackColor = System.Drawing.Color.Transparent;
|
||||
this.panelAction.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold);
|
||||
|
@ -617,6 +580,7 @@
|
|||
this.panelAction.CustomColors.ContentGradientBegin = System.Drawing.SystemColors.ButtonFace;
|
||||
this.panelAction.CustomColors.ContentGradientEnd = System.Drawing.Color.FromArgb(((int)(((byte)(252)))), ((int)(((byte)(252)))), ((int)(((byte)(252)))));
|
||||
this.panelAction.CustomColors.InnerBorderColor = System.Drawing.SystemColors.Window;
|
||||
resources.ApplyResources(this.panelAction, "panelAction");
|
||||
this.panelAction.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
this.panelAction.Image = null;
|
||||
this.panelAction.LinearGradientMode = System.Drawing.Drawing2D.LinearGradientMode.Vertical;
|
||||
|
@ -624,7 +588,6 @@
|
|||
this.panelAction.Name = "panelAction";
|
||||
this.panelAction.PanelStyle = BSE.Windows.Forms.PanelStyle.Default;
|
||||
this.panelAction.ShowExpandIcon = true;
|
||||
this.toolTip1.SetToolTip(this.panelAction, resources.GetString("panelAction.ToolTip"));
|
||||
this.panelAction.ToolTipTextCloseIcon = null;
|
||||
this.panelAction.ToolTipTextExpandIconPanelCollapsed = null;
|
||||
this.panelAction.ToolTipTextExpandIconPanelExpanded = null;
|
||||
|
@ -632,7 +595,6 @@
|
|||
//
|
||||
// panelMap
|
||||
//
|
||||
resources.ApplyResources(this.panelMap, "panelMap");
|
||||
this.panelMap.BackColor = System.Drawing.Color.Transparent;
|
||||
this.panelMap.Controls.Add(this.lbl_distance);
|
||||
this.panelMap.Controls.Add(this.lbl_homedist);
|
||||
|
@ -640,31 +602,28 @@
|
|||
this.panelMap.Controls.Add(this.MainMap);
|
||||
this.panelMap.Controls.Add(this.trackBar1);
|
||||
this.panelMap.Controls.Add(this.label11);
|
||||
resources.ApplyResources(this.panelMap, "panelMap");
|
||||
this.panelMap.ForeColor = System.Drawing.SystemColors.ControlText;
|
||||
this.panelMap.MinimumSize = new System.Drawing.Size(27, 27);
|
||||
this.panelMap.Name = "panelMap";
|
||||
this.toolTip1.SetToolTip(this.panelMap, resources.GetString("panelMap.ToolTip"));
|
||||
//
|
||||
// lbl_distance
|
||||
//
|
||||
resources.ApplyResources(this.lbl_distance, "lbl_distance");
|
||||
this.lbl_distance.ForeColor = System.Drawing.Color.White;
|
||||
this.lbl_distance.Name = "lbl_distance";
|
||||
this.toolTip1.SetToolTip(this.lbl_distance, resources.GetString("lbl_distance.ToolTip"));
|
||||
//
|
||||
// lbl_homedist
|
||||
//
|
||||
resources.ApplyResources(this.lbl_homedist, "lbl_homedist");
|
||||
this.lbl_homedist.ForeColor = System.Drawing.Color.White;
|
||||
this.lbl_homedist.Name = "lbl_homedist";
|
||||
this.toolTip1.SetToolTip(this.lbl_homedist, resources.GetString("lbl_homedist.ToolTip"));
|
||||
//
|
||||
// lbl_prevdist
|
||||
//
|
||||
resources.ApplyResources(this.lbl_prevdist, "lbl_prevdist");
|
||||
this.lbl_prevdist.ForeColor = System.Drawing.Color.White;
|
||||
this.lbl_prevdist.Name = "lbl_prevdist";
|
||||
this.toolTip1.SetToolTip(this.lbl_prevdist, resources.GetString("lbl_prevdist.ToolTip"));
|
||||
//
|
||||
// MainMap
|
||||
//
|
||||
|
@ -687,12 +646,10 @@
|
|||
this.MainMap.RoutesEnabled = false;
|
||||
this.MainMap.ShowTileGridLines = false;
|
||||
this.MainMap.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("MainMap.streamjpg")));
|
||||
this.toolTip1.SetToolTip(this.MainMap, resources.GetString("MainMap.ToolTip"));
|
||||
this.MainMap.Zoom = 0D;
|
||||
//
|
||||
// contextMenuStrip1
|
||||
//
|
||||
resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1");
|
||||
this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.deleteWPToolStripMenuItem,
|
||||
this.loiterToolStripMenuItem,
|
||||
|
@ -703,102 +660,102 @@
|
|||
this.gridToolStripMenuItem,
|
||||
this.clearMissionToolStripMenuItem});
|
||||
this.contextMenuStrip1.Name = "contextMenuStrip1";
|
||||
this.toolTip1.SetToolTip(this.contextMenuStrip1, resources.GetString("contextMenuStrip1.ToolTip"));
|
||||
resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1");
|
||||
//
|
||||
// deleteWPToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.deleteWPToolStripMenuItem, "deleteWPToolStripMenuItem");
|
||||
this.deleteWPToolStripMenuItem.Name = "deleteWPToolStripMenuItem";
|
||||
resources.ApplyResources(this.deleteWPToolStripMenuItem, "deleteWPToolStripMenuItem");
|
||||
this.deleteWPToolStripMenuItem.Click += new System.EventHandler(this.deleteWPToolStripMenuItem_Click);
|
||||
//
|
||||
// loiterToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.loiterToolStripMenuItem, "loiterToolStripMenuItem");
|
||||
this.loiterToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.loiterForeverToolStripMenuItem,
|
||||
this.loitertimeToolStripMenuItem,
|
||||
this.loitercirclesToolStripMenuItem});
|
||||
this.loiterToolStripMenuItem.Name = "loiterToolStripMenuItem";
|
||||
resources.ApplyResources(this.loiterToolStripMenuItem, "loiterToolStripMenuItem");
|
||||
//
|
||||
// loiterForeverToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.loiterForeverToolStripMenuItem, "loiterForeverToolStripMenuItem");
|
||||
this.loiterForeverToolStripMenuItem.Name = "loiterForeverToolStripMenuItem";
|
||||
resources.ApplyResources(this.loiterForeverToolStripMenuItem, "loiterForeverToolStripMenuItem");
|
||||
this.loiterForeverToolStripMenuItem.Click += new System.EventHandler(this.loiterForeverToolStripMenuItem_Click);
|
||||
//
|
||||
// loitertimeToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.loitertimeToolStripMenuItem, "loitertimeToolStripMenuItem");
|
||||
this.loitertimeToolStripMenuItem.Name = "loitertimeToolStripMenuItem";
|
||||
resources.ApplyResources(this.loitertimeToolStripMenuItem, "loitertimeToolStripMenuItem");
|
||||
this.loitertimeToolStripMenuItem.Click += new System.EventHandler(this.loitertimeToolStripMenuItem_Click);
|
||||
//
|
||||
// loitercirclesToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.loitercirclesToolStripMenuItem, "loitercirclesToolStripMenuItem");
|
||||
this.loitercirclesToolStripMenuItem.Name = "loitercirclesToolStripMenuItem";
|
||||
resources.ApplyResources(this.loitercirclesToolStripMenuItem, "loitercirclesToolStripMenuItem");
|
||||
this.loitercirclesToolStripMenuItem.Click += new System.EventHandler(this.loitercirclesToolStripMenuItem_Click);
|
||||
//
|
||||
// jumpToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.jumpToolStripMenuItem, "jumpToolStripMenuItem");
|
||||
this.jumpToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.jumpstartToolStripMenuItem,
|
||||
this.jumpwPToolStripMenuItem});
|
||||
this.jumpToolStripMenuItem.Name = "jumpToolStripMenuItem";
|
||||
resources.ApplyResources(this.jumpToolStripMenuItem, "jumpToolStripMenuItem");
|
||||
//
|
||||
// jumpstartToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.jumpstartToolStripMenuItem, "jumpstartToolStripMenuItem");
|
||||
this.jumpstartToolStripMenuItem.Name = "jumpstartToolStripMenuItem";
|
||||
resources.ApplyResources(this.jumpstartToolStripMenuItem, "jumpstartToolStripMenuItem");
|
||||
this.jumpstartToolStripMenuItem.Click += new System.EventHandler(this.jumpstartToolStripMenuItem_Click);
|
||||
//
|
||||
// jumpwPToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.jumpwPToolStripMenuItem, "jumpwPToolStripMenuItem");
|
||||
this.jumpwPToolStripMenuItem.Name = "jumpwPToolStripMenuItem";
|
||||
resources.ApplyResources(this.jumpwPToolStripMenuItem, "jumpwPToolStripMenuItem");
|
||||
this.jumpwPToolStripMenuItem.Click += new System.EventHandler(this.jumpwPToolStripMenuItem_Click);
|
||||
//
|
||||
// toolStripSeparator1
|
||||
//
|
||||
resources.ApplyResources(this.toolStripSeparator1, "toolStripSeparator1");
|
||||
this.toolStripSeparator1.Name = "toolStripSeparator1";
|
||||
resources.ApplyResources(this.toolStripSeparator1, "toolStripSeparator1");
|
||||
//
|
||||
// ContextMeasure
|
||||
//
|
||||
resources.ApplyResources(this.ContextMeasure, "ContextMeasure");
|
||||
this.ContextMeasure.Name = "ContextMeasure";
|
||||
resources.ApplyResources(this.ContextMeasure, "ContextMeasure");
|
||||
this.ContextMeasure.Click += new System.EventHandler(this.ContextMeasure_Click);
|
||||
//
|
||||
// rotateMapToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.rotateMapToolStripMenuItem, "rotateMapToolStripMenuItem");
|
||||
this.rotateMapToolStripMenuItem.Name = "rotateMapToolStripMenuItem";
|
||||
resources.ApplyResources(this.rotateMapToolStripMenuItem, "rotateMapToolStripMenuItem");
|
||||
this.rotateMapToolStripMenuItem.Click += new System.EventHandler(this.rotateMapToolStripMenuItem_Click);
|
||||
//
|
||||
// gridToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.gridToolStripMenuItem, "gridToolStripMenuItem");
|
||||
this.gridToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.addPolygonPointToolStripMenuItem,
|
||||
this.clearPolygonToolStripMenuItem});
|
||||
this.gridToolStripMenuItem.Name = "gridToolStripMenuItem";
|
||||
resources.ApplyResources(this.gridToolStripMenuItem, "gridToolStripMenuItem");
|
||||
//
|
||||
// addPolygonPointToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.addPolygonPointToolStripMenuItem, "addPolygonPointToolStripMenuItem");
|
||||
this.addPolygonPointToolStripMenuItem.Name = "addPolygonPointToolStripMenuItem";
|
||||
resources.ApplyResources(this.addPolygonPointToolStripMenuItem, "addPolygonPointToolStripMenuItem");
|
||||
this.addPolygonPointToolStripMenuItem.Click += new System.EventHandler(this.addPolygonPointToolStripMenuItem_Click);
|
||||
//
|
||||
// clearPolygonToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.clearPolygonToolStripMenuItem, "clearPolygonToolStripMenuItem");
|
||||
this.clearPolygonToolStripMenuItem.Name = "clearPolygonToolStripMenuItem";
|
||||
resources.ApplyResources(this.clearPolygonToolStripMenuItem, "clearPolygonToolStripMenuItem");
|
||||
this.clearPolygonToolStripMenuItem.Click += new System.EventHandler(this.clearPolygonToolStripMenuItem_Click);
|
||||
//
|
||||
// clearMissionToolStripMenuItem
|
||||
//
|
||||
resources.ApplyResources(this.clearMissionToolStripMenuItem, "clearMissionToolStripMenuItem");
|
||||
this.clearMissionToolStripMenuItem.Name = "clearMissionToolStripMenuItem";
|
||||
resources.ApplyResources(this.clearMissionToolStripMenuItem, "clearMissionToolStripMenuItem");
|
||||
this.clearMissionToolStripMenuItem.Click += new System.EventHandler(this.clearMissionToolStripMenuItem_Click);
|
||||
//
|
||||
// trackBar1
|
||||
|
@ -812,7 +769,6 @@
|
|||
this.trackBar1.SmallChange = 50;
|
||||
this.trackBar1.TickFrequency = 100;
|
||||
this.trackBar1.TickStyle = System.Windows.Forms.TickStyle.TopLeft;
|
||||
this.toolTip1.SetToolTip(this.trackBar1, resources.GetString("trackBar1.ToolTip"));
|
||||
this.trackBar1.Value = 2D;
|
||||
this.trackBar1.Scroll += new System.EventHandler(this.trackBar1_Scroll);
|
||||
//
|
||||
|
@ -821,18 +777,16 @@
|
|||
resources.ApplyResources(this.label11, "label11");
|
||||
this.label11.ForeColor = System.Drawing.Color.White;
|
||||
this.label11.Name = "label11";
|
||||
this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip"));
|
||||
//
|
||||
// panelBASE
|
||||
//
|
||||
resources.ApplyResources(this.panelBASE, "panelBASE");
|
||||
this.panelBASE.Controls.Add(this.splitter1);
|
||||
this.panelBASE.Controls.Add(this.panelMap);
|
||||
this.panelBASE.Controls.Add(this.panelWaypoints);
|
||||
this.panelBASE.Controls.Add(this.panelAction);
|
||||
this.panelBASE.Controls.Add(this.label6);
|
||||
resources.ApplyResources(this.panelBASE, "panelBASE");
|
||||
this.panelBASE.Name = "panelBASE";
|
||||
this.toolTip1.SetToolTip(this.panelBASE, resources.GetString("panelBASE.ToolTip"));
|
||||
//
|
||||
// FlightPlanner
|
||||
//
|
||||
|
@ -842,7 +796,6 @@
|
|||
this.Controls.Add(this.panelBASE);
|
||||
this.MinimumSize = new System.Drawing.Size(1008, 461);
|
||||
this.Name = "FlightPlanner";
|
||||
this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip"));
|
||||
this.Load += new System.EventHandler(this.Planner_Load);
|
||||
this.Resize += new System.EventHandler(this.Planner_Resize);
|
||||
((System.ComponentModel.ISupportInitialize)(this.Commands)).EndInit();
|
||||
|
|
|
@ -2107,37 +2107,40 @@
|
|||
<data name="Delete.ToolTipText" xml:space="preserve">
|
||||
<value>Delete the row</value>
|
||||
</data>
|
||||
<metadata name="Down.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<data name="Down.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Param1.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Param1.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Command.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Param3.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Param3.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="contextMenuStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
</data>
|
||||
<data name="contextMenuStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<metadata name="Param4.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Param4.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Delete.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Delete.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="$this.Localizable" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Param2.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Param2.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
</data>
|
||||
<data name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing">
|
||||
<value>172, 17</value>
|
||||
</metadata>
|
||||
<metadata name="Up.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
</data>
|
||||
<data name="Up.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
</data>
|
||||
<data name="MAVCmd" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\MAVCmd.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
|
||||
</data>
|
||||
</root>
|
|
@ -322,6 +322,21 @@ namespace ArdupilotMega
|
|||
lastpos = (position[positionindex][position[positionindex].Count - 1]);
|
||||
lastline = line;
|
||||
}
|
||||
if (items[0].Contains("GPS") && items[4] != "0" && items[4] != "-1")
|
||||
{
|
||||
if (position[positionindex] == null)
|
||||
position[positionindex] = new List<Point3D>();
|
||||
|
||||
MainV2.cs.firmware = MainV2.Firmwares.ArduCopter2;
|
||||
|
||||
double alt = double.Parse(items[5], new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
position[positionindex].Add(new Point3D(double.Parse(items[4], new System.Globalization.CultureInfo("en-US")), double.Parse(items[3], new System.Globalization.CultureInfo("en-US")), alt));
|
||||
oldlastpos = lastpos;
|
||||
lastpos = (position[positionindex][position[positionindex].Count - 1]);
|
||||
lastline = line;
|
||||
|
||||
}
|
||||
if (items[0].Contains("CTUN"))
|
||||
{
|
||||
ctunlast = items;
|
||||
|
|
|
@ -33,6 +33,7 @@ namespace ArdupilotMega
|
|||
bool oldlogformat = false;
|
||||
|
||||
byte mavlinkversion = 0;
|
||||
byte[] readingpacket = new byte[256];
|
||||
|
||||
public PointLatLngAlt[] wps = new PointLatLngAlt[200];
|
||||
|
||||
|
@ -526,6 +527,8 @@ namespace ArdupilotMega
|
|||
continue;
|
||||
}
|
||||
|
||||
modifyParamForDisplay(true, st, ref par.param_value);
|
||||
|
||||
param[st] = (par.param_value);
|
||||
|
||||
MainV2.givecomport = false;
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.Runtime.InteropServices;
|
||||
|
||||
namespace ArdupilotMega
|
||||
|
|
|
@ -1162,79 +1162,102 @@ namespace ArdupilotMega
|
|||
//url = url.Replace(" HTTP/1.0", "");
|
||||
//url = url.Replace(" HTTP/1.1", "");
|
||||
|
||||
string header = "HTTP/1.1 200 OK\r\nContent-Type: multipart/x-mixed-replace;boundary=APMPLANNER\n\n--APMPLANNER\r\n";
|
||||
byte[] temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
while (client.Connected)
|
||||
if (url.Contains("websocket"))
|
||||
{
|
||||
System.Threading.Thread.Sleep(200); // 5hz
|
||||
byte[] data = null;
|
||||
|
||||
if (url.ToLower().Contains("hud"))
|
||||
using (var writer = new StreamWriter(stream))
|
||||
{
|
||||
GCSViews.FlightData.myhud.streamjpgenable = true;
|
||||
data = GCSViews.FlightData.myhud.streamjpg.ToArray();
|
||||
writer.WriteLine("HTTP/1.1 101 Web Socket Protocol Handshake");
|
||||
writer.WriteLine("Upgrade: WebSocket");
|
||||
writer.WriteLine("Connection: Upgrade");
|
||||
writer.WriteLine("WebSocket-Origin: http://localhost:56781/");
|
||||
writer.WriteLine("WebSocket-Location: ws://localhost:56781/websocket/server");
|
||||
writer.WriteLine("");
|
||||
|
||||
while (client.Connected)
|
||||
{
|
||||
System.Threading.Thread.Sleep(200);
|
||||
Console.WriteLine(stream.DataAvailable + " " + client.Available);
|
||||
stream.WriteByte(0x00);
|
||||
writer.WriteLine("test from planner");
|
||||
stream.WriteByte(0xff);
|
||||
|
||||
//break;
|
||||
}
|
||||
|
||||
stream.WriteByte(0x00);
|
||||
//message
|
||||
stream.WriteByte(0xff);
|
||||
}
|
||||
else if (url.ToLower().Contains("map"))
|
||||
{
|
||||
GCSViews.FlightData.mymap.streamjpgenable = true;
|
||||
data = GCSViews.FlightData.mymap.streamjpg.ToArray();
|
||||
} else if (url.Contains(".html")) {
|
||||
BinaryReader file = new BinaryReader(File.Open("hud.html",FileMode.Open,FileAccess.Read,FileShare.Read));
|
||||
byte[] buffer = new byte[1024];
|
||||
while (file.PeekChar() != -1) {
|
||||
|
||||
int leng = file.Read(buffer,0,buffer.Length);
|
||||
|
||||
stream.Write(buffer,0,leng);
|
||||
}
|
||||
else
|
||||
{
|
||||
GCSViews.FlightData.mymap.streamjpgenable = true;
|
||||
GCSViews.FlightData.myhud.streamjpgenable = true;
|
||||
Image img1 = Image.FromStream(GCSViews.FlightData.myhud.streamjpg);
|
||||
Image img2 = Image.FromStream(GCSViews.FlightData.mymap.streamjpg);
|
||||
int bigger = img1.Height > img2.Height ? img1.Height : img2.Height;
|
||||
Image imgout = new Bitmap(img1.Width + img2.Width, bigger);
|
||||
|
||||
Graphics grap = Graphics.FromImage(imgout);
|
||||
|
||||
grap.DrawImageUnscaled(img1, 0, 0);
|
||||
grap.DrawImageUnscaled(img2, img1.Width, 0);
|
||||
|
||||
MemoryStream streamjpg = new MemoryStream();
|
||||
imgout.Save(streamjpg, System.Drawing.Imaging.ImageFormat.Jpeg);
|
||||
data = streamjpg.ToArray();
|
||||
|
||||
}
|
||||
|
||||
header = "Content-Type: image/jpeg\r\nContent-Length: " + data.Length + "\r\n\r\n";
|
||||
temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
stream.Write(data, 0, data.Length);
|
||||
|
||||
header = "\r\n--APMPLANNER\r\n";
|
||||
temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
file.Close();
|
||||
stream.Close();
|
||||
}
|
||||
GCSViews.FlightData.mymap.streamjpgenable = false;
|
||||
GCSViews.FlightData.myhud.streamjpgenable = false;
|
||||
/*
|
||||
while (client.Connected)
|
||||
else if (url.ToLower().Contains("hud") || url.ToLower().Contains("map"))
|
||||
{
|
||||
|
||||
byte[] data = GCSViews.FlightData.myhud.streamjpg.ToArray();
|
||||
|
||||
byte[] request = new byte[1024];
|
||||
|
||||
int len = stream.Read(request, 0, request.Length);
|
||||
Console.WriteLine(System.Text.ASCIIEncoding.ASCII.GetString(request, 0, len));
|
||||
|
||||
string header = "HTTP/1.1 200 OK\nContent-Length: " + data.Length + "\nContent-Type: image/jpeg\n\n";
|
||||
string header = "HTTP/1.1 200 OK\r\nContent-Type: multipart/x-mixed-replace;boundary=APMPLANNER\n\n--APMPLANNER\r\n";
|
||||
byte[] temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
stream.Write(data, 0, data.Length);
|
||||
while (client.Connected)
|
||||
{
|
||||
System.Threading.Thread.Sleep(200); // 5hz
|
||||
byte[] data = null;
|
||||
|
||||
if (url.ToLower().Contains("hud"))
|
||||
{
|
||||
GCSViews.FlightData.myhud.streamjpgenable = true;
|
||||
data = GCSViews.FlightData.myhud.streamjpg.ToArray();
|
||||
}
|
||||
else if (url.ToLower().Contains("map"))
|
||||
{
|
||||
GCSViews.FlightData.mymap.streamjpgenable = true;
|
||||
data = GCSViews.FlightData.mymap.streamjpg.ToArray();
|
||||
}
|
||||
else
|
||||
{
|
||||
GCSViews.FlightData.mymap.streamjpgenable = true;
|
||||
GCSViews.FlightData.myhud.streamjpgenable = true;
|
||||
Image img1 = Image.FromStream(GCSViews.FlightData.myhud.streamjpg);
|
||||
Image img2 = Image.FromStream(GCSViews.FlightData.mymap.streamjpg);
|
||||
int bigger = img1.Height > img2.Height ? img1.Height : img2.Height;
|
||||
Image imgout = new Bitmap(img1.Width + img2.Width, bigger);
|
||||
|
||||
Graphics grap = Graphics.FromImage(imgout);
|
||||
|
||||
grap.DrawImageUnscaled(img1, 0, 0);
|
||||
grap.DrawImageUnscaled(img2, img1.Width, 0);
|
||||
|
||||
MemoryStream streamjpg = new MemoryStream();
|
||||
imgout.Save(streamjpg, System.Drawing.Imaging.ImageFormat.Jpeg);
|
||||
data = streamjpg.ToArray();
|
||||
|
||||
}
|
||||
|
||||
header = "Content-Type: image/jpeg\r\nContent-Length: " + data.Length + "\r\n\r\n";
|
||||
temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
stream.Write(data, 0, data.Length);
|
||||
|
||||
header = "\r\n--APMPLANNER\r\n";
|
||||
temp = encoding.GetBytes(header);
|
||||
stream.Write(temp, 0, temp.Length);
|
||||
|
||||
}
|
||||
GCSViews.FlightData.mymap.streamjpgenable = false;
|
||||
GCSViews.FlightData.myhud.streamjpgenable = false;
|
||||
stream.Close();
|
||||
|
||||
}
|
||||
*/
|
||||
stream.Close();
|
||||
|
||||
}
|
||||
catch (Exception ee) { Console.WriteLine("Failed mjpg " + ee.Message); }
|
||||
}
|
||||
|
|
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.0.75")]
|
||||
[assembly: AssemblyFileVersion("1.0.76")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
|
|
@ -248,6 +248,20 @@ namespace ArdupilotMega.Setup
|
|||
|
||||
private void tabControl1_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (tabControl1.SelectedTab == tabRadioIn)
|
||||
{
|
||||
startup = true;
|
||||
try
|
||||
{
|
||||
CHK_revch1.Checked = MainV2.comPort.param["RC1_REV"].ToString() == "-1";
|
||||
CHK_revch2.Checked = MainV2.comPort.param["RC2_REV"].ToString() == "-1";
|
||||
CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
|
||||
CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
|
||||
}
|
||||
catch { MessageBox.Show("Missing RC rev Param"); }
|
||||
startup = false;
|
||||
}
|
||||
|
||||
if (tabControl1.SelectedTab == tabModes)
|
||||
{
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
||||
|
@ -280,7 +294,8 @@ namespace ArdupilotMega.Setup
|
|||
CMB_fmode3.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
|
||||
CMB_fmode4.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
|
||||
CMB_fmode5.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
|
||||
CMB_fmode6.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE6"].ToString()).ToString();
|
||||
CMB_fmode6.Text = Common.apmmodes.MANUAL.ToString();
|
||||
CMB_fmode6.Enabled = false;
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
@ -308,6 +323,7 @@ namespace ArdupilotMega.Setup
|
|||
CMB_fmode4.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
|
||||
CMB_fmode5.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
|
||||
CMB_fmode6.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE6"].ToString()).ToString();
|
||||
CMB_fmode6.Enabled = true;
|
||||
|
||||
int simple = int.Parse(MainV2.comPort.param["SIMPLE"].ToString());
|
||||
|
||||
|
@ -1034,6 +1050,17 @@ namespace ArdupilotMega.Setup
|
|||
|
||||
void reverseChannel(string name,bool normalreverse,Control progressbar)
|
||||
{
|
||||
if (normalreverse == true)
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(148, 193, 31);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
else
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(148, 193, 31);
|
||||
}
|
||||
|
||||
if (startup)
|
||||
return;
|
||||
if (MainV2.comPort.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.param["SWITCH_ENABLE"] == 1)
|
||||
|
@ -1049,17 +1076,6 @@ namespace ArdupilotMega.Setup
|
|||
{
|
||||
int i = normalreverse == false ? 1 : -1;
|
||||
MainV2.comPort.setParam(name, i);
|
||||
|
||||
if (normalreverse == true)
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(148, 193, 31);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
else
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(148, 193, 31);
|
||||
}
|
||||
}
|
||||
catch { MessageBox.Show("Error Reversing"); }
|
||||
}
|
||||
|
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -4,19 +4,21 @@
|
|||
<AC2>
|
||||
<GPS>
|
||||
<F1>Time</F1>
|
||||
<F2>Fix</F2>
|
||||
<F3>Sats</F3>
|
||||
<F4>Lat</F4>
|
||||
<F5>Long</F5>
|
||||
<F6>Mix Alt</F6>
|
||||
<F7>GPSAlt</F7>
|
||||
<F8>GR Speed</F8>
|
||||
<F9>CRS</F9>
|
||||
<F2>Sats</F2>
|
||||
<F3>Lat</F3>
|
||||
<F4>Long</F4>
|
||||
<F5>Mix Alt</F5>
|
||||
<F6>GPSAlt</F6>
|
||||
<F7>GR Speed</F7>
|
||||
<F8>CRS</F8>
|
||||
</GPS>
|
||||
<ATT>
|
||||
<F1>Roll</F1>
|
||||
<F2>Pitch</F2>
|
||||
<F3>Yaw</F3>
|
||||
<F4>rc1 servo</F4>
|
||||
<F5>rc2 servo</F5>
|
||||
<F6>rc3 servo</F6>
|
||||
</ATT>
|
||||
<NTUN>
|
||||
<F1>WP Dist</F1>
|
||||
|
|
|
@ -4,19 +4,21 @@
|
|||
<AC2>
|
||||
<GPS>
|
||||
<F1>Time</F1>
|
||||
<F2>Fix</F2>
|
||||
<F3>Sats</F3>
|
||||
<F4>Lat</F4>
|
||||
<F5>Long</F5>
|
||||
<F6>Mix Alt</F6>
|
||||
<F7>GPSAlt</F7>
|
||||
<F8>GR Speed</F8>
|
||||
<F9>CRS</F9>
|
||||
<F2>Sats</F2>
|
||||
<F3>Lat</F3>
|
||||
<F4>Long</F4>
|
||||
<F5>Mix Alt</F5>
|
||||
<F6>GPSAlt</F6>
|
||||
<F7>GR Speed</F7>
|
||||
<F8>CRS</F8>
|
||||
</GPS>
|
||||
<ATT>
|
||||
<F1>Roll</F1>
|
||||
<F2>Pitch</F2>
|
||||
<F3>Yaw</F3>
|
||||
<F4>rc1 servo</F4>
|
||||
<F5>rc2 servo</F5>
|
||||
<F6>rc3 servo</F6>
|
||||
</ATT>
|
||||
<NTUN>
|
||||
<F1>WP Dist</F1>
|
||||
|
|
Loading…
Reference in New Issue