This commit is contained in:
James Goppert 2011-11-18 14:36:47 -05:00
commit 2337153966
82 changed files with 6596 additions and 4199 deletions

View File

@ -27,7 +27,7 @@
V_FRAME V_FRAME
*/ */
# define CH7_OPTION CH7_DO_NOTHING # define CH7_OPTION CH7_SAVE_WP
/* /*
CH7_DO_NOTHING CH7_DO_NOTHING
CH7_SET_HOVER CH7_SET_HOVER

View File

@ -299,16 +299,18 @@ static bool did_ground_start = false; // have we ground started after first ar
// Location & Navigation // Location & Navigation
// --------------------- // ---------------------
static bool nav_ok;
static const float radius_of_earth = 6378100; // meters static const float radius_of_earth = 6378100; // meters
static const float gravity = 9.81; // meters/ sec^2 static const float gravity = 9.81; // meters/ sec^2
static int32_t target_bearing; // deg * 100 : 0 to 360 location of the plane to the target static int32_t target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
static byte wp_control; // used to control - navgation or loiter static byte wp_control; // used to control - navgation or loiter
static byte command_must_index; // current command memory location static byte command_nav_index; // current command memory location
static byte command_may_index; // current command memory location static byte prev_nav_index;
static byte command_must_ID; // current command ID static byte command_cond_index; // current command memory location
static byte command_may_ID; // current command ID //static byte command_nav_ID; // current command ID
//static byte command_cond_ID; // current command ID
static byte wp_verify_byte; // used for tracking state of navigating waypoints static byte wp_verify_byte; // used for tracking state of navigating waypoints
static float cos_roll_x = 1; static float cos_roll_x = 1;
@ -317,16 +319,20 @@ static float cos_yaw_x = 1;
static float sin_pitch_y, sin_yaw_y, sin_roll_y; static float sin_pitch_y, sin_yaw_y, sin_roll_y;
static int32_t initial_simple_bearing; // used for Simple mode static int32_t initial_simple_bearing; // used for Simple mode
static float simple_sin_y, simple_cos_x; static float simple_sin_y, simple_cos_x;
static byte jump = -10; // used to track loops in jump command static int8_t jump = -10; // used to track loops in jump command
static int16_t waypoint_speed_gov; static int16_t waypoint_speed_gov;
static float circle_angle;
// replace with param
static const float circle_rate = 0.0872664625;
// Acro // Acro
#if CH7_OPTION == CH7_FLIP #if CH7_OPTION == CH7_FLIP
static bool do_flip = false; static bool do_flip = false;
#endif #endif
static boolean trim_flag; static boolean trim_flag;
static int16_t CH7_wp_index = 0; static int8_t CH7_wp_index;
// Airspeed // Airspeed
// -------- // --------
@ -458,7 +464,8 @@ static struct Location prev_WP; // last waypoint
static struct Location current_loc; // current location static struct Location current_loc; // current location
static struct Location next_WP; // next waypoint static struct Location next_WP; // next waypoint
static struct Location target_WP; // where do we want to you towards? static struct Location target_WP; // where do we want to you towards?
static struct Location next_command; // command preloaded static struct Location command_nav_queue; // command preloaded
static struct Location command_cond_queue; // command preloaded
static struct Location guided_WP; // guided mode waypoint static struct Location guided_WP; // guided mode waypoint
static int32_t target_altitude; // used for static int32_t target_altitude; // used for
static boolean home_is_set; // Flag for if we have g_gps lock and have set the home location static boolean home_is_set; // Flag for if we have g_gps lock and have set the home location
@ -613,9 +620,8 @@ static void medium_loop()
update_GPS(); update_GPS();
} }
//readCommands();
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
if(g.compass_enabled){ if(g.compass_enabled){
compass.read(); // Read magnetometer compass.read(); // Read magnetometer
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
@ -637,18 +643,14 @@ static void medium_loop()
medium_loopCounter++; medium_loopCounter++;
// Auto control modes: // Auto control modes:
if(g_gps->new_data && g_gps->fix){ if(nav_ok){
// clear nav flag
nav_ok = false;
// invalidate GPS data // invalidate GPS data
// -------------------
g_gps->new_data = false; g_gps->new_data = false;
// we are not tracking I term on navigation, so this isn't needed
dTnav = (float)(millis() - nav_loopTimer)/ 1000.0;
nav_loopTimer = millis();
// prevent runup from bad GPS
dTnav = min(dTnav, 1.0);
// calculate the copter's desired bearing and WP distance // calculate the copter's desired bearing and WP distance
// ------------------------------------------------------ // ------------------------------------------------------
if(navigate()){ if(navigate()){
@ -660,10 +662,7 @@ static void medium_loop()
if (g.log_bitmask & MASK_LOG_NTUN) if (g.log_bitmask & MASK_LOG_NTUN)
Log_Write_Nav_Tuning(); Log_Write_Nav_Tuning();
} }
}else{
g_gps->new_data = false;
} }
break; break;
// command processing // command processing
@ -673,7 +672,9 @@ static void medium_loop()
// Read altitude from sensors // Read altitude from sensors
// -------------------------- // --------------------------
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
update_altitude(); update_altitude();
#endif
// invalidate the throttle hold value // invalidate the throttle hold value
// ---------------------------------- // ----------------------------------
@ -689,7 +690,9 @@ static void medium_loop()
// perform next command // perform next command
// -------------------- // --------------------
if(control_mode == AUTO){ if(control_mode == AUTO){
update_commands(); if(home_is_set == true && g.command_total > 1){
update_commands(true);
}
} }
if(motor_armed){ if(motor_armed){
@ -895,18 +898,27 @@ static void update_GPS(void)
gps_watchdog++; gps_watchdog++;
}else{ }else{
// we have lost GPS signal for a moment. Reduce our error to avoid flyaways // we have lost GPS signal for a moment. Reduce our error to avoid flyaways
// commented temporarily nav_roll >>= 1;
//nav_roll >>= 1; nav_pitch >>= 1;
//nav_pitch >>= 1;
} }
if (g_gps->new_data && g_gps->fix) { if (g_gps->new_data && g_gps->fix) {
gps_watchdog = 0; gps_watchdog = 0;
// OK to run the nav routines
nav_ok = true;
// for performance // for performance
// --------------- // ---------------
gps_fix_count++; gps_fix_count++;
// we are not tracking I term on navigation, so this isn't needed
dTnav = (float)(millis() - nav_loopTimer)/ 1000.0;
nav_loopTimer = millis();
// prevent runup from bad GPS
dTnav = min(dTnav, 1.0);
if(ground_start_count > 1){ if(ground_start_count > 1){
ground_start_count--; ground_start_count--;
@ -930,6 +942,13 @@ static void update_GPS(void)
if (g.log_bitmask & MASK_LOG_GPS){ if (g.log_bitmask & MASK_LOG_GPS){
Log_Write_GPS(); Log_Write_GPS();
} }
#if HIL_MODE == HIL_MODE_ATTITUDE // only execute in HIL mode
update_altitude();
#endif
} else {
g_gps->new_data = false;
} }
} }
@ -1209,32 +1228,50 @@ static void update_trig(void){
static void update_altitude() static void update_altitude()
{ {
altitude_sensor = BARO; altitude_sensor = BARO;
//current_loc.alt = g_gps->altitude - gps_base_alt;
//climb_rate = (g_gps->altitude - old_baro_alt) * 10;
//old_baro_alt = g_gps->altitude;
//baro_alt = g_gps->altitude;
#if HIL_MODE == HIL_MODE_ATTITUDE #if HIL_MODE == HIL_MODE_ATTITUDE
current_loc.alt = g_gps->altitude - gps_base_alt; // we are in the SIM, fake out the baro and Sonar
climb_rate = (g_gps->altitude - old_baro_alt) * 10; int fake_relative_alt = g_gps->altitude - gps_base_alt;
old_baro_alt = g_gps->altitude; baro_alt = fake_relative_alt;
return; sonar_alt = fake_relative_alt;
#else
baro_rate = (baro_alt - old_baro_alt) * 5; // 5hz
old_baro_alt = baro_alt;
#else
// This is real life
// calc the vertical accel rate // calc the vertical accel rate
int temp_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale
baro_rate = (temp_alt - old_baro_alt) * 10; baro_rate = (temp_baro_alt - old_baro_alt) * 10;
old_baro_alt = temp_alt; old_baro_alt = temp_baro_alt;
// read in Actual Baro Altitude
baro_alt = (baro_alt + read_barometer()) >> 1;
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
#endif
if(g.sonar_enabled){ if(g.sonar_enabled){
// filter out offset // filter out offset
float scale; float scale;
// read barometer
baro_alt = (baro_alt + read_barometer()) >> 1;
// calc rate of change for Sonar // calc rate of change for Sonar
#if HIL_MODE == HIL_MODE_ATTITUDE
// we are in the SIM, fake outthe Sonar rate
sonar_rate = baro_rate;
#else
// This is real life
// calc the vertical accel rate
sonar_rate = (sonar_alt - old_sonar_alt) * 10; sonar_rate = (sonar_alt - old_sonar_alt) * 10;
old_sonar_alt = sonar_alt; old_sonar_alt = sonar_alt;
#endif
if(baro_alt < 700){ if(baro_alt < 800){
#if SONAR_TILT_CORRECTION == 1 #if SONAR_TILT_CORRECTION == 1
// correct alt for angle of the sonar // correct alt for angle of the sonar
float temp = cos_pitch_x * cos_roll_x; float temp = cos_pitch_x * cos_roll_x;
@ -1246,22 +1283,23 @@ static void update_altitude()
scale = constrain(scale, 0, 1); scale = constrain(scale, 0, 1);
current_loc.alt = ((float)sonar_alt * (1.0 - scale)) + ((float)baro_alt * scale) + home.alt; current_loc.alt = ((float)sonar_alt * (1.0 - scale)) + ((float)baro_alt * scale) + home.alt;
// solve for a blended climb_rate
climb_rate = ((float)sonar_rate * (1.0 - scale)) + (float)baro_rate * scale; climb_rate = ((float)sonar_rate * (1.0 - scale)) + (float)baro_rate * scale;
}else{ }else{
current_loc.alt = baro_alt + home.alt; // we must be higher than sonar, don't get tricked by bad sonar reads
current_loc.alt = baro_alt + home.alt; // home alt = 0
// dont blend, go straight baro
climb_rate = baro_rate; climb_rate = baro_rate;
} }
}else{ }else{
// No Sonar Case
baro_alt = read_barometer(); // NO Sonar case
current_loc.alt = baro_alt + home.alt; current_loc.alt = baro_alt + home.alt;
climb_rate = baro_rate; climb_rate = baro_rate;
} }
#endif
} }
static void static void
@ -1419,10 +1457,17 @@ static void update_nav_wp()
// create a virtual waypoint that circles the next_WP // create a virtual waypoint that circles the next_WP
// Count the degrees we have circulated the WP // Count the degrees we have circulated the WP
int circle_angle = wrap_360(target_bearing + 3000 + 18000) / 100; //int circle_angle = wrap_360(target_bearing + 3000 + 18000) / 100;
target_WP.lng = next_WP.lng + (g.loiter_radius * cos(radians(90 - circle_angle))); circle_angle += (circle_rate * dTnav);
target_WP.lat = next_WP.lat + (g.loiter_radius * sin(radians(90 - circle_angle))); //1° = 0.0174532925 radians
// wrap
if (circle_angle > 6.28318531)
circle_angle -= 6.28318531;
target_WP.lng = next_WP.lng + (g.loiter_radius * cos(1.57 - circle_angle) * scaleLongUp);
target_WP.lat = next_WP.lat + (g.loiter_radius * sin(1.57 - circle_angle));
// calc the lat and long error to the target // calc the lat and long error to the target
calc_location_error(&target_WP); calc_location_error(&target_WP);
@ -1431,9 +1476,14 @@ static void update_nav_wp()
// nav_lon, nav_lat is calculated // nav_lon, nav_lat is calculated
calc_loiter(long_error, lat_error); calc_loiter(long_error, lat_error);
//CIRCLE: angle:29, dist:0, lat:400, lon:242
// rotate pitch and roll to the copter frame of reference // rotate pitch and roll to the copter frame of reference
calc_loiter_pitch_roll(); calc_loiter_pitch_roll();
//int angleTest = degrees(circle_angle);
//int nroll = nav_roll;
//int npitch = nav_pitch;
//Serial.printf("CIRCLE: angle:%d, dist:%d, X:%d, Y:%d, P:%d, R:%d \n", angleTest, (int)wp_distance , (int)long_error, (int)lat_error, npitch, nroll);
} else { } else {
// use error as the desired rate towards the target // use error as the desired rate towards the target
calc_nav_rate(g.waypoint_speed_max); calc_nav_rate(g.waypoint_speed_max);

View File

@ -146,6 +146,15 @@ static void reset_nav(void)
g.pi_nav_lat.reset_I(); g.pi_nav_lat.reset_I();
g.pi_nav_lon.reset_I(); g.pi_nav_lon.reset_I();
circle_angle = 0;
crosstrack_error = 0;
nav_lat = 0;
nav_lon = 0;
nav_roll = 0;
nav_pitch = 0;
target_bearing = 0;
wp_distance = 0;
wp_totalDistance = 0;
long_error = 0; long_error = 0;
lat_error = 0; lat_error = 0;
} }

View File

@ -66,6 +66,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
break; break;
case GUIDED: case GUIDED:
mode = MAV_MODE_GUIDED; mode = MAV_MODE_GUIDED;
nav_mode = MAV_NAV_WAYPOINT;
break; break;
default: default:
mode = control_mode + 100; mode = control_mode + 100;
@ -579,7 +580,7 @@ GCS_MAVLINK::update(void)
uint32_t tnow = millis(); uint32_t tnow = millis();
if (waypoint_receiving && if (waypoint_receiving &&
waypoint_request_i <= (unsigned)g.command_total && waypoint_request_i < (unsigned)g.command_total &&
tnow > waypoint_timelast_request + 500) { tnow > waypoint_timelast_request + 500) {
waypoint_timelast_request = tnow; waypoint_timelast_request = tnow;
send_message(MSG_NEXT_WAYPOINT); send_message(MSG_NEXT_WAYPOINT);
@ -809,7 +810,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
*/ */
case MAV_ACTION_CONTINUE: case MAV_ACTION_CONTINUE:
process_next_command(); //process_command_queue();
result=1; result=1;
break; break;
@ -947,7 +948,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_waypoint_count_send( mavlink_msg_waypoint_count_send(
chan,msg->sysid, chan,msg->sysid,
msg->compid, msg->compid,
g.command_total + 1); // + home g.command_total); // includes home
waypoint_timelast_send = millis(); waypoint_timelast_send = millis();
waypoint_sending = true; waypoint_sending = true;
@ -1005,8 +1006,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
z = tell_command.alt/1.0e2; // local (z), global/relative (altitude) z = tell_command.alt/1.0e2; // local (z), global/relative (altitude)
} }
// Switch to map APM command fields inot MAVLink command fields
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields switch (tell_command.id) {
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_CONDITION_CHANGE_ALT: case MAV_CMD_CONDITION_CHANGE_ALT:
@ -1122,7 +1123,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// clear all waypoints // clear all waypoints
uint8_t type = 0; // ok (0), error(1) uint8_t type = 0; // ok (0), error(1)
g.command_total.set_and_save(0); g.command_total.set_and_save(1);
// send acknowledgement 3 times to makes sure it is received // send acknowledgement 3 times to makes sure it is received
for (int i=0;i<3;i++) for (int i=0;i<3;i++)
@ -1160,7 +1161,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.count > MAX_WAYPOINTS) { if (packet.count > MAX_WAYPOINTS) {
packet.count = MAX_WAYPOINTS; packet.count = MAX_WAYPOINTS;
} }
g.command_total.set_and_save(packet.count - 1); g.command_total.set_and_save(packet.count);
waypoint_timelast_receive = millis(); waypoint_timelast_receive = millis();
waypoint_receiving = true; waypoint_receiving = true;
@ -1313,8 +1314,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// Check if receiving waypoints (mission upload expected) // Check if receiving waypoints (mission upload expected)
if (!waypoint_receiving) break; if (!waypoint_receiving) break;
//Serial.printf("req: %d, seq: %d, total: %d\n", waypoint_request_i,packet.seq, g.command_total.get());
// check if this is the requested waypoint // check if this is the requested waypoint
if (packet.seq != waypoint_request_i) break; if (packet.seq != waypoint_request_i)
break;
if(packet.seq != 0)
set_command_with_index(tell_command, packet.seq); set_command_with_index(tell_command, packet.seq);
// update waypoint receiving state machine // update waypoint receiving state machine
@ -1322,7 +1329,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
waypoint_timelast_request = 0; waypoint_timelast_request = 0;
waypoint_request_i++; waypoint_request_i++;
if (waypoint_request_i > (uint16_t)g.command_total){ if (waypoint_request_i == (uint16_t)g.command_total){
uint8_t type = 0; // ok (0), error(1) uint8_t type = 0; // ok (0), error(1)
mavlink_msg_waypoint_ack_send( mavlink_msg_waypoint_ack_send(
@ -1657,7 +1664,7 @@ void
GCS_MAVLINK::queued_waypoint_send() GCS_MAVLINK::queued_waypoint_send()
{ {
if (waypoint_receiving && if (waypoint_receiving &&
waypoint_request_i <= (unsigned)g.command_total) { waypoint_request_i < (unsigned)g.command_total) {
mavlink_msg_waypoint_request_send( mavlink_msg_waypoint_request_send(
chan, chan,
waypoint_dest_sysid, waypoint_dest_sysid,

View File

@ -738,15 +738,14 @@ static void Log_Write_Performance()
//DataFlash.WriteByte( loop_step); //DataFlash.WriteByte( loop_step);
//*
//DataFlash.WriteLong( millis()- perf_mon_timer);
//DataFlash.WriteByte( dcm.gyro_sat_count); //2
//DataFlash.WriteByte( imu.adc_constraints); //3
//DataFlash.WriteByte( dcm.renorm_sqrt_count); //4
//DataFlash.WriteByte( dcm.renorm_blowup_count); //5
//DataFlash.WriteByte( gps_fix_count); //6
DataFlash.WriteLong( millis()- perf_mon_timer); //1
DataFlash.WriteByte( dcm.gyro_sat_count); //2
DataFlash.WriteByte( imu.adc_constraints); //3
DataFlash.WriteByte( dcm.renorm_sqrt_count); //4
DataFlash.WriteByte( dcm.renorm_blowup_count); //5
DataFlash.WriteByte( gps_fix_count); //6
DataFlash.WriteByte(END_BYTE);
//DataFlash.WriteInt ( (int)(dcm.get_health() * 1000)); //7 //DataFlash.WriteInt ( (int)(dcm.get_health() * 1000)); //7
@ -754,6 +753,7 @@ static void Log_Write_Performance()
// control_mode // control_mode
/*
DataFlash.WriteByte(control_mode); //1 DataFlash.WriteByte(control_mode); //1
DataFlash.WriteByte(yaw_mode); //2 DataFlash.WriteByte(yaw_mode); //2
DataFlash.WriteByte(roll_pitch_mode); //3 DataFlash.WriteByte(roll_pitch_mode); //3
@ -761,20 +761,22 @@ static void Log_Write_Performance()
DataFlash.WriteInt(g.throttle_cruise.get()); //5 DataFlash.WriteInt(g.throttle_cruise.get()); //5
DataFlash.WriteLong(throttle_integrator); //6 DataFlash.WriteLong(throttle_integrator); //6
DataFlash.WriteByte(END_BYTE); DataFlash.WriteByte(END_BYTE);
*/
} }
// Read a performance packet // Read a performance packet
static void Log_Read_Performance() static void Log_Read_Performance()
{ {
int8_t temp1 = DataFlash.ReadByte(); int32_t temp1 = DataFlash.ReadLong();
int8_t temp2 = DataFlash.ReadByte(); int8_t temp2 = DataFlash.ReadByte();
int8_t temp3 = DataFlash.ReadByte(); int8_t temp3 = DataFlash.ReadByte();
int8_t temp4 = DataFlash.ReadByte(); int8_t temp4 = DataFlash.ReadByte();
int16_t temp5 = DataFlash.ReadInt(); int8_t temp5 = DataFlash.ReadByte();
int32_t temp6 = DataFlash.ReadLong(); int8_t temp6 = DataFlash.ReadByte();
//1 2 3 4 5 6 //1 2 3 4 5 6
Serial.printf_P(PSTR("PM, %d, %d, %d, %d, %d, %ld\n"), Serial.printf_P(PSTR("PM, %ld, %d, %d, %d, %d, %d\n"),
temp1, temp1,
temp2, temp2,
temp3, temp3,
@ -852,9 +854,9 @@ static void Log_Read_Attitude()
int16_t temp1 = DataFlash.ReadInt(); int16_t temp1 = DataFlash.ReadInt();
int16_t temp2 = DataFlash.ReadInt(); int16_t temp2 = DataFlash.ReadInt();
uint16_t temp3 = DataFlash.ReadInt(); uint16_t temp3 = DataFlash.ReadInt();
int16_t temp4 = DataFlash.ReadByte(); int16_t temp4 = DataFlash.ReadInt();
int16_t temp5 = DataFlash.ReadByte(); int16_t temp5 = DataFlash.ReadInt();
int16_t temp6 = DataFlash.ReadByte(); int16_t temp6 = DataFlash.ReadInt();
// 1 2 3 4 5 6 // 1 2 3 4 5 6
Serial.printf_P(PSTR("ATT, %d, %d, %u, %d, %d, %d\n"), Serial.printf_P(PSTR("ATT, %d, %d, %u, %d, %d, %d\n"),

View File

@ -75,7 +75,10 @@ public:
k_param_heli_collective_mid, k_param_heli_collective_mid,
k_param_heli_ext_gyro_enabled, k_param_heli_ext_gyro_enabled,
k_param_heli_ext_gyro_gain, k_param_heli_ext_gyro_gain,
k_param_heli_servo_averaging, // 94 k_param_heli_servo_averaging,
k_param_heli_servo_manual,
k_param_heli_phase_angle,
k_param_heli_coll_yaw_effect, // 97
#endif #endif
// 110: Telemetry control // 110: Telemetry control
@ -148,7 +151,7 @@ public:
k_param_waypoint_mode = 220, k_param_waypoint_mode = 220,
k_param_command_total, k_param_command_total,
k_param_command_index, k_param_command_index,
k_param_command_must_index, k_param_command_nav_index,
k_param_waypoint_radius, k_param_waypoint_radius,
k_param_loiter_radius, k_param_loiter_radius,
k_param_waypoint_speed_max, k_param_waypoint_speed_max,
@ -195,9 +198,9 @@ public:
AP_Int8 waypoint_mode; AP_Int8 waypoint_mode;
AP_Int8 command_total; AP_Int8 command_total;
AP_Int8 command_index; AP_Int8 command_index;
AP_Int8 command_must_index; AP_Int8 command_nav_index;
AP_Int8 waypoint_radius; AP_Int8 waypoint_radius;
AP_Int8 loiter_radius; AP_Int16 loiter_radius;
AP_Int16 waypoint_speed_max; AP_Int16 waypoint_speed_max;
// Throttle // Throttle
@ -253,6 +256,9 @@ public:
AP_Int8 heli_ext_gyro_enabled; // 0 = no external tail gyro, 1 = external tail gyro 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) 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)
AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
AP_Int16 heli_phase_angle; // 0 to 360 degrees. specifies mixing between roll and pitch for helis
AP_Float heli_coll_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point
#endif #endif
// RC channels // RC channels
@ -318,7 +324,7 @@ public:
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")), waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
command_total (0, k_param_command_total, PSTR("WP_TOTAL")), command_total (0, k_param_command_total, PSTR("WP_TOTAL")),
command_index (0, k_param_command_index, PSTR("WP_INDEX")), command_index (0, k_param_command_index, PSTR("WP_INDEX")),
command_must_index (0, k_param_command_must_index, PSTR("WP_MUST_INDEX")), command_nav_index (0, k_param_command_nav_index, PSTR("WP_MUST_INDEX")),
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")), waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")), waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
@ -361,6 +367,9 @@ public:
heli_ext_gyro_enabled (0, k_param_heli_ext_gyro_enabled, PSTR("GYR_ENABLE_")), 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_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")), heli_servo_averaging (0, k_param_heli_servo_averaging, PSTR("SV_AVG")),
heli_servo_manual (0, k_param_heli_servo_manual, PSTR("HSV_MAN")),
heli_phase_angle (0, k_param_heli_phase_angle, PSTR("H_PHANG")),
heli_coll_yaw_effect (0, k_param_heli_coll_yaw_effect, PSTR("H_COLYAW")),
#endif #endif
// RC channel group key name // RC channel group key name

View File

@ -2,22 +2,12 @@
static void init_commands() static void init_commands()
{ {
// zero is home, but we always load the next command (1), in the code. g.command_index = NO_COMMAND;
g.command_index = 0; command_nav_index = NO_COMMAND;
command_cond_index = NO_COMMAND;
// This are registers for the current may and must commands prev_nav_index = NO_COMMAND;
// setting to zero will allow them to be written to by new commands command_cond_queue.id = NO_COMMAND;
command_must_index = NO_COMMAND; command_nav_queue.id = NO_COMMAND;
command_may_index = NO_COMMAND;
// clear the command queue
clear_command_queue();
}
// forces the loading of a new command
// queue is emptied after a new command is processed
static void clear_command_queue(){
next_command.id = NO_COMMAND;
} }
// Getters // Getters
@ -28,7 +18,7 @@ static struct Location get_cmd_with_index(int i)
// Find out proper location in memory by using the start_byte position + the index // Find out proper location in memory by using the start_byte position + the index
// -------------------------------------------------------------------------------- // --------------------------------------------------------------------------------
if (i > g.command_total) { if (i >= g.command_total) {
// we do not have a valid command to load // we do not have a valid command to load
// return a WP with a "Blank" id // return a WP with a "Blank" id
temp.id = CMD_BLANK; temp.id = CMD_BLANK;
@ -78,6 +68,15 @@ static struct Location get_cmd_with_index(int i)
static void set_command_with_index(struct Location temp, int i) static void set_command_with_index(struct Location temp, int i)
{ {
i = constrain(i, 0, g.command_total.get()); i = constrain(i, 0, g.command_total.get());
//Serial.printf("set_command: %d with id: %d\n", i, temp.id);
// store home as 0 altitude!!!
// Home is always a MAV_CMD_NAV_WAYPOINT (16)
if (i == 0){
temp.alt = 0;
temp.id = MAV_CMD_NAV_WAYPOINT;
}
uint32_t mem = WP_START_BYTE + (i * WP_SIZE); uint32_t mem = WP_START_BYTE + (i * WP_SIZE);
eeprom_write_byte((uint8_t *) mem, temp.id); eeprom_write_byte((uint8_t *) mem, temp.id);
@ -96,19 +95,24 @@ static void set_command_with_index(struct Location temp, int i)
mem += 4; mem += 4;
eeprom_write_dword((uint32_t *) mem, temp.lng); // Long is stored in decimal degrees * 10^7 eeprom_write_dword((uint32_t *) mem, temp.lng); // Long is stored in decimal degrees * 10^7
// Make sure our WP_total
if(g.command_total <= i)
g.command_total.set_and_save(i+1);
} }
static void increment_WP_index() /*
//static void increment_WP_index()
{ {
if (g.command_index < g.command_total) { if (g.command_index < (g.command_total-1)) {
g.command_index++; g.command_index++;
} }
SendDebugln(g.command_index,DEC); SendDebugln(g.command_index,DEC);
} }
*/
/* /*
static void decrement_WP_index() //static void decrement_WP_index()
{ {
if (g.command_index > 0) { if (g.command_index > 0) {
g.command_index.set_and_save(g.command_index - 1); g.command_index.set_and_save(g.command_index - 1);
@ -117,7 +121,7 @@ static void decrement_WP_index()
static int32_t read_alt_to_hold() static int32_t read_alt_to_hold()
{ {
if(g.RTL_altitude < 0) if(g.RTL_altitude <= 0)
return current_loc.alt; return current_loc.alt;
else else
return g.RTL_altitude;// + home.alt; return g.RTL_altitude;// + home.alt;
@ -129,18 +133,6 @@ static int32_t read_alt_to_hold()
// It's not currently used // It's not currently used
//******************************************************************************** //********************************************************************************
/*static Location get_LOITER_home_wp()
{
//so we know where we are navigating from
next_WP = current_loc;
// read home position
struct Location temp = get_cmd_with_index(0); // 0 = home
temp.id = MAV_CMD_NAV_LOITER_UNLIM;
temp.alt = read_alt_to_hold();
return temp;
}
*/
/* /*
This function sets the next waypoint command This function sets the next waypoint command
It precalculates all the necessary stuff. It precalculates all the necessary stuff.

View File

@ -3,9 +3,9 @@
/********************************************************************************/ /********************************************************************************/
// Command Event Handlers // Command Event Handlers
/********************************************************************************/ /********************************************************************************/
static void handle_process_must() static void process_nav_command()
{ {
switch(next_command.id){ switch(command_nav_queue.id){
case MAV_CMD_NAV_TAKEOFF: // 22 case MAV_CMD_NAV_TAKEOFF: // 22
do_takeoff(); do_takeoff();
@ -41,9 +41,9 @@ static void handle_process_must()
} }
static void handle_process_may() static void process_cond_command()
{ {
switch(next_command.id){ switch(command_cond_queue.id){
case MAV_CMD_CONDITION_DELAY: // 112 case MAV_CMD_CONDITION_DELAY: // 112
do_wait_delay(); do_wait_delay();
@ -66,9 +66,9 @@ static void handle_process_may()
} }
} }
static void handle_process_now() static void process_now_command()
{ {
switch(next_command.id){ switch(command_cond_queue.id){
case MAV_CMD_DO_JUMP: // 177 case MAV_CMD_DO_JUMP: // 177
do_jump(); do_jump();
@ -121,9 +121,9 @@ static void handle_no_commands()
static bool verify_must() static bool verify_must()
{ {
//Serial.printf("vmust: %d\n", command_must_ID); //Serial.printf("vmust: %d\n", command_nav_ID);
switch(command_must_ID) { switch(command_nav_queue.id) {
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
return verify_takeoff(); return verify_takeoff();
@ -162,7 +162,7 @@ static bool verify_must()
static bool verify_may() static bool verify_may()
{ {
switch(command_may_ID) { switch(command_cond_queue.id) {
case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay(); return verify_wait_delay();
@ -221,12 +221,12 @@ static void do_takeoff()
// Start with current location // Start with current location
Location temp = current_loc; Location temp = current_loc;
// next_command.alt is a relative altitude!!! // command_nav_queue.alt is a relative altitude!!!
if (next_command.options & WP_OPTION_ALT_RELATIVE) { if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) {
temp.alt = next_command.alt + home.alt; temp.alt = command_nav_queue.alt + home.alt;
//Serial.printf("rel alt: %ld",temp.alt); //Serial.printf("rel alt: %ld",temp.alt);
} else { } else {
temp.alt = next_command.alt; temp.alt = command_nav_queue.alt;
//Serial.printf("abs alt: %ld",temp.alt); //Serial.printf("abs alt: %ld",temp.alt);
} }
@ -241,11 +241,11 @@ static void do_nav_wp()
{ {
wp_control = WP_MODE; wp_control = WP_MODE;
// next_command.alt is a relative altitude!!! // command_nav_queue.alt is a relative altitude!!!
if (next_command.options & WP_OPTION_ALT_RELATIVE) { if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) {
next_command.alt += home.alt; command_nav_queue.alt += home.alt;
} }
set_next_WP(&next_command); set_next_WP(&command_nav_queue);
// this is our bitmask to verify we have met all conditions to move on // this is our bitmask to verify we have met all conditions to move on
@ -255,7 +255,7 @@ static void do_nav_wp()
loiter_time = 0; loiter_time = 0;
// this is the delay, stored in seconds and expanded to millis // this is the delay, stored in seconds and expanded to millis
loiter_time_max = next_command.p1 * 1000; loiter_time_max = command_nav_queue.p1 * 1000;
// if we don't require an altitude minimum, we save this flag as passed (1) // if we don't require an altitude minimum, we save this flag as passed (1)
if((next_WP.options & WP_OPTION_ALT_REQUIRED) == 0){ if((next_WP.options & WP_OPTION_ALT_REQUIRED) == 0){
@ -291,37 +291,38 @@ static void do_loiter_unlimited()
wp_control = LOITER_MODE; wp_control = LOITER_MODE;
//Serial.println("dloi "); //Serial.println("dloi ");
if(next_command.lat == 0) if(command_nav_queue.lat == 0)
set_next_WP(&current_loc); set_next_WP(&current_loc);
else else
set_next_WP(&next_command); set_next_WP(&command_nav_queue);
} }
static void do_loiter_turns() static void do_loiter_turns()
{ {
wp_control = CIRCLE_MODE; wp_control = CIRCLE_MODE;
if(next_command.lat == 0) if(command_nav_queue.lat == 0)
set_next_WP(&current_loc); set_next_WP(&current_loc);
else else
set_next_WP(&next_command); set_next_WP(&command_nav_queue);
loiter_total = next_command.p1 * 360; loiter_total = command_nav_queue.p1 * 360;
loiter_sum = 0; loiter_sum = 0;
old_target_bearing = target_bearing;
} }
static void do_loiter_time() static void do_loiter_time()
{ {
if(next_command.lat == 0){ if(command_nav_queue.lat == 0){
wp_control = LOITER_MODE; wp_control = LOITER_MODE;
loiter_time = millis(); loiter_time = millis();
set_next_WP(&current_loc); set_next_WP(&current_loc);
}else{ }else{
wp_control = WP_MODE; wp_control = WP_MODE;
set_next_WP(&next_command); set_next_WP(&command_nav_queue);
} }
loiter_time_max = next_command.p1 * 1000; // units are (seconds) loiter_time_max = command_nav_queue.p1 * 1000; // units are (seconds)
} }
/********************************************************************************/ /********************************************************************************/
@ -420,7 +421,7 @@ static bool verify_nav_wp()
if(wp_verify_byte >= 7){ if(wp_verify_byte >= 7){
//if(wp_verify_byte & NAV_LOCATION){ //if(wp_verify_byte & NAV_LOCATION){
char message[30]; char message[30];
sprintf(message,"Reached Command #%i",command_must_index); sprintf(message,"Reached Command #%i",command_nav_index);
gcs_send_text(SEVERITY_LOW,message); gcs_send_text(SEVERITY_LOW,message);
wp_verify_byte = 0; wp_verify_byte = 0;
return true; return true;
@ -452,6 +453,7 @@ static bool verify_loiter_time()
static bool verify_loiter_turns() static bool verify_loiter_turns()
{ {
//Serial.printf("loiter_sum: %d \n", loiter_sum);
// have we rotated around the center enough times? // have we rotated around the center enough times?
// ----------------------------------------------- // -----------------------------------------------
if(abs(loiter_sum) > loiter_total) { if(abs(loiter_sum) > loiter_total) {
@ -488,7 +490,7 @@ static void do_wait_delay()
{ {
//Serial.print("dwd "); //Serial.print("dwd ");
condition_start = millis(); condition_start = millis();
condition_value = next_command.lat * 1000; // convert to milliseconds condition_value = command_cond_queue.lat * 1000; // convert to milliseconds
//Serial.println(condition_value,DEC); //Serial.println(condition_value,DEC);
} }
@ -496,14 +498,14 @@ static void do_change_alt()
{ {
Location temp = next_WP; Location temp = next_WP;
condition_start = current_loc.alt; condition_start = current_loc.alt;
condition_value = next_command.alt; condition_value = command_cond_queue.alt;
temp.alt = next_command.alt; temp.alt = command_cond_queue.alt;
set_next_WP(&temp); set_next_WP(&temp);
} }
static void do_within_distance() static void do_within_distance()
{ {
condition_value = next_command.lat; condition_value = command_cond_queue.lat;
} }
static void do_yaw() static void do_yaw()
@ -515,9 +517,9 @@ static void do_yaw()
command_yaw_start = nav_yaw; // current position command_yaw_start = nav_yaw; // current position
command_yaw_start_time = millis(); command_yaw_start_time = millis();
command_yaw_dir = next_command.p1; // 1 = clockwise, 0 = counterclockwise command_yaw_dir = command_cond_queue.p1; // 1 = clockwise, 0 = counterclockwise
command_yaw_speed = next_command.lat * 100; // ms * 100 command_yaw_speed = command_cond_queue.lat * 100; // ms * 100
command_yaw_relative = next_command.lng; // 1 = Relative, 0 = Absolute command_yaw_relative = command_cond_queue.lng; // 1 = Relative, 0 = Absolute
@ -533,11 +535,11 @@ static void do_yaw()
if (command_yaw_relative == 1){ if (command_yaw_relative == 1){
// relative // relative
command_yaw_delta = next_command.alt * 100; command_yaw_delta = command_cond_queue.alt * 100;
}else{ }else{
// absolute // absolute
command_yaw_end = next_command.alt * 100; command_yaw_end = command_cond_queue.alt * 100;
// calculate the delta travel in deg * 100 // calculate the delta travel in deg * 100
if(command_yaw_dir == 1){ if(command_yaw_dir == 1){
@ -580,6 +582,7 @@ static bool verify_wait_delay()
static bool verify_change_alt() static bool verify_change_alt()
{ {
//Serial.printf("change_alt, ca:%d, na:%d\n", (int)current_loc.alt, (int)next_WP.alt);
if (condition_start < next_WP.alt){ if (condition_start < next_WP.alt){
// we are going higer // we are going higer
if(current_loc.alt > next_WP.alt){ if(current_loc.alt > next_WP.alt){
@ -598,6 +601,7 @@ static bool verify_change_alt()
static bool verify_within_distance() static bool verify_within_distance()
{ {
//Serial.printf("cond dist :%d\n", (int)condition_value);
if (wp_distance < condition_value){ if (wp_distance < condition_value){
condition_value = 0; condition_value = 0;
return true; return true;
@ -607,7 +611,7 @@ static bool verify_within_distance()
static bool verify_yaw() static bool verify_yaw()
{ {
//Serial.print("vyaw "); //Serial.printf("vyaw %d\n", (int)(nav_yaw/100));
if((millis() - command_yaw_start_time) > command_yaw_time){ if((millis() - command_yaw_start_time) > command_yaw_time){
// time out // time out
@ -637,15 +641,15 @@ static bool verify_yaw()
static void do_change_speed() static void do_change_speed()
{ {
g.waypoint_speed_max = next_command.p1 * 100; g.waypoint_speed_max = command_cond_queue.p1 * 100;
} }
static void do_target_yaw() static void do_target_yaw()
{ {
yaw_tracking = next_command.p1; yaw_tracking = command_cond_queue.p1;
if(yaw_tracking == MAV_ROI_LOCATION){ if(yaw_tracking == MAV_ROI_LOCATION){
target_WP = next_command; target_WP = command_cond_queue;
} }
} }
@ -656,51 +660,55 @@ static void do_loiter_at_location()
static void do_jump() static void do_jump()
{ {
//Serial.printf("do Jump: %d\n", jump);
if(jump == -10){ if(jump == -10){
jump = next_command.lat; //Serial.printf("Fresh Jump\n");
// we use a locally stored index for jump
jump = command_cond_queue.lat;
} }
//Serial.printf("Jumps left: %d\n",jump);
if(jump > 0) { if(jump > 0) {
//Serial.printf("Do Jump to %d\n",command_cond_queue.p1);
jump--; jump--;
command_must_index = 0; change_command(command_cond_queue.p1);
command_may_index = 0;
// set pointer to desired index
g.command_index = next_command.p1 - 1;
} else if (jump == 0){ } else if (jump == 0){
//Serial.printf("Did last jump\n");
// we're done, move along // we're done, move along
jump = -10; jump = -11;
} else if (jump == -1) { } else if (jump == -1) {
//Serial.printf("jumpForever\n");
// repeat forever // repeat forever
g.command_index = next_command.p1 - 1; change_command(command_cond_queue.p1);
} }
} }
static void do_set_home() static void do_set_home()
{ {
if(next_command.p1 == 1) { if(command_cond_queue.p1 == 1) {
init_home(); init_home();
} else { } else {
home.id = MAV_CMD_NAV_WAYPOINT; home.id = MAV_CMD_NAV_WAYPOINT;
home.lng = next_command.lng; // Lon * 10**7 home.lng = command_cond_queue.lng; // Lon * 10**7
home.lat = next_command.lat; // Lat * 10**7 home.lat = command_cond_queue.lat; // Lat * 10**7
home.alt = max(next_command.alt, 0); home.alt = max(command_cond_queue.alt, 0);
home_is_set = true; home_is_set = true;
} }
} }
static void do_set_servo() static void do_set_servo()
{ {
APM_RC.OutputCh(next_command.p1 - 1, next_command.alt); APM_RC.OutputCh(command_cond_queue.p1 - 1, command_cond_queue.alt);
} }
static void do_set_relay() static void do_set_relay()
{ {
if (next_command.p1 == 1) { if (command_cond_queue.p1 == 1) {
relay.on(); relay.on();
} else if (next_command.p1 == 0) { } else if (command_cond_queue.p1 == 0) {
relay.off(); relay.off();
}else{ }else{
relay.toggle(); relay.toggle();
@ -709,16 +717,16 @@ static void do_set_relay()
static void do_repeat_servo() static void do_repeat_servo()
{ {
event_id = next_command.p1 - 1; event_id = command_cond_queue.p1 - 1;
if(next_command.p1 >= CH_5 + 1 && next_command.p1 <= CH_8 + 1) { if(command_cond_queue.p1 >= CH_5 + 1 && command_cond_queue.p1 <= CH_8 + 1) {
event_timer = 0; event_timer = 0;
event_value = next_command.alt; event_value = command_cond_queue.alt;
event_repeat = next_command.lat * 2; event_repeat = command_cond_queue.lat * 2;
event_delay = next_command.lng * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds) event_delay = command_cond_queue.lng * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds)
switch(next_command.p1) { switch(command_cond_queue.p1) {
case CH_5: case CH_5:
event_undo_value = g.rc_5.radio_trim; event_undo_value = g.rc_5.radio_trim;
break; break;
@ -740,7 +748,7 @@ static void do_repeat_relay()
{ {
event_id = RELAY_TOGGLE; event_id = RELAY_TOGGLE;
event_timer = 0; event_timer = 0;
event_delay = next_command.lat * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds) event_delay = command_cond_queue.lat * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds)
event_repeat = next_command.alt * 2; event_repeat = command_cond_queue.alt * 2;
update_events(); update_events();
} }

View File

@ -4,61 +4,118 @@
//---------------------------------------- //----------------------------------------
static void change_command(uint8_t cmd_index) static void change_command(uint8_t cmd_index)
{ {
// limit range
cmd_index = min(g.command_total-1, cmd_index);
// load command
struct Location temp = get_cmd_with_index(cmd_index); struct Location temp = get_cmd_with_index(cmd_index);
//Serial.printf("loading cmd: %d with id:%d\n", cmd_index, temp.id);
// verify it's a nav command
if (temp.id > MAV_CMD_NAV_LAST ){ if (temp.id > MAV_CMD_NAV_LAST ){
gcs_send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd")); //gcs_send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd"));
} else { } else {
command_must_index = NO_COMMAND; //Serial.printf("APM:New cmd Index: %d\n", cmd_index);
next_command.id = NO_COMMAND; init_commands();
g.command_index = cmd_index - 1; command_nav_index = cmd_index;
update_commands(); prev_nav_index = command_nav_index;
update_commands(false);
} }
} }
// called by 10 Hz loop // called by 10 Hz loop
// -------------------- // --------------------
static void update_commands(void) static void update_commands(bool increment)
{ {
// fill command queue with a new command if available // A: if we do not have any commands there is nothing to do
if(next_command.id == NO_COMMAND){ // B: We have completed the mission, don't redo the mission
if (g.command_total <= 1 || g.command_index == 255)
return;
// fetch next command if the next command queue is empty if(command_nav_queue.id == NO_COMMAND){
// ----------------------------------------------------- // Our queue is empty
if (g.command_index < g.command_total) { // fill command queue with a new command if available, or exit mission
// -------------------------------------------------------------------
if (command_nav_index < (g.command_total -1)) {
// only if we have a cmd stored in EEPROM // load next index
next_command = get_cmd_with_index(g.command_index + 1); if (increment)
//Serial.printf("queue CMD %d\n", next_command.id); command_nav_index++;
command_nav_queue = get_cmd_with_index(command_nav_index);
if (command_nav_queue.id <= MAV_CMD_NAV_LAST ){
// This is what we report to MAVLINK
g.command_index = command_nav_index;
// Save CMD to Log
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Cmd(g.command_index + 1, &command_nav_queue);
// Act on the new command
process_nav_command();
// clear May indexes to force loading of more commands
// existing May commands are tossed.
command_cond_index = NO_COMMAND;
} else{
// this is a conditional command so we skip it
command_nav_queue.id = NO_COMMAND;
}
} }
} }
// Are we out of must commands and the queue is empty? if(command_cond_queue.id == NO_COMMAND){
if(next_command.id == NO_COMMAND && command_must_index == NO_COMMAND){ // Our queue is empty
// if no commands were available from EEPROM // fill command queue with a new command if available, or do nothing
// And we have no nav commands // -------------------------------------------------------------------
// --------------------------------------------
if (command_must_ID == NO_COMMAND){ // no nav commands completed yet
gcs_send_text_P(SEVERITY_LOW,PSTR("out of commands!")); if (prev_nav_index == NO_COMMAND)
handle_no_commands(); return;
}
if (command_cond_index >= command_nav_index){
// don't process the fututre
//command_cond_index = NO_COMMAND;
return;
}else if (command_cond_index == NO_COMMAND){
// start from scratch
// look at command after the most recent completed nav
command_cond_index = prev_nav_index + 1;
}else{
// we've completed 1 cond, look at next command for another
command_cond_index++;
} }
// check to see if we need to act on our command queue if(command_cond_index < (g.command_total -2)){
if (process_next_command()){ // we're OK to load a new command (last command must be a nav command)
//Serial.printf("did PNC: %d\n", next_command.id); command_cond_queue = get_cmd_with_index(command_cond_index);
// We acted on the queue - let's debug that if (command_cond_queue.id > MAV_CMD_CONDITION_LAST){
// ---------------------------------------- // this is a do now command
print_wp(&next_command, g.command_index); process_now_command();
// invalidate command queue so a new one is loaded // clear command queue
// ----------------------------------------------- command_cond_queue.id = NO_COMMAND;
clear_command_queue();
// make sure we load the next command index }else if (command_cond_queue.id > MAV_CMD_NAV_LAST ){
// ---------------------------------------- // this is a conditional command
increment_WP_index(); process_cond_command();
}else{
// this is a nav command, don't process
// clear the command conditional queue and index
prev_nav_index = NO_COMMAND;
command_cond_index = NO_COMMAND;
command_cond_queue.id = NO_COMMAND;
}
}
} }
} }
@ -66,109 +123,22 @@ static void update_commands(void)
static void verify_commands(void) static void verify_commands(void)
{ {
if(verify_must()){ if(verify_must()){
//Serial.printf("verified must cmd %d\n" , command_must_index); //Serial.printf("verified must cmd %d\n" , command_nav_index);
command_must_index = NO_COMMAND; command_nav_queue.id = NO_COMMAND;
// store our most recent executed nav command
prev_nav_index = command_nav_index;
// Wipe existing conditionals
command_cond_index = NO_COMMAND;
command_cond_queue.id = NO_COMMAND;
}else{ }else{
//Serial.printf("verified must false %d\n" , command_must_index); //Serial.printf("verified must false %d\n" , command_nav_index);
} }
if(verify_may()){ if(verify_may()){
//Serial.printf("verified may cmd %d\n" , command_may_index); //Serial.printf("verified may cmd %d\n" , command_cond_index);
command_may_index = NO_COMMAND; command_cond_queue.id = NO_COMMAND;
command_may_ID = NO_COMMAND;
} }
} }
static bool
process_next_command()
{
// these are Navigation/Must commands
// ---------------------------------
if (command_must_index == NO_COMMAND){ // no current command loaded
if (next_command.id < MAV_CMD_NAV_LAST ){
// we remember the index of our mission here
command_must_index = g.command_index + 1;
// Save CMD to Log
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Cmd(g.command_index + 1, &next_command);
// Act on the new command
process_must();
return true;
}
}
// these are Condition/May commands
// ----------------------
if (command_may_index == NO_COMMAND){
if (next_command.id > MAV_CMD_NAV_LAST && next_command.id < MAV_CMD_CONDITION_LAST ){
// we remember the index of our mission here
command_may_index = g.command_index + 1;
//SendDebug("MSG <pnc> new may ");
//SendDebugln(next_command.id,DEC);
//Serial.print("new command_may_index ");
//Serial.println(command_may_index,DEC);
// Save CMD to Log
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Cmd(g.command_index + 1, &next_command);
process_may();
return true;
}
// these are Do/Now commands
// ---------------------------
if (next_command.id > MAV_CMD_CONDITION_LAST){
//SendDebug("MSG <pnc> new now ");
//SendDebugln(next_command.id,DEC);
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Cmd(g.command_index + 1, &next_command);
process_now();
return true;
}
}
// we did not need any new commands
return false;
}
/**************************************************/
// These functions implement the commands.
/**************************************************/
static void process_must()
{
//gcs_send_text_P(SEVERITY_LOW,PSTR("New cmd: <process_must>"));
//Serial.printf("pmst %d\n", (int)next_command.id);
// clear May indexes to force loading of more commands
// existing May commands are tossed.
command_may_index = NO_COMMAND;
command_may_ID = NO_COMMAND;
// remember our command ID
command_must_ID = next_command.id;
// implements the Flight Logic
handle_process_must();
}
static void process_may()
{
//gcs_send_text_P(SEVERITY_LOW,PSTR("<process_may>"));
//Serial.print("pmay");
command_may_ID = next_command.id;
handle_process_may();
}
static void process_now()
{
//Serial.print("pnow");
handle_process_now();
}

View File

@ -670,11 +670,11 @@
#endif #endif
#ifndef LOITER_RADIUS #ifndef LOITER_RADIUS
# define LOITER_RADIUS 10 # define LOITER_RADIUS 10 // meters for circle mode
#endif #endif
#ifndef ALT_HOLD_HOME #ifndef ALT_HOLD_HOME
# define ALT_HOLD_HOME 10 # define ALT_HOLD_HOME 0 // height to return to Home, 0 = Maintain current altitude
#endif #endif
#ifndef USE_CURRENT_ALT #ifndef USE_CURRENT_ALT

View File

@ -78,13 +78,13 @@ static void read_trim_switch()
}else{ // switch is disengaged }else{ // switch is disengaged
if(trim_flag){ if(trim_flag){
trim_flag = false;
// set the throttle nominal // set the throttle nominal
if(g.rc_3.control_in > 150){ if(g.rc_3.control_in > 150){
g.throttle_cruise.set_and_save(g.rc_3.control_in); g.throttle_cruise.set_and_save(g.rc_3.control_in);
//Serial.printf("tnom %d\n", g.throttle_cruise.get()); //Serial.printf("tnom %d\n", g.throttle_cruise.get());
} }
trim_flag = false;
} }
} }
@ -95,11 +95,22 @@ static void read_trim_switch()
}else{ // switch is disengaged }else{ // switch is disengaged
if(trim_flag){ if(trim_flag){
// set the next_WP trim_flag = false;
// increment index
CH7_wp_index++; CH7_wp_index++;
// set the next_WP, 0 is Home so we don't set that
// max out at 100 since I think we need to stay under the EEPROM limit
CH7_wp_index = constrain(CH7_wp_index, 1, 100);
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
current_loc.id = MAV_CMD_NAV_WAYPOINT; current_loc.id = MAV_CMD_NAV_WAYPOINT;
g.command_total.set_and_save(CH7_wp_index);
// save command
set_command_with_index(current_loc, CH7_wp_index); set_command_with_index(current_loc, CH7_wp_index);
// save the index
g.command_total.set_and_save(CH7_wp_index + 1);
} }
} }

View File

@ -5,8 +5,8 @@
#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz #define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz
#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz #define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz
static int heli_manual_override = false;
static float heli_throttle_scaler = 0; static float heli_throttle_scaler = 0;
static bool heli_swash_initialised = false;
// heli_servo_averaging: // heli_servo_averaging:
// 0 or 1 = no averaging, 250hz // 0 or 1 = no averaging, 250hz
@ -29,14 +29,14 @@ static void heli_init_swash()
g.heli_servo_4.set_angle(4500); g.heli_servo_4.set_angle(4500);
// pitch factors // pitch factors
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos)); heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos)); heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos)); heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
// roll factors // roll factors
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90)); heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90)); heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90)); heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
// collective min / max // collective min / max
total_tilt_max = 0; total_tilt_max = 0;
@ -65,6 +65,9 @@ static void heli_init_swash()
g.heli_servo_averaging = 0; g.heli_servo_averaging = 0;
g.heli_servo_averaging.save(); g.heli_servo_averaging.save();
} }
// mark swash as initialised
heli_swash_initialised = true;
} }
static void heli_move_servos_to_mid() static void heli_move_servos_to_mid()
@ -82,25 +85,38 @@ static void heli_move_servos_to_mid()
// //
static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out) static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
{ {
int yaw_offset = 0;
if( g.heli_servo_manual == 1 ) { // are we in manual servo mode? (i.e. swash set-up mode)?
// we must be in set-up mode so mark swash as uninitialised
heli_swash_initialised = false;
}else{ // regular flight mode
// check if we need to reinitialise the swash
if( !heli_swash_initialised ) {
heli_init_swash();
}
// ensure values are acceptable: // ensure values are acceptable:
roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max); roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max); pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max); coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max);
// rudder feed forward based on collective
#if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator
if( !g.heli_ext_gyro_enabled ) {
yaw_offset = g.heli_coll_yaw_effect * (coll_out - g.heli_coll_mid);
}
#endif
}
// swashplate servos // swashplate servos
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out + (g.heli_servo_1.radio_trim-1500); g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_1.radio_trim-1500);
if( g.heli_servo_1.get_reverse() ) g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_2.radio_trim-1500);
g.heli_servo_1.servo_out = 3000 - g.heli_servo_1.servo_out; g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_3.radio_trim-1500);
g.heli_servo_4.servo_out = yaw_out + yaw_offset;
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out + (g.heli_servo_2.radio_trim-1500);
if( g.heli_servo_2.get_reverse() )
g.heli_servo_2.servo_out = 3000 - g.heli_servo_2.servo_out;
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out + (g.heli_servo_3.radio_trim-1500);
if( g.heli_servo_3.get_reverse() )
g.heli_servo_3.servo_out = 3000 - g.heli_servo_3.servo_out;
g.heli_servo_4.servo_out = yaw_out;
// use servo_out to calculate pwm_out and radio_out // use servo_out to calculate pwm_out and radio_out
g.heli_servo_1.calc_pwm(); g.heli_servo_1.calc_pwm();
@ -109,9 +125,9 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
g.heli_servo_4.calc_pwm(); g.heli_servo_4.calc_pwm();
// add the servo values to the averaging // add the servo values to the averaging
heli_servo_out[0] += g.heli_servo_1.servo_out; heli_servo_out[0] += g.heli_servo_1.radio_out;
heli_servo_out[1] += g.heli_servo_2.servo_out; heli_servo_out[1] += g.heli_servo_2.radio_out;
heli_servo_out[2] += g.heli_servo_3.servo_out; heli_servo_out[2] += g.heli_servo_3.radio_out;
heli_servo_out[3] += g.heli_servo_4.radio_out; heli_servo_out[3] += g.heli_servo_4.radio_out;
heli_servo_out_count++; heli_servo_out_count++;
@ -164,19 +180,21 @@ static void init_motors_out()
// 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 // these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
static void output_motors_armed() static void output_motors_armed()
{ {
// if manual override (i.e. when setting up swash), pass pilot commands straight through to swash
if( g.heli_servo_manual == 1 ) {
g.rc_1.servo_out = g.rc_1.control_in;
g.rc_2.servo_out = g.rc_2.control_in;
g.rc_3.servo_out = g.rc_3.control_in;
g.rc_4.servo_out = g.rc_4.control_in;
}
//static int counter = 0; //static int counter = 0;
g.rc_1.calc_pwm(); g.rc_1.calc_pwm();
g.rc_2.calc_pwm(); g.rc_2.calc_pwm();
g.rc_3.calc_pwm(); g.rc_3.calc_pwm();
g.rc_4.calc_pwm(); g.rc_4.calc_pwm();
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 );
}else{
// 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 ); heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out );
}
} }
// for helis - armed or disarmed we allow servos to move // for helis - armed or disarmed we allow servos to move
@ -200,7 +218,7 @@ static void output_motor_test()
static int heli_get_scaled_throttle(int throttle) static int heli_get_scaled_throttle(int throttle)
{ {
float scaled_throttle = (g.heli_coll_min - 1000) + throttle * heli_throttle_scaler; float scaled_throttle = (g.heli_coll_min - 1000) + throttle * heli_throttle_scaler;
return g.heli_coll_min - 1000 + (throttle * heli_throttle_scaler); return scaled_throttle;
} }
// heli_angle_boost - takes servo_out position // heli_angle_boost - takes servo_out position

View File

@ -7,7 +7,7 @@ static void init_motors_out()
#if INSTANT_PWM == 0 #if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9 ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10 ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 50 hz output CH 7, 8, 11 ICR3 = 5000; // 400 hz output CH 7, 8, 11
#endif #endif
} }

View File

@ -7,7 +7,7 @@ static void init_motors_out()
#if INSTANT_PWM == 0 #if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9 ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10 ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 50 hz output CH 7, 8, 11 ICR3 = 5000; // 400 hz output CH 7, 8, 11
#endif #endif
} }

View File

@ -7,7 +7,7 @@ static void init_motors_out()
#if INSTANT_PWM == 0 #if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9 ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10 ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 50 hz output CH 7, 8, 11 ICR3 = 5000; // 400 hz output CH 7, 8, 11
#endif #endif
} }

View File

@ -4,13 +4,12 @@
#define YAW_DIRECTION 1 #define YAW_DIRECTION 1
static void init_motors_out() static void init_motors_out()
{ {
#if INSTANT_PWM == 0 #if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9 ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10 ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 50 hz output CH 7, 8, 11 ICR3 = 5000; // 400 hz output CH 7, 8, 11
#endif #endif
} }

View File

@ -30,7 +30,9 @@ static bool check_missed_wp()
{ {
int32_t temp = target_bearing - original_target_bearing; int32_t temp = target_bearing - original_target_bearing;
temp = wrap_180(temp); temp = wrap_180(temp);
return (abs(temp) > 10000); //we pased the waypoint by 10 ° //return (abs(temp) > 10000); //we pased the waypoint by 10 °
// temp testing
return false;
} }
// ------------------------------ // ------------------------------

View File

@ -9,8 +9,8 @@ static void default_dead_zones()
g.rc_1.set_dead_zone(60); g.rc_1.set_dead_zone(60);
g.rc_2.set_dead_zone(60); g.rc_2.set_dead_zone(60);
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
g.rc_3.set_dead_zone(0); g.rc_3.set_dead_zone(20);
g.rc_4.set_dead_zone(60); g.rc_4.set_dead_zone(30);
#else #else
g.rc_3.set_dead_zone(60); g.rc_3.set_dead_zone(60);
g.rc_4.set_dead_zone(200); g.rc_4.set_dead_zone(200);

View File

@ -469,8 +469,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
// initialise swash plate // initialise swash plate
heli_init_swash(); heli_init_swash();
// source swash plate movements directly from // source swash plate movements directly from radio
heli_manual_override = true; g.heli_servo_manual = true;
// display initial settings // display initial settings
report_heli(); report_heli();
@ -495,19 +495,21 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
// read radio although we don't use it yet // read radio although we don't use it yet
read_radio(); read_radio();
// allow swash plate to move
output_motors_armed();
// record min/max // record min/max
if( state == 1 ) { if( state == 1 ) {
if( abs(g.rc_1.control_in) > max_roll ) if( abs(g.rc_1.control_in) > max_roll )
max_roll = abs(g.rc_1.control_in); max_roll = abs(g.rc_1.control_in);
if( abs(g.rc_2.control_in) > max_pitch ) if( abs(g.rc_2.control_in) > max_pitch )
max_pitch = abs(g.rc_2.control_in); max_pitch = abs(g.rc_2.control_in);
if( g.rc_3.radio_in < min_coll ) if( g.rc_3.radio_out < min_coll )
min_coll = g.rc_3.radio_in; min_coll = g.rc_3.radio_out;
if( g.rc_3.radio_in > max_coll ) if( g.rc_3.radio_out > max_coll )
max_coll = g.rc_3.radio_in; max_coll = g.rc_3.radio_out;
min_tail = min(g.rc_4.radio_in, min_tail); min_tail = min(g.rc_4.radio_out, min_tail);
max_tail = max(g.rc_4.radio_in, max_tail); max_tail = max(g.rc_4.radio_out, max_tail);
//Serial.printf_P(PSTR("4: ri:%d \tro:%d \tso:%d \n"), (int)g.rc_4.radio_in, (int)g.rc_4.radio_out, (int)g.rc_4.servo_out);
} }
if( Serial.available() ) { if( Serial.available() ) {
@ -533,8 +535,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
break; break;
case 'c': case 'c':
case 'C': case 'C':
if( g.rc_3.radio_in >= 900 && g.rc_3.radio_in <= 2100 ) { if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) {
g.heli_coll_mid = g.rc_3.radio_in; g.heli_coll_mid = g.rc_3.radio_out;
Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_coll_mid); Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_coll_mid);
} }
break; break;
@ -561,7 +563,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
max_pitch = abs(g.rc_2.control_in); max_pitch = abs(g.rc_2.control_in);
min_coll = 2000; min_coll = 2000;
max_coll = 1000; max_coll = 1000;
min_tail = max_tail = abs(g.rc_4.radio_in); min_tail = max_tail = abs(g.rc_4.radio_out);
}else{ }else{
state = 0; // switch back to normal mode state = 0; // switch back to normal mode
// double check values aren't totally terrible // double check values aren't totally terrible
@ -639,9 +641,6 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
} }
} }
// allow swash plate to move
output_motors_armed();
delay(20); delay(20);
} }
@ -664,7 +663,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
g.heli_servo_averaging.save(); g.heli_servo_averaging.save();
// return swash plate movements to attitude controller // return swash plate movements to attitude controller
heli_manual_override = false; g.heli_servo_manual = false;
return(0); return(0);
} }
@ -815,7 +814,7 @@ static void report_batt_monitor()
static void report_wp(byte index = 255) static void report_wp(byte index = 255)
{ {
if(index == 255){ if(index == 255){
for(byte i = 0; i <= g.command_total; i++){ for(byte i = 0; i < g.command_total; i++){
struct Location temp = get_cmd_with_index(i); struct Location temp = get_cmd_with_index(i);
print_wp(&temp, i); print_wp(&temp, i);
} }
@ -1145,14 +1144,17 @@ init_esc()
static void print_wp(struct Location *cmd, byte index) static void print_wp(struct Location *cmd, byte index)
{ {
Serial.printf_P(PSTR("command #: %d id:%d op:%d p1:%d p2:%ld p3:%ld p4:%ld \n"), float t1 = (float)cmd->lat / t7;
float t2 = (float)cmd->lng / t7;
Serial.printf_P(PSTR("scommand #: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"),
(int)index, (int)index,
(int)cmd->id, (int)cmd->id,
(int)cmd->options, (int)cmd->options,
(int)cmd->p1, (int)cmd->p1,
cmd->alt, (long)cmd->alt,
cmd->lat, t1,
cmd->lng); t2);
} }
static void report_gps() static void report_gps()

View File

@ -178,6 +178,7 @@ static void init_ardupilot()
#endif #endif
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
g.heli_servo_manual = false;
heli_init_swash(); // heli initialisation heli_init_swash(); // heli initialisation
#endif #endif
@ -377,42 +378,33 @@ static void set_mode(byte mode)
// report the GPS and Motor arming status // report the GPS and Motor arming status
led_mode = NORMAL_LEDS; led_mode = NORMAL_LEDS;
reset_nav();
switch(control_mode) switch(control_mode)
{ {
case ACRO: case ACRO:
yaw_mode = YAW_ACRO; yaw_mode = YAW_ACRO;
roll_pitch_mode = ROLL_PITCH_ACRO; roll_pitch_mode = ROLL_PITCH_ACRO;
throttle_mode = THROTTLE_MANUAL; throttle_mode = THROTTLE_MANUAL;
reset_hold_I();
break; break;
case STABILIZE: case STABILIZE:
yaw_mode = YAW_HOLD; yaw_mode = YAW_HOLD;
roll_pitch_mode = ROLL_PITCH_STABLE; roll_pitch_mode = ROLL_PITCH_STABLE;
throttle_mode = THROTTLE_MANUAL; throttle_mode = THROTTLE_MANUAL;
reset_hold_I();
break; break;
case ALT_HOLD: case ALT_HOLD:
yaw_mode = ALT_HOLD_YAW; yaw_mode = ALT_HOLD_YAW;
roll_pitch_mode = ALT_HOLD_RP; roll_pitch_mode = ALT_HOLD_RP;
throttle_mode = ALT_HOLD_THR; throttle_mode = ALT_HOLD_THR;
reset_hold_I();
init_throttle_cruise();
next_WP = current_loc; next_WP = current_loc;
break; break;
case AUTO: case AUTO:
reset_hold_I();
yaw_mode = AUTO_YAW; yaw_mode = AUTO_YAW;
roll_pitch_mode = AUTO_RP; roll_pitch_mode = AUTO_RP;
throttle_mode = AUTO_THR; throttle_mode = AUTO_THR;
init_throttle_cruise();
// loads the commands from where we left off // loads the commands from where we left off
init_commands(); init_commands();
break; break;
@ -422,7 +414,6 @@ static void set_mode(byte mode)
roll_pitch_mode = CIRCLE_RP; roll_pitch_mode = CIRCLE_RP;
throttle_mode = CIRCLE_THR; throttle_mode = CIRCLE_THR;
init_throttle_cruise();
next_WP = current_loc; next_WP = current_loc;
break; break;
@ -431,7 +422,6 @@ static void set_mode(byte mode)
roll_pitch_mode = LOITER_RP; roll_pitch_mode = LOITER_RP;
throttle_mode = LOITER_THR; throttle_mode = LOITER_THR;
init_throttle_cruise();
next_WP = current_loc; next_WP = current_loc;
break; break;
@ -448,8 +438,6 @@ static void set_mode(byte mode)
roll_pitch_mode = ROLL_PITCH_AUTO; roll_pitch_mode = ROLL_PITCH_AUTO;
throttle_mode = THROTTLE_AUTO; throttle_mode = THROTTLE_AUTO;
//xtrack_enabled = true;
init_throttle_cruise();
next_WP = current_loc; next_WP = current_loc;
set_next_WP(&guided_WP); set_next_WP(&guided_WP);
break; break;
@ -459,8 +447,6 @@ static void set_mode(byte mode)
roll_pitch_mode = RTL_RP; roll_pitch_mode = RTL_RP;
throttle_mode = RTL_THR; throttle_mode = RTL_THR;
//xtrack_enabled = true;
init_throttle_cruise();
do_RTL(); do_RTL();
break; break;
@ -468,6 +454,22 @@ static void set_mode(byte mode)
break; break;
} }
if(throttle_mode == THROTTLE_MANUAL){
// reset all of the throttle iterms
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();
}else { // an automatic throttle
// todo: replace with a throttle cruise estimator
init_throttle_cruise();
}
if(roll_pitch_mode <= ROLL_PITCH_ACRO){
// We are under manual attitude control
// reset out nav parameters
reset_nav();
}
Log_Write_Mode(control_mode); Log_Write_Mode(control_mode);
} }

View File

@ -70,7 +70,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
{"tri", test_tri}, {"tri", test_tri},
{"current", test_current}, {"current", test_current},
{"relay", test_relay}, {"relay", test_relay},
{"waypoints", test_wp}, {"wp", test_wp},
//{"nav", test_nav}, //{"nav", test_nav},
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
{"altitude", test_baro}, {"altitude", test_baro},
@ -755,6 +755,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
} }
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) { static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) {
/*
print_hit_enter(); print_hit_enter();
delay(1000); delay(1000);
while(1){ while(1){
@ -772,6 +773,7 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) {
return (0); return (0);
} }
} }
*/
} }
/*static int8_t /*static int8_t

View File

@ -17,3 +17,23 @@
/* /*
#define HIL_MODE HIL_MODE_ATTITUDE #define HIL_MODE HIL_MODE_ATTITUDE
*/ */
/*
// HIL_MODE SELECTION
//
// Mavlink supports
// 1. HIL_MODE_ATTITUDE : simulated position, airspeed, and attitude
// 2. HIL_MODE_SENSORS: full sensor simulation
#define HIL_MODE HIL_MODE_ATTITUDE
// Sensors
// All sensors are supported in all modes.
// The magnetometer is not used in
// HIL_MODE_ATTITUDE but you may leave it
// enabled if you wish.
#define AIRSPEED_SENSOR ENABLED
#define MAGNETOMETER ENABLED
#define AIRSPEED_CRUISE 25
#define THROTTLE_FAILSAFE ENABLED
*/
#define GPS_PROTOCOL GPS_NONE

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduPlane V2.24" #define THISFIRMWARE "ArduPlane V2.251"
/* /*
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short
Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi
@ -450,7 +450,9 @@ void loop()
if (millis() - perf_mon_timer > 20000) { if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) { if (mainLoop_count != 0) {
if (g.log_bitmask & MASK_LOG_PM) if (g.log_bitmask & MASK_LOG_PM)
#if HIL_MODE != HIL_MODE_ATTITUDE
Log_Write_Performance(); Log_Write_Performance();
#endif
resetPerfData(); resetPerfData();
} }

View File

@ -53,7 +53,9 @@ print_log_menu(void)
{ {
int log_start; int log_start;
int log_end; int log_end;
byte last_log_num = get_num_logs(); int temp;
uint16_t num_logs = get_num_logs();
//Serial.print("num logs: "); Serial.println(num_logs, DEC);
Serial.printf_P(PSTR("logs enabled: ")); Serial.printf_P(PSTR("logs enabled: "));
if (0 == g.log_bitmask) { if (0 == g.log_bitmask) {
@ -78,15 +80,16 @@ print_log_menu(void)
} }
Serial.println(); Serial.println();
if (last_log_num == 0) { if (num_logs == 0) {
Serial.printf_P(PSTR("\nNo logs available for download\n")); Serial.printf_P(PSTR("\nNo logs available for download\n"));
}else{ }else{
Serial.printf_P(PSTR("\n%d logs available for download\n"), last_log_num); Serial.printf_P(PSTR("\n%d logs available for download\n"), num_logs);
for(int i=1;i<last_log_num+1;i++) { for(int i=num_logs;i>=1;i--) {
get_log_boundaries(i, log_start, log_end); temp = g.log_last_filenumber-i+1;
get_log_boundaries(temp, log_start, log_end);
Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"), Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"),
i, log_start, log_end); temp, log_start, log_end);
} }
Serial.println(); Serial.println();
} }
@ -103,8 +106,8 @@ dump_log(uint8_t argc, const Menu::arg *argv)
// check that the requested log number can be read // check that the requested log number can be read
dump_log = argv[1].i; dump_log = argv[1].i;
last_log_num = get_num_logs(); last_log_num = g.log_last_filenumber;
if ((argc != 2) || (dump_log < 1) || (dump_log > last_log_num)) { if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
Serial.printf_P(PSTR("bad log number\n")); Serial.printf_P(PSTR("bad log number\n"));
return(-1); return(-1);
} }
@ -128,15 +131,13 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
delay(1000); delay(1000);
} }
Serial.printf_P(PSTR("\nErasing log...\n")); Serial.printf_P(PSTR("\nErasing log...\n"));
for(int j = 1; j < 4096; j++) DataFlash.SetFileNumber(0xFFFF);
for(int j = 1; j <= DF_LAST_PAGE; j++) {
DataFlash.PageErase(j); DataFlash.PageErase(j);
DataFlash.StartWrite(1); DataFlash.StartWrite(j); // We need this step to clean FileNumbers
DataFlash.WriteByte(HEAD_BYTE1); }
DataFlash.WriteByte(HEAD_BYTE2); g.log_last_filenumber.set_and_save(0);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(0);
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
Serial.printf_P(PSTR("\nLog erased.\n")); Serial.printf_P(PSTR("\nLog erased.\n"));
return 0; return 0;
} }
@ -192,139 +193,214 @@ process_logs(uint8_t argc, const Menu::arg *argv)
} }
// This function determines the number of whole or partial log files in the DataFlash
// Wholly overwritten files are (of course) lost.
static byte get_num_logs(void) static byte get_num_logs(void)
{ {
int page = 1; uint16_t lastpage;
byte data; uint16_t last;
byte log_step = 0; uint16_t first;
if(g.log_last_filenumber < 1) return 0;
DataFlash.StartRead(1); DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) return 0;
while (page == 1) { lastpage = find_last();
data = DataFlash.ReadByte(); DataFlash.StartRead(lastpage);
last = DataFlash.GetFileNumber();
switch(log_step){ //This is a state machine to read the packets DataFlash.StartRead(lastpage + 2);
case 0: first = DataFlash.GetFileNumber();
if(data==HEAD_BYTE1) // Head byte 1 if(first == 0xFFFF) {
log_step++; DataFlash.StartRead(1);
break; first = DataFlash.GetFileNumber();
case 1:
if(data==HEAD_BYTE2) // Head byte 2
log_step++;
else
log_step = 0;
break;
case 2:
if(data==LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
return num_logs;
}else{
log_step=0; // Restart, we have a problem...
} }
break; if(last == first)
{
return 1;
} else {
return (last - first + 1);
} }
page = DataFlash.GetPage();
}
return 0;
} }
// send the number of the last log? // This function starts a new log file in the DataFlash
static void start_new_log(byte num_existing_logs) static void start_new_log()
{ {
int start_pages[50] = {0,0,0}; uint16_t last_page;
int end_pages[50] = {0,0,0};
if(num_existing_logs > 0) { if(g.log_last_filenumber < 1) {
for(int i=0;i<num_existing_logs;i++) { last_page = 0;
get_log_boundaries(i+1,start_pages[i],end_pages[i]); } else {
} last_page = find_last();
end_pages[num_existing_logs - 1] = find_last_log_page(start_pages[num_existing_logs - 1]);
}
if(num_existing_logs == 0 ||
(end_pages[num_existing_logs - 1] < 4095 && num_existing_logs < MAX_NUM_LOGS)) {
if(num_existing_logs > 0)
start_pages[num_existing_logs] = end_pages[num_existing_logs - 1] + 1;
else
start_pages[0] = 2;
num_existing_logs++;
DataFlash.StartWrite(1);
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(num_existing_logs);
for(int i=0;i<MAX_NUM_LOGS;i++) {
DataFlash.WriteInt(start_pages[i]);
DataFlash.WriteInt(end_pages[i]);
}
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
DataFlash.StartWrite(start_pages[num_existing_logs-1]);
}else{
gcs_send_text_P(SEVERITY_LOW,PSTR("<start_new_log> Logs full - logging discontinued"));
} }
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
DataFlash.SetFileNumber(g.log_last_filenumber);
DataFlash.StartWrite(last_page + 1);
} }
// This function finds the first and last pages of a log file
// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
static void get_log_boundaries(byte log_num, int & start_page, int & end_page) static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
{ {
int page = 1; int num = get_num_logs();
byte data; if(num == 1)
byte log_step = 0;
DataFlash.StartRead(1);
while (page == 1) {
data = DataFlash.ReadByte();
switch(log_step) //This is a state machine to read the packets
{ {
case 0: DataFlash.StartRead(DF_LAST_PAGE);
if(data==HEAD_BYTE1) // Head byte 1 if(DataFlash.GetFileNumber() == 0xFFFF)
log_step++; {
break; start_page = 1;
case 1: end_page = find_last_log_page((uint16_t)log_num);
if(data==HEAD_BYTE2) // Head byte 2 } else {
log_step++; end_page = find_last_log_page((uint16_t)log_num);
else start_page = end_page + 1;
log_step = 0;
break;
case 2:
if(data==LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
for(int i=0;i<log_num;i++) {
start_page = DataFlash.ReadInt();
end_page = DataFlash.ReadInt();
} }
if(log_num==num_logs)
end_page = find_last_log_page(start_page);
return; // This is the normal exit point } else {
}else{ end_page = find_last_log_page((uint16_t)log_num);
log_step=0; // Restart, we have a problem... if(log_num==1)
start_page = 1;
else
if(log_num == g.log_last_filenumber - num + 1) {
start_page = find_last_log_page(g.log_last_filenumber) + 1;
} else {
start_page = find_last_log_page((uint16_t)(log_num-1)) + 1;
} }
break;
} }
page = DataFlash.GetPage(); if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
}
// Error condition if we reach here with page = 2 TO DO - report condition
} }
static int find_last_log_page(int bottom_page) // This function finds the last page of the last file
// It also cleans up in the situation where a file was initiated, but no pages written
static int find_last(void)
{ {
int top_page = 4096; int16_t num;
int look_page; do
int32_t check; {
num = find_last_log_page(g.log_last_filenumber);
if (num == -1) g.log_last_filenumber.set_and_save(g.log_last_filenumber - 1);
} while (num == -1);
return num;
}
// This function finds the last page of a particular log file
static int find_last_log_page(uint16_t log_number)
{
int16_t bottom_page;
int16_t top_page;
int16_t bottom_page_file;
int16_t bottom_page_filepage;
int16_t top_page_file;
int16_t top_page_filepage;
int16_t look_page;
int16_t look_page_file;
int16_t look_page_filepage;
int16_t check;
bool XLflag = false;
// First see if the logs are empty
DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) {
return 0;
}
// Next, see if logs wrap the top of the dataflash
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
{
// This case is that we have not wrapped the top of the dataflash
top_page = DF_LAST_PAGE;
bottom_page = 1;
while((top_page - bottom_page) > 1) { while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2; look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page); DataFlash.StartRead(look_page);
check = DataFlash.ReadLong(); if(DataFlash.GetFileNumber() > log_number)
if(check == -1L)
top_page = look_page; top_page = look_page;
else else
bottom_page = look_page; bottom_page = look_page;
} }
return top_page; return bottom_page;
} else {
// The else case is that the logs do wrap the top of the dataflash
bottom_page = 1;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
top_page_filepage = DataFlash.GetFilePage();
// Check is we have exactly filled the dataflash but not wrapped. If so we can exit quickly.
if(top_page_file == log_number && bottom_page_file != log_number) {
return top_page_file;
}
// Check if the top is 1 file higher than we want. If so we can exit quickly.
if(top_page_file == log_number+1) {
return top_page - top_page_filepage;
}
// Check if the file has partially overwritten itself
if(top_page_filepage >= DF_LAST_PAGE) {
XLflag = true;
} else {
top_page = top_page - top_page_filepage;
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
}
if(top_page_file == log_number) {
bottom_page = top_page;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(top_page);
top_page_filepage = DataFlash.GetFilePage();
if(XLflag) bottom_page = 1;
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
if(DataFlash.GetFilePage() < top_page_filepage)
{
top_page = look_page;
top_page_filepage = DataFlash.GetFilePage();
} else {
bottom_page = look_page;
}
}
return bottom_page;
}
// Step down through the files to find the one we want
bottom_page = top_page;
bottom_page_filepage = top_page_filepage;
do
{
top_page = bottom_page;
bottom_page = bottom_page - bottom_page_filepage;
if(bottom_page < 1) bottom_page = 1;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
} while (bottom_page_file != log_number && bottom_page != 1);
// Deal with stepping down too far due to overwriting a file
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
if(DataFlash.GetFileNumber() < log_number)
top_page = look_page;
else
bottom_page = look_page;
}
// The -1 return is for the case where a very short power up increments the log
// number counter but no log file is actually created. This happens if power is
// removed before the first page is written to flash.
if(bottom_page ==1 && DataFlash.GetFileNumber() != log_number) return -1;
return bottom_page;
}
} }
@ -341,6 +417,7 @@ static void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw)
} }
// Write a performance monitoring packet. Total length : 19 bytes // Write a performance monitoring packet. Total length : 19 bytes
#if HIL_MODE != HIL_MODE_ATTITUDE
static void Log_Write_Performance() static void Log_Write_Performance()
{ {
DataFlash.WriteByte(HEAD_BYTE1); DataFlash.WriteByte(HEAD_BYTE1);
@ -355,9 +432,13 @@ static void Log_Write_Performance()
DataFlash.WriteByte(dcm.renorm_blowup_count); DataFlash.WriteByte(dcm.renorm_blowup_count);
DataFlash.WriteByte(gps_fix_count); DataFlash.WriteByte(gps_fix_count);
DataFlash.WriteInt((int)(dcm.get_health() * 1000)); DataFlash.WriteInt((int)(dcm.get_health() * 1000));
DataFlash.WriteInt((int)(dcm.get_integrator().x * 1000));
DataFlash.WriteInt((int)(dcm.get_integrator().y * 1000));
DataFlash.WriteInt((int)(dcm.get_integrator().z * 1000));
DataFlash.WriteInt(pmTest1); DataFlash.WriteInt(pmTest1);
DataFlash.WriteByte(END_BYTE); DataFlash.WriteByte(END_BYTE);
} }
#endif
// Write a command processing packet. Total length : 19 bytes // Write a command processing packet. Total length : 19 bytes
//void Log_Write_Cmd(byte num, byte id, byte p1, long alt, long lat, long lng) //void Log_Write_Cmd(byte num, byte id, byte p1, long alt, long lat, long lng)
@ -547,7 +628,7 @@ static void Log_Read_Performance()
pm_time = DataFlash.ReadLong(); pm_time = DataFlash.ReadLong();
Serial.print(pm_time); Serial.print(pm_time);
Serial.print(comma); Serial.print(comma);
for (int y = 1; y <= 9; y++) { for (int y = 1; y <= 12; y++) {
if(y < 3 || y > 7){ if(y < 3 || y > 7){
logvar = DataFlash.ReadInt(); logvar = DataFlash.ReadInt();
}else{ }else{
@ -642,10 +723,7 @@ static void Log_Read_Raw()
// Read the DataFlash log memory : Packet Parser // Read the DataFlash log memory : Packet Parser
static void Log_Read(int start_page, int end_page) static void Log_Read(int start_page, int end_page)
{ {
byte data;
byte log_step = 0;
int packet_count = 0; int packet_count = 0;
int page = start_page;
#ifdef AIRFRAME_NAME #ifdef AIRFRAME_NAME
Serial.printf_P(PSTR((AIRFRAME_NAME) Serial.printf_P(PSTR((AIRFRAME_NAME)
@ -654,6 +732,25 @@ static void Log_Read(int start_page, int end_page)
"\nFree RAM: %u\n"), "\nFree RAM: %u\n"),
memcheck_available_memory()); memcheck_available_memory());
if(start_page > end_page)
{
packet_count = Log_Read_Process(start_page, DF_LAST_PAGE);
packet_count += Log_Read_Process(1, end_page);
} else {
packet_count = Log_Read_Process(start_page, end_page);
}
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
}
// Read the DataFlash log memory : Packet Parser
static int Log_Read_Process(int start_page, int end_page)
{
byte data;
byte log_step = 0;
int page = start_page;
int packet_count = 0;
DataFlash.StartRead(start_page); DataFlash.StartRead(start_page);
while (page < end_page && page != -1){ while (page < end_page && page != -1){
data = DataFlash.ReadByte(); data = DataFlash.ReadByte();
@ -726,7 +823,7 @@ static void Log_Read(int start_page, int end_page)
} }
page = DataFlash.GetPage(); page = DataFlash.GetPage();
} }
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count); return packet_count;
} }
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
@ -742,7 +839,7 @@ static void Log_Write_GPS( long log_Time, long log_Lattitude, long log_Longitude
static void Log_Write_Performance() {} static void Log_Write_Performance() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
static byte get_num_logs(void) { return 0; } static byte get_num_logs(void) { return 0; }
static void start_new_log(byte num_existing_logs) {} static void start_new_log() {}
static void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw) {} static void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw) {}
static void Log_Write_Control_Tuning() {} static void Log_Write_Control_Tuning() {}
static void Log_Write_Raw() {} static void Log_Write_Raw() {}

View File

@ -69,6 +69,7 @@ public:
k_param_flap_2_percent, k_param_flap_2_percent,
k_param_flap_2_speed, k_param_flap_2_speed,
k_param_num_resets, k_param_num_resets,
k_param_log_last_filenumber,
// 110: Telemetry control // 110: Telemetry control
@ -305,6 +306,7 @@ public:
AP_Int8 reverse_ch2_elevon; AP_Int8 reverse_ch2_elevon;
AP_Int16 num_resets; AP_Int16 num_resets;
AP_Int16 log_bitmask; AP_Int16 log_bitmask;
AP_Int16 log_last_filenumber;
AP_Int16 airspeed_cruise; AP_Int16 airspeed_cruise;
AP_Int16 pitch_trim; AP_Int16 pitch_trim;
AP_Int16 RTL_altitude; AP_Int16 RTL_altitude;
@ -410,6 +412,7 @@ public:
reverse_ch2_elevon (ELEVON_CH2_REVERSE, k_param_reverse_ch2_elevon, PSTR("ELEVON_CH2_REV")), reverse_ch2_elevon (ELEVON_CH2_REVERSE, k_param_reverse_ch2_elevon, PSTR("ELEVON_CH2_REV")),
num_resets (0, k_param_num_resets, PSTR("SYS_NUM_RESETS")), num_resets (0, k_param_num_resets, PSTR("SYS_NUM_RESETS")),
log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")), log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")),
log_last_filenumber (0, k_param_log_last_filenumber, PSTR("LOG_LASTFILE")),
airspeed_cruise (AIRSPEED_CRUISE_CM, k_param_airspeed_cruise, PSTR("TRIM_ARSPD_CM")), airspeed_cruise (AIRSPEED_CRUISE_CM, k_param_airspeed_cruise, PSTR("TRIM_ARSPD_CM")),
pitch_trim (0, k_param_pitch_trim, PSTR("TRIM_PITCH_CD")), pitch_trim (0, k_param_pitch_trim, PSTR("TRIM_PITCH_CD")),
RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")), RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),

View File

@ -469,19 +469,30 @@ static void do_loiter_at_location()
static void do_jump() static void do_jump()
{ {
struct Location temp; struct Location temp;
gcs_send_text_fmt(PSTR("In jump. Jumps left: %i"),next_nonnav_command.lat);
if(next_nonnav_command.lat > 0) { if(next_nonnav_command.lat > 0) {
nav_command_ID = NO_COMMAND; nav_command_ID = NO_COMMAND;
next_nav_command.id = NO_COMMAND;
non_nav_command_ID = NO_COMMAND; non_nav_command_ID = NO_COMMAND;
temp = get_cmd_with_index(g.command_index); temp = get_cmd_with_index(g.command_index);
temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter
set_cmd_with_index(temp, g.command_index); set_cmd_with_index(temp, g.command_index);
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
g.command_index.set_and_save(next_nonnav_command.p1 - 1); g.command_index.set_and_save(next_nonnav_command.p1 - 1);
nav_command_index = next_nonnav_command.p1 - 1;
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
process_next_command();
} else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever } else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever
nav_command_ID = NO_COMMAND; nav_command_ID = NO_COMMAND;
non_nav_command_ID = NO_COMMAND; non_nav_command_ID = NO_COMMAND;
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
g.command_index.set_and_save(next_nonnav_command.p1 - 1); g.command_index.set_and_save(next_nonnav_command.p1 - 1);
nav_command_index = next_nonnav_command.p1 - 1;
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
process_next_command();
} }
} }

View File

@ -16,8 +16,8 @@ static void change_command(uint8_t cmd_index)
non_nav_command_ID = NO_COMMAND; non_nav_command_ID = NO_COMMAND;
nav_command_index = cmd_index - 1; nav_command_index = cmd_index - 1;
g.command_index.set_and_save(cmd_index - 1); g.command_index.set_and_save(cmd_index);
process_next_command(); update_commands();
} }
} }
@ -25,12 +25,10 @@ static void change_command(uint8_t cmd_index)
// -------------------- // --------------------
static void update_commands(void) static void update_commands(void)
{ {
if(home_is_set == false){
return; // don't do commands
}
if(control_mode == AUTO){ if(control_mode == AUTO){
if(home_is_set == true && g.command_total > 1){
process_next_command(); process_next_command();
}
} // Other (eg GCS_Auto) modes may be implemented here } // Other (eg GCS_Auto) modes may be implemented here
} }
@ -63,7 +61,9 @@ static void process_next_command()
nav_command_index++; nav_command_index++;
temp = get_cmd_with_index(nav_command_index); temp = get_cmd_with_index(nav_command_index);
} }
gcs_send_text_fmt(PSTR("Nav command index updated to #%i"),nav_command_index); gcs_send_text_fmt(PSTR("Nav command index updated to #%i"),nav_command_index);
if(nav_command_index > g.command_total){ if(nav_command_index > g.command_total){
// we are out of commands! // we are out of commands!
gcs_send_text_P(SEVERITY_LOW,PSTR("out of commands!")); gcs_send_text_P(SEVERITY_LOW,PSTR("out of commands!"));
@ -100,11 +100,13 @@ static void process_next_command()
non_nav_command_index = nav_command_index; non_nav_command_index = nav_command_index;
non_nav_command_ID = WAIT_COMMAND; non_nav_command_ID = WAIT_COMMAND;
gcs_send_text_fmt(PSTR("Non-Nav command ID updated to #%i"),non_nav_command_ID); gcs_send_text_fmt(PSTR("Non-Nav command ID updated to #%i"),non_nav_command_ID);
} else { // The next command is a non-nav command. Prepare to execute it. } else { // The next command is a non-nav command. Prepare to execute it.
g.command_index.set_and_save(non_nav_command_index); g.command_index.set_and_save(non_nav_command_index);
next_nonnav_command = temp; next_nonnav_command = temp;
non_nav_command_ID = next_nonnav_command.id; non_nav_command_ID = next_nonnav_command.id;
gcs_send_text_fmt(PSTR("Non-Nav command ID updated to #%i"),non_nav_command_ID); gcs_send_text_fmt(PSTR("Non-Nav command ID updated to #%i"),non_nav_command_ID);
if (g.log_bitmask & MASK_LOG_CMD) { if (g.log_bitmask & MASK_LOG_CMD) {
Log_Write_Cmd(g.command_index, &next_nonnav_command); Log_Write_Cmd(g.command_index, &next_nonnav_command);
} }

View File

@ -143,7 +143,7 @@ enum gcs_severity {
#define LOG_STARTUP_MSG 0x0A #define LOG_STARTUP_MSG 0x0A
#define TYPE_AIRSTART_MSG 0x00 #define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01 #define TYPE_GROUNDSTART_MSG 0x01
#define MAX_NUM_LOGS 50 #define MAX_NUM_LOGS 100
#define MASK_LOG_ATTITUDE_FAST (1<<0) #define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1) #define MASK_LOG_ATTITUDE_MED (1<<1)

View File

@ -183,7 +183,7 @@ static void update_crosstrack(void)
static void reset_crosstrack() static void reset_crosstrack()
{ {
crosstrack_bearing = get_bearing(&current_loc, &next_WP); // Used for track following crosstrack_bearing = get_bearing(&prev_WP, &next_WP); // Used for track following
} }
static long get_distance(struct Location *loc1, struct Location *loc2) static long get_distance(struct Location *loc1, struct Location *loc2)

View File

@ -210,10 +210,7 @@ static void init_ardupilot()
#endif // CLI_ENABLED #endif // CLI_ENABLED
if(g.log_bitmask != 0){ if(g.log_bitmask != 0){
// TODO - Here we will check on the length of the last log start_new_log();
// We don't want to create a bunch of little logs due to powering on and off
byte last_log_num = get_num_logs();
start_new_log(last_log_num);
} }
// read in the flight switches // read in the flight switches

View File

@ -2,6 +2,7 @@
using System.Collections.Generic; using System.Collections.Generic;
using System.Linq; using System.Linq;
using System.Text; using System.Text;
using System.Management;
namespace ArdupilotMega namespace ArdupilotMega
{ {
@ -54,6 +55,26 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(500); System.Threading.Thread.Sleep(500);
//HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
if (!MainV2.MAC)
{
ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
foreach (ManagementObject obj2 in searcher.Get())
{
Console.WriteLine("Dependant : " + obj2["Dependent"]);
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
{
return "2560-2";
}
}
}
else
{
int fixme;
}
serialPort.DtrEnable = true; serialPort.DtrEnable = true;
serialPort.BaudRate = 115200; serialPort.BaudRate = 115200;
serialPort.Open(); serialPort.Open();
@ -92,7 +113,7 @@ namespace ArdupilotMega
port = new ArduinoSTK(); port = new ArduinoSTK();
port.BaudRate = 57600; port.BaudRate = 57600;
} }
else if (version == "2560") else if (version == "2560" || version == "2560-2")
{ {
port = new ArduinoSTKv2(); port = new ArduinoSTKv2();
port.BaudRate = 115200; port.BaudRate = 115200;

View File

@ -166,6 +166,7 @@
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\x86\System.Data.SQLite.DLL</HintPath> <HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\x86\System.Data.SQLite.DLL</HintPath>
</Reference> </Reference>
<Reference Include="System.Drawing" /> <Reference Include="System.Drawing" />
<Reference Include="System.Management" />
<Reference Include="System.Speech"> <Reference Include="System.Speech">
<Private>True</Private> <Private>True</Private>
</Reference> </Reference>
@ -539,6 +540,9 @@
<CopyToOutputDirectory>Always</CopyToOutputDirectory> <CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType> <SubType>Designer</SubType>
</Content> </Content>
<Content Include="mavcmd.xml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</Content>
<Content Include="Resources\MAVCmd.zh-Hans.txt" /> <Content Include="Resources\MAVCmd.zh-Hans.txt" />
<Content Include="Resources\MAVParam.zh-Hans.txt" /> <Content Include="Resources\MAVParam.zh-Hans.txt" />
<None Include="Resources\MAVCmd.txt"> <None Include="Resources\MAVCmd.txt">

View File

@ -32,11 +32,14 @@ namespace ArdupilotMega
public struct Locationwp public struct Locationwp
{ {
public byte id; // command id public byte id; // command id
public byte options; ///< options bitmask (1<<0 = relative altitude) public byte options;
public byte p1; // param 1 public float p1; // param 1
public int lat; // Lattitude * 10**7 public float p2; // param 2
public int lng; // Longitude * 10**7 public float p3; // param 3
public int alt; // Altitude in centimeters (meters * 100) public float p4; // param 4
public float lat; // Lattitude * 10**7
public float lng; // Longitude * 10**7
public float alt; // Altitude in centimeters (meters * 100)
}; };
@ -796,6 +799,7 @@ System.ComponentModel.Description("Text under Bar")]
base.OnPaint(e); base.OnPaint(e);
drawlbl(e.Graphics); drawlbl(e.Graphics);
} }
} }
public class HorizontalProgressBar : ProgressBar public class HorizontalProgressBar : ProgressBar

View File

@ -211,7 +211,6 @@ namespace ArdupilotMega
dowindcalc(); dowindcalc();
} }
// Console.WriteLine("Updating CurrentState " + DateTime.Now.Millisecond);
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
{ {

View File

@ -3,11 +3,13 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -25,12 +26,10 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000001 B relay
00000002 T ReadSCP1000() 00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -50,7 +49,6 @@
00000002 b event_undo_value 00000002 b event_undo_value
00000002 b ground_start_avg 00000002 b ground_start_avg
00000002 b airspeed_pressure 00000002 b airspeed_pressure
00000002 b adc
00000002 r comma 00000002 r comma
00000002 b g_gps 00000002 b g_gps
00000002 b pmTest1 00000002 b pmTest1
@ -60,7 +58,6 @@
00000002 d ch2_temp 00000002 d ch2_temp
00000002 b failsafe 00000002 b failsafe
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c 00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c 00000002 r test_gps(unsigned char, Menu::arg const*)::__c
@ -72,6 +69,7 @@
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c 00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c 00000003 r print_log_menu()::__c
00000003 r report_compass()::__c 00000003 r report_compass()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -82,6 +80,7 @@
00000004 b airspeed_raw 00000004 b airspeed_raw
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -123,8 +122,6 @@
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(bool)::__c 00000004 r print_enabled(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -214,14 +211,14 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a r __menu_name__main_menu 00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r report_compass()::__c 0000000a r report_compass()::__c
0000000a r report_throttle()::__c 0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -232,31 +229,30 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c 0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_gains()::__c 0000000b r report_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c 0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c 0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c 0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
@ -267,6 +263,9 @@
0000000d r print_log_menu()::__c 0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__c 0000000d r Log_Read_Startup()::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -287,6 +286,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6> 0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
@ -296,10 +296,10 @@
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c 0000000e r report_gains()::__c
0000000e r print_log_menu()::__c 0000000e r print_log_menu()::__c
0000000e r control_failsafe(unsigned int)::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c 0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c 0000000e r report_flight_modes()::__c
@ -325,23 +325,25 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r report_gains()::__c 0000000f r report_gains()::__c
0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c 0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c 00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -349,17 +351,18 @@
00000010 r Log_Read_Startup()::__c 00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status 00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c 00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c 00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -372,6 +375,7 @@
00000012 r print_done()::__c 00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r init_barometer()::__c 00000012 r init_barometer()::__c
00000012 r handle_no_commands()::__c
00000012 r startup_IMU_ground()::__c 00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
@ -391,11 +395,11 @@
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c 00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c 00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c 00000015 r report_gains()::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c 00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
@ -403,21 +407,22 @@
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c 00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c 00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c 00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c 00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c 00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c 00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c 00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
0000001a r reset_control_switch()::__c 00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c 0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -434,12 +439,12 @@
0000001d r startup_ground()::__c 0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c 0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings 0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c 0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c 00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c 00000020 r init_barometer()::__c
@ -447,7 +452,10 @@
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -459,23 +467,22 @@
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c 00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c 00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c 00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -485,71 +492,75 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c 0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c 0000002a r startup_ground()::__c
0000002b r verify_must()::__c 0000002a r verify_nav_command()::__c
0000002a t _mav_put_int8_t_array
0000002b r test_battery(unsigned char, Menu::arg const*)::__c 0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c 0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*) 00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*) 00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c 00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c 00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c 00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c 00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio() 00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c 00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t report_imu() 0000003a t report_imu()
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char) 0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e t verify_RTL() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000043 r Log_Read_GPS()::__c 00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c 00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c 00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c 0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*) 0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode() 0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_divider() 00000054 t print_divider()
00000054 t print_enabled(bool) 00000054 t print_enabled(bool)
00000054 t report_flight_modes() 00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char) 00000056 T GCS_MAVLINK::queued_waypoint_send()
00000058 t radio_input_switch() 00000058 t radio_input_switch()
0000005a t update_GPS_light() 0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
@ -557,143 +568,158 @@
0000005c t readSwitch() 0000005c t readSwitch()
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000062 t print_switch(unsigned char, unsigned char) 00000062 t print_switch(unsigned char, unsigned char)
00000064 t Log_Write_Attitude(int, int, unsigned int) 00000064 t Log_Write_Attitude(int, int, unsigned int)
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom() 00000068 t zero_eeprom()
00000068 t find_last_log_page(int) 00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_show(unsigned char, Menu::arg const*) 0000006c t setup_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*) 0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
00000076 t startup_IMU_ground() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000078 t read_control_switch() 00000078 t read_control_switch()
0000007c t failsafe_short_on_event() 0000007c t send_gps_status(mavlink_channel_t)
0000007c t do_RTL()
0000007e t test_rawgps(unsigned char, Menu::arg const*) 0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands 00000080 r setup_menu_commands
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
00000086 t Log_Read_Attitude() 00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*) 0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
0000008c t print_accel_offsets() 0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c 0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL() 0000008e t handle_no_commands()
0000008e t failsafe_short_on_event()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char) 00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009c t print_PID(PID*) 0000009c t print_PID(PID*)
0000009d B gcs 0000009c B gcs0
0000009d B hil 0000009c B gcs3
000000a0 t report_xtrack() 000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd() 000000a4 t Log_Read_Cmd()
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ac t Log_Read_Performance() 000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t Log_Read_Startup() 000000b2 t Log_Read_Startup()
000000b4 t test_relay(unsigned char, Menu::arg const*)
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass 000000b7 b compass
000000bc t Log_Read_Control_Tuning() 000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle() 000000c0 t report_throttle()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c7 B dcm 000000c7 B dcm
000000ca t send_radio_out(mavlink_channel_t)
000000ca t test_modeswitch(unsigned char, Menu::arg const*) 000000ca t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed() 000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp() 000000d4 t trim_radio()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c 000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*) 000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*) 000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current() 000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*) 00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
00000110 t test_radio(unsigned char, Menu::arg const*) 00000110 t test_radio(unsigned char, Menu::arg const*)
00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t startup_ground() 00000112 t send_servo_out(mavlink_channel_t)
00000112 t report_batt_monitor() 00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer() 00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*) 00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*) 00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 t set_cmd_with_index(Location, int)
00000130 r test_menu_commands 00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000013e t handle_process_condition_command()
00000146 t select_logs(unsigned char, Menu::arg const*) 00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may() 00000146 t send_vfr_hud(mavlink_channel_t)
0000014e T GCS_MAVLINK::update()
00000152 t report_gains() 00000152 t report_gains()
00000152 t verify_condition_command()
0000015a t test_airspeed(unsigned char, Menu::arg const*) 0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*) 0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must() 0000016c t navigate()
0000016a t set_guided_WP() 0000016e t send_attitude(mavlink_channel_t)
00000172 t navigate()
00000174 t report_compass() 00000174 t report_compass()
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning() 0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*) 00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
000001ae T init_home() 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000192 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019c t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
000001bc t send_nav_controller_output(mavlink_channel_t)
000001be t Log_Read_GPS() 000001be t Log_Read_GPS()
000001c8 t read_airspeed() 000001c0 t read_airspeed()
000001ca t mavlink_delay(unsigned long) 000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001ca t start_new_log(unsigned char) 000001d2 T GCS_MAVLINK::update()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001ec t init_barometer() 000001ea t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*) 00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle() 00000208 t calc_throttle()
00000226 t Log_Read(int, int) 00000216 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
0000022a t send_gps_raw(mavlink_channel_t)
0000022c t process_next_command()
0000022c t test_wp(unsigned char, Menu::arg const*) 0000022c t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char) 00000230 t verify_nav_command()
00000232 t verify_must()
0000023e t print_radio_values() 0000023e t print_radio_values()
0000024c t update_loiter() 0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*) 0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
0000031e t read_battery() 0000031e t test_mag(unsigned char, Menu::arg const*)
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
00000404 t process_next_command() 000003e6 t read_battery()
0000041c t set_servos()
0000044c t print_log_menu() 0000044c t print_log_menu()
000004b2 t mavlink_parse_char 000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int) 0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot() 0000064a t init_ardupilot()
00000831 b g 00000920 W Parameters::Parameters()
0000090a W Parameters::Parameters() 0000092b b g
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*) 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001cbe T loop
00001ae8 T loop

View File

@ -3,11 +3,13 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -25,12 +26,10 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000001 B relay
00000002 T ReadSCP1000() 00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -50,7 +49,6 @@
00000002 b event_undo_value 00000002 b event_undo_value
00000002 b ground_start_avg 00000002 b ground_start_avg
00000002 b airspeed_pressure 00000002 b airspeed_pressure
00000002 b adc
00000002 r comma 00000002 r comma
00000002 b g_gps 00000002 b g_gps
00000002 b pmTest1 00000002 b pmTest1
@ -60,7 +58,6 @@
00000002 d ch2_temp 00000002 d ch2_temp
00000002 b failsafe 00000002 b failsafe
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c 00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c 00000002 r test_gps(unsigned char, Menu::arg const*)::__c
@ -72,6 +69,7 @@
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c 00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c 00000003 r print_log_menu()::__c
00000003 r report_compass()::__c 00000003 r report_compass()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -82,6 +80,7 @@
00000004 b airspeed_raw 00000004 b airspeed_raw
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -123,8 +122,6 @@
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(bool)::__c 00000004 r print_enabled(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -214,14 +211,14 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a r __menu_name__main_menu 00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r report_compass()::__c 0000000a r report_compass()::__c
0000000a r report_throttle()::__c 0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -232,31 +229,30 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c 0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_gains()::__c 0000000b r report_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c 0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c 0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c 0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
@ -267,6 +263,9 @@
0000000d r print_log_menu()::__c 0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__c 0000000d r Log_Read_Startup()::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -287,6 +286,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6> 0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
@ -296,10 +296,10 @@
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c 0000000e r report_gains()::__c
0000000e r print_log_menu()::__c 0000000e r print_log_menu()::__c
0000000e r control_failsafe(unsigned int)::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c 0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c 0000000e r report_flight_modes()::__c
@ -325,23 +325,25 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r report_gains()::__c 0000000f r report_gains()::__c
0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c 0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c 00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -349,17 +351,18 @@
00000010 r Log_Read_Startup()::__c 00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status 00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c 00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c 00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -372,6 +375,7 @@
00000012 r print_done()::__c 00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r init_barometer()::__c 00000012 r init_barometer()::__c
00000012 r handle_no_commands()::__c
00000012 r startup_IMU_ground()::__c 00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
@ -391,11 +395,11 @@
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c 00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c 00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c 00000015 r report_gains()::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c 00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
@ -403,21 +407,22 @@
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c 00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c 00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c 00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c 00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c 00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c 00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c 00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
0000001a r reset_control_switch()::__c 00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c 0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -434,12 +439,12 @@
0000001d r startup_ground()::__c 0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c 0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings 0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c 0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c 00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c 00000020 r init_barometer()::__c
@ -447,7 +452,10 @@
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -459,23 +467,22 @@
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c 00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c 00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c 00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -485,71 +492,75 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c 0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c 0000002a r startup_ground()::__c
0000002b r verify_must()::__c 0000002a r verify_nav_command()::__c
0000002a t _mav_put_int8_t_array
0000002b r test_battery(unsigned char, Menu::arg const*)::__c 0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c 0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*) 00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*) 00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c 00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c 00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c 00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c 00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio() 00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c 00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t report_imu() 0000003a t report_imu()
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char) 0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e t verify_RTL() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000043 r Log_Read_GPS()::__c 00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c 00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c 00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c 0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*) 0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode() 0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_divider() 00000054 t print_divider()
00000054 t print_enabled(bool) 00000054 t print_enabled(bool)
00000054 t report_flight_modes() 00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char) 00000056 T GCS_MAVLINK::queued_waypoint_send()
00000058 t radio_input_switch() 00000058 t radio_input_switch()
0000005a t update_GPS_light() 0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
@ -558,142 +569,157 @@
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char) 00000060 t print_switch(unsigned char, unsigned char)
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t Log_Write_Attitude(int, int, unsigned int) 00000064 t Log_Write_Attitude(int, int, unsigned int)
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom() 00000068 t zero_eeprom()
00000068 t find_last_log_page(int) 00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_show(unsigned char, Menu::arg const*) 0000006c t setup_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*) 0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
00000076 t startup_IMU_ground() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000078 t read_control_switch() 00000078 t read_control_switch()
0000007c t failsafe_short_on_event() 0000007c t send_gps_status(mavlink_channel_t)
0000007c t do_RTL()
0000007e t test_rawgps(unsigned char, Menu::arg const*) 0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands 00000080 r setup_menu_commands
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
00000086 t Log_Read_Attitude() 00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*) 0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
0000008c t print_accel_offsets() 0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c 0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL() 0000008e t failsafe_short_on_event()
00000090 t handle_no_commands()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char) 00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009c t print_PID(PID*) 0000009c t print_PID(PID*)
0000009d B gcs 0000009c B gcs0
0000009d B hil 0000009c B gcs3
000000a0 t report_xtrack() 000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd() 000000a4 t Log_Read_Cmd()
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ac t Log_Read_Performance() 000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b0 t Log_Read_Startup() 000000b0 t Log_Read_Startup()
000000b4 t test_relay(unsigned char, Menu::arg const*)
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass 000000b7 b compass
000000bc t Log_Read_Control_Tuning() 000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle() 000000c0 t report_throttle()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c4 t update_events() 000000c6 t zero_airspeed()
000000c4 t load_next_command_from_EEPROM() 000000c6 t startup_ground()
000000c7 B dcm 000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*) 000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t send_radio_out(mavlink_channel_t)
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed() 000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp() 000000d4 t trim_radio()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c 000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*) 000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*) 000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current() 000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*) 00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
00000110 t test_radio(unsigned char, Menu::arg const*) 00000110 t test_radio(unsigned char, Menu::arg const*)
00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t startup_ground() 00000112 t send_servo_out(mavlink_channel_t)
00000112 t report_batt_monitor() 00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*) 00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer() 00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*) 00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 t set_cmd_with_index(Location, int)
00000130 r test_menu_commands 00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000013e t handle_process_condition_command()
00000146 t select_logs(unsigned char, Menu::arg const*) 00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may() 00000146 t send_vfr_hud(mavlink_channel_t)
0000014e T GCS_MAVLINK::update()
00000152 t report_gains() 00000152 t report_gains()
00000152 t verify_condition_command()
00000158 t test_airspeed(unsigned char, Menu::arg const*) 00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*) 0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must() 0000016c t navigate()
0000016a t set_guided_WP() 0000016e t send_attitude(mavlink_channel_t)
00000172 t navigate()
00000174 t report_compass() 00000174 t report_compass()
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning() 0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*) 00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
000001ae T init_home() 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000190 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019a t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
000001bc t send_nav_controller_output(mavlink_channel_t)
000001be t Log_Read_GPS() 000001be t Log_Read_GPS()
000001c8 t read_airspeed() 000001c0 t read_airspeed()
000001ca t mavlink_delay(unsigned long) 000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001ca t start_new_log(unsigned char) 000001d2 T GCS_MAVLINK::update()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001ec t init_barometer() 000001ea t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*) 000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle() 00000208 t calc_throttle()
00000222 t Log_Read(int, int) 00000210 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t test_wp(unsigned char, Menu::arg const*) 00000228 t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t)
00000232 t verify_must() 0000022c t process_next_command()
00000230 t verify_nav_command()
0000023e t print_radio_values() 0000023e t print_radio_values()
0000024c t update_loiter() 0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*) 0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
0000031e t read_battery() 0000031e t test_mag(unsigned char, Menu::arg const*)
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
00000404 t process_next_command() 000003e6 t read_battery()
0000041c t set_servos()
00000436 t print_log_menu() 00000436 t print_log_menu()
000004b2 t mavlink_parse_char 000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int) 0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot() 00000648 t init_ardupilot()
00000831 b g 00000920 W Parameters::Parameters()
0000090a W Parameters::Parameters() 0000092b b g
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*) 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001cbe T loop
00001ae8 T loop

View File

@ -3,11 +3,13 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -25,12 +26,10 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000001 B relay
00000002 T ReadSCP1000() 00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -50,7 +49,6 @@
00000002 b event_undo_value 00000002 b event_undo_value
00000002 b ground_start_avg 00000002 b ground_start_avg
00000002 b airspeed_pressure 00000002 b airspeed_pressure
00000002 b adc
00000002 r comma 00000002 r comma
00000002 b g_gps 00000002 b g_gps
00000002 b pmTest1 00000002 b pmTest1
@ -60,7 +58,6 @@
00000002 d ch2_temp 00000002 d ch2_temp
00000002 b failsafe 00000002 b failsafe
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c 00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c 00000002 r test_gps(unsigned char, Menu::arg const*)::__c
@ -72,6 +69,7 @@
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c 00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c 00000003 r print_log_menu()::__c
00000003 r report_compass()::__c 00000003 r report_compass()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -82,6 +80,7 @@
00000004 b airspeed_raw 00000004 b airspeed_raw
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -123,8 +122,6 @@
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(bool)::__c 00000004 r print_enabled(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -214,14 +211,14 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a r __menu_name__main_menu 00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r report_compass()::__c 0000000a r report_compass()::__c
0000000a r report_throttle()::__c 0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -232,31 +229,30 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c 0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_gains()::__c 0000000b r report_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c 0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c 0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c 0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
@ -267,6 +263,9 @@
0000000d r print_log_menu()::__c 0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__c 0000000d r Log_Read_Startup()::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -287,6 +286,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6> 0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
@ -296,10 +296,10 @@
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c 0000000e r report_gains()::__c
0000000e r print_log_menu()::__c 0000000e r print_log_menu()::__c
0000000e r control_failsafe(unsigned int)::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c 0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c 0000000e r report_flight_modes()::__c
@ -325,23 +325,25 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r report_gains()::__c 0000000f r report_gains()::__c
0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c 0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c 00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -349,17 +351,18 @@
00000010 r Log_Read_Startup()::__c 00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status 00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c 00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c 00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -372,6 +375,7 @@
00000012 r print_done()::__c 00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r init_barometer()::__c 00000012 r init_barometer()::__c
00000012 r handle_no_commands()::__c
00000012 r startup_IMU_ground()::__c 00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
@ -391,11 +395,11 @@
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c 00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c 00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c 00000015 r report_gains()::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c 00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
@ -403,21 +407,22 @@
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c 00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c 00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c 00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c 00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c 00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c 00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c 00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
0000001a r reset_control_switch()::__c 00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c 0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -434,12 +439,12 @@
0000001d r startup_ground()::__c 0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c 0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings 0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c 0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c 00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c 00000020 r init_barometer()::__c
@ -447,7 +452,10 @@
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -459,23 +467,22 @@
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c 00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c 00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c 00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -485,71 +492,75 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c 0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c 0000002a r startup_ground()::__c
0000002b r verify_must()::__c 0000002a r verify_nav_command()::__c
0000002a t _mav_put_int8_t_array
0000002b r test_battery(unsigned char, Menu::arg const*)::__c 0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c 0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*) 00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*) 00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c 00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c 00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c 00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c 00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio() 00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c 00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t report_imu() 0000003a t report_imu()
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char) 0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e t verify_RTL() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000043 r Log_Read_GPS()::__c 00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c 00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c 00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c 0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*) 0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode() 0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_divider() 00000054 t print_divider()
00000054 t print_enabled(bool) 00000054 t print_enabled(bool)
00000054 t report_flight_modes() 00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char) 00000056 T GCS_MAVLINK::queued_waypoint_send()
00000058 t radio_input_switch() 00000058 t radio_input_switch()
0000005a t update_GPS_light() 0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
@ -557,143 +568,158 @@
0000005c t readSwitch() 0000005c t readSwitch()
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000062 t print_switch(unsigned char, unsigned char) 00000062 t print_switch(unsigned char, unsigned char)
00000064 t Log_Write_Attitude(int, int, unsigned int) 00000064 t Log_Write_Attitude(int, int, unsigned int)
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom() 00000068 t zero_eeprom()
00000068 t find_last_log_page(int) 00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_show(unsigned char, Menu::arg const*) 0000006c t setup_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*) 0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
00000076 t startup_IMU_ground() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000078 t read_control_switch() 00000078 t read_control_switch()
0000007c t failsafe_short_on_event() 0000007c t send_gps_status(mavlink_channel_t)
0000007c t do_RTL()
0000007e t test_rawgps(unsigned char, Menu::arg const*) 0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands 00000080 r setup_menu_commands
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
00000086 t Log_Read_Attitude() 00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*) 0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
0000008c t print_accel_offsets() 0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c 0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL() 0000008e t handle_no_commands()
0000008e t failsafe_short_on_event()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char) 00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009c t print_PID(PID*) 0000009c t print_PID(PID*)
0000009d B gcs 0000009c B gcs0
0000009d B hil 0000009c B gcs3
000000a0 t report_xtrack() 000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd() 000000a4 t Log_Read_Cmd()
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ac t Log_Read_Performance() 000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t Log_Read_Startup() 000000b2 t Log_Read_Startup()
000000b4 t test_relay(unsigned char, Menu::arg const*)
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass 000000b7 b compass
000000bc t Log_Read_Control_Tuning() 000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle() 000000c0 t report_throttle()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t zero_airspeed()
000000c6 t startup_ground()
000000c7 B dcm 000000c7 B dcm
000000ca t send_radio_out(mavlink_channel_t)
000000ca t test_modeswitch(unsigned char, Menu::arg const*) 000000ca t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed() 000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp() 000000d4 t trim_radio()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c 000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*) 000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*) 000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current() 000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*) 00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
00000110 t test_radio(unsigned char, Menu::arg const*) 00000110 t test_radio(unsigned char, Menu::arg const*)
00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t startup_ground() 00000112 t send_servo_out(mavlink_channel_t)
00000112 t report_batt_monitor() 00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer() 00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*) 00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*) 00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 t set_cmd_with_index(Location, int)
00000130 r test_menu_commands 00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000013e t handle_process_condition_command()
00000146 t select_logs(unsigned char, Menu::arg const*) 00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may() 00000146 t send_vfr_hud(mavlink_channel_t)
0000014e T GCS_MAVLINK::update()
00000152 t report_gains() 00000152 t report_gains()
00000152 t verify_condition_command()
0000015a t test_airspeed(unsigned char, Menu::arg const*) 0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*) 0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must() 0000016c t navigate()
0000016a t set_guided_WP() 0000016e t send_attitude(mavlink_channel_t)
00000172 t navigate()
00000174 t report_compass() 00000174 t report_compass()
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning() 0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*) 00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
000001ae T init_home() 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000192 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019c t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
000001bc t send_nav_controller_output(mavlink_channel_t)
000001be t Log_Read_GPS() 000001be t Log_Read_GPS()
000001c8 t read_airspeed() 000001c0 t read_airspeed()
000001ca t mavlink_delay(unsigned long) 000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001ca t start_new_log(unsigned char) 000001d2 T GCS_MAVLINK::update()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001ec t init_barometer() 000001ea t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*) 00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle() 00000208 t calc_throttle()
00000226 t Log_Read(int, int) 00000216 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
0000022a t send_gps_raw(mavlink_channel_t)
0000022c t process_next_command()
0000022c t test_wp(unsigned char, Menu::arg const*) 0000022c t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char) 00000230 t verify_nav_command()
00000232 t verify_must()
0000023e t print_radio_values() 0000023e t print_radio_values()
0000024c t update_loiter() 0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*) 0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
0000031e t read_battery() 0000031e t test_mag(unsigned char, Menu::arg const*)
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
00000404 t process_next_command() 000003e6 t read_battery()
0000041c t set_servos()
0000044c t print_log_menu() 0000044c t print_log_menu()
000004b2 t mavlink_parse_char 000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int) 0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot() 0000064a t init_ardupilot()
00000831 b g 00000920 W Parameters::Parameters()
0000090a W Parameters::Parameters() 0000092b b g
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*) 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001cbe T loop
00001ae8 T loop

View File

@ -3,11 +3,13 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -25,12 +26,10 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000001 B relay
00000002 T ReadSCP1000() 00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -50,7 +49,6 @@
00000002 b event_undo_value 00000002 b event_undo_value
00000002 b ground_start_avg 00000002 b ground_start_avg
00000002 b airspeed_pressure 00000002 b airspeed_pressure
00000002 b adc
00000002 r comma 00000002 r comma
00000002 b g_gps 00000002 b g_gps
00000002 b pmTest1 00000002 b pmTest1
@ -60,7 +58,6 @@
00000002 d ch2_temp 00000002 d ch2_temp
00000002 b failsafe 00000002 b failsafe
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c 00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c 00000002 r test_gps(unsigned char, Menu::arg const*)::__c
@ -72,6 +69,7 @@
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c 00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c 00000003 r print_log_menu()::__c
00000003 r report_compass()::__c 00000003 r report_compass()::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -82,6 +80,7 @@
00000004 b airspeed_raw 00000004 b airspeed_raw
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -123,8 +122,6 @@
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 r select_logs(unsigned char, Menu::arg const*)::__c 00000004 r select_logs(unsigned char, Menu::arg const*)::__c
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 r print_enabled(bool)::__c 00000004 r print_enabled(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -214,14 +211,14 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
0000000a r __menu_name__main_menu 00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r verify_nav_wp()::__c
0000000a r report_compass()::__c 0000000a r report_compass()::__c
0000000a r report_throttle()::__c 0000000a r report_throttle()::__c
0000000a r test_mag(unsigned char, Menu::arg const*)::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c
@ -232,31 +229,30 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c 0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_gains()::__c 0000000b r report_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c 0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c 0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c 0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c 0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
@ -267,6 +263,9 @@
0000000d r print_log_menu()::__c 0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c 0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__c 0000000d r Log_Read_Startup()::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -287,6 +286,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarA<float, (unsigned char)6> 0000000e V vtable for AP_VarA<float, (unsigned char)6>
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
@ -296,10 +296,10 @@
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c 0000000e r report_gains()::__c
0000000e r print_log_menu()::__c 0000000e r print_log_menu()::__c
0000000e r control_failsafe(unsigned int)::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c 0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c 0000000e r report_flight_modes()::__c
@ -325,23 +325,25 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r report_gains()::__c 0000000f r report_gains()::__c
0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c 0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c 00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
@ -349,17 +351,18 @@
00000010 r Log_Read_Startup()::__c 00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status 00000011 r __menu_name__main_menu
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c 00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c 00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -372,6 +375,7 @@
00000012 r print_done()::__c 00000012 r print_done()::__c
00000012 r select_logs(unsigned char, Menu::arg const*)::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c
00000012 r init_barometer()::__c 00000012 r init_barometer()::__c
00000012 r handle_no_commands()::__c
00000012 r startup_IMU_ground()::__c 00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c 00000012 r report_batt_monitor()::__c
@ -391,11 +395,11 @@
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c 00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c 00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c 00000015 r report_gains()::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c 00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
@ -403,21 +407,22 @@
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c 00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c 00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c 00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c 00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c 00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c 00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c 00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
0000001a r reset_control_switch()::__c 00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001a r Log_Read(int, int)::__c 0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -434,12 +439,12 @@
0000001d r startup_ground()::__c 0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c 0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings 0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c 0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 t gcs_send_message(ap_message)
00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c 00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c 00000020 r init_barometer()::__c
@ -447,7 +452,10 @@
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA() 00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
@ -459,23 +467,22 @@
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c 00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c 00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c 00000026 r print_PID(PID*)::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*) 00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*) 00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
@ -485,71 +492,75 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c 0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c 0000002a r startup_ground()::__c
0000002b r verify_must()::__c 0000002a r verify_nav_command()::__c
0000002a t _mav_put_int8_t_array
0000002b r test_battery(unsigned char, Menu::arg const*)::__c 0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c 0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*) 00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 t test_mode(unsigned char, Menu::arg const*) 00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c 00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c 00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000033 b pending_status
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c 00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c 00000035 r Log_Read_Nav_Tuning()::__c
00000035 r verify_condition_command()::__c
00000036 t report_radio() 00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 b barometer
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c 00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t report_imu() 0000003a t report_imu()
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003c t verify_RTL()
0000003c t Log_Write_Mode(unsigned char) 0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e t verify_RTL() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 b adc
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000043 r Log_Read_GPS()::__c 00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c 00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c 00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c 0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*) 0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode() 0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 b mavlink_queue
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000050 B imu
00000054 t print_divider() 00000054 t print_divider()
00000054 t print_enabled(bool) 00000054 t print_enabled(bool)
00000054 t report_flight_modes() 00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char) 00000056 T GCS_MAVLINK::queued_waypoint_send()
00000058 t radio_input_switch() 00000058 t radio_input_switch()
0000005a t update_GPS_light() 0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
@ -558,142 +569,157 @@
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char) 00000060 t print_switch(unsigned char, unsigned char)
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t Log_Write_Attitude(int, int, unsigned int) 00000064 t Log_Write_Attitude(int, int, unsigned int)
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 t test_xbee(unsigned char, Menu::arg const*)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
00000068 t zero_eeprom() 00000068 t zero_eeprom()
00000068 t find_last_log_page(int) 00000068 t find_last_log_page(int)
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t demo_servos(unsigned char)
0000006a t startup_IMU_ground()
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_show(unsigned char, Menu::arg const*) 0000006c t setup_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*) 0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
00000076 t startup_IMU_ground() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000078 t read_control_switch() 00000078 t read_control_switch()
0000007c t failsafe_short_on_event() 0000007c t send_gps_status(mavlink_channel_t)
0000007c t do_RTL()
0000007e t test_rawgps(unsigned char, Menu::arg const*) 0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands 00000080 r setup_menu_commands
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
00000086 t Log_Read_Attitude() 00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*) 0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
0000008c t print_accel_offsets() 0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c 0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL() 0000008e t failsafe_short_on_event()
00000090 t handle_no_commands()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char) 00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009c t print_PID(PID*) 0000009c t print_PID(PID*)
0000009d B gcs 0000009c B gcs0
0000009d B hil 0000009c B gcs3
000000a0 t report_xtrack() 000000a0 t report_xtrack()
000000a2 t verify_nav_wp()
000000a4 t Log_Read_Cmd() 000000a4 t Log_Read_Cmd()
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ac t Log_Read_Performance() 000000ac t Log_Read_Performance()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b0 t Log_Read_Startup() 000000b0 t Log_Read_Startup()
000000b4 t test_relay(unsigned char, Menu::arg const*)
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b6 t get_log_boundaries(unsigned char, int&, int&)
000000b7 b compass 000000b7 b compass
000000bc t Log_Read_Control_Tuning() 000000bc t Log_Read_Control_Tuning()
000000be t update_events()
000000c0 t report_throttle() 000000c0 t report_throttle()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c4 t update_events() 000000c6 t zero_airspeed()
000000c4 t load_next_command_from_EEPROM() 000000c6 t startup_ground()
000000c7 B dcm 000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*) 000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t send_radio_out(mavlink_channel_t)
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed() 000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp() 000000d4 t trim_radio()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c 000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*) 000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*) 000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current() 000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*) 00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
00000110 t test_radio(unsigned char, Menu::arg const*) 00000110 t test_radio(unsigned char, Menu::arg const*)
00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t startup_ground() 00000112 t send_servo_out(mavlink_channel_t)
00000112 t report_batt_monitor() 00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*) 00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer() 00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*) 00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 t set_cmd_with_index(Location, int)
00000130 r test_menu_commands 00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000013e t handle_process_condition_command()
00000146 t select_logs(unsigned char, Menu::arg const*) 00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may() 00000146 t send_vfr_hud(mavlink_channel_t)
0000014e T GCS_MAVLINK::update()
00000152 t report_gains() 00000152 t report_gains()
00000152 t verify_condition_command()
00000158 t test_airspeed(unsigned char, Menu::arg const*) 00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015e t set_guided_WP()
0000015e t handle_process_nav_cmd()
0000015e t test_gyro(unsigned char, Menu::arg const*) 0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must() 0000016c t navigate()
0000016a t set_guided_WP() 0000016e t send_attitude(mavlink_channel_t)
00000172 t navigate()
00000174 t report_compass() 00000174 t report_compass()
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
0000017e t Log_Read_Nav_Tuning() 0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*) 00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
000001ae T init_home() 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000190 T init_home()
00000192 t test_imu(unsigned char, Menu::arg const*)
0000019a t do_jump()
000001ae t start_new_log(unsigned char)
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001b2 t set_mode(unsigned char)
000001bc t set_next_WP(Location*)
000001bc t send_nav_controller_output(mavlink_channel_t)
000001be t Log_Read_GPS() 000001be t Log_Read_GPS()
000001c8 t read_airspeed() 000001c0 t read_airspeed()
000001ca t mavlink_delay(unsigned long) 000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001ca t start_new_log(unsigned char) 000001d2 T GCS_MAVLINK::update()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001ec t init_barometer() 000001ea t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*) 000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle() 00000208 t calc_throttle()
00000222 t Log_Read(int, int) 00000210 t Log_Read(int, int)
0000021a t send_raw_imu1(mavlink_channel_t)
00000228 t test_wp(unsigned char, Menu::arg const*) 00000228 t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t)
00000232 t verify_must() 0000022c t process_next_command()
00000230 t verify_nav_command()
0000023e t print_radio_values() 0000023e t print_radio_values()
0000024c t update_loiter() 0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*) 0000025c t setup_radio(unsigned char, Menu::arg const*)
00000268 t send_raw_imu3(mavlink_channel_t)
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
0000031e t read_battery() 0000031e t test_mag(unsigned char, Menu::arg const*)
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
00000404 t process_next_command() 000003e6 t read_battery()
0000041c t set_servos()
00000436 t print_log_menu() 00000436 t print_log_menu()
000004b2 t mavlink_parse_char 000004de t set_servos()
0000059c t __static_initialization_and_destruction_0(int, int) 0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot() 00000648 t init_ardupilot()
00000831 b g 00000920 W Parameters::Parameters()
0000090a W Parameters::Parameters() 0000092b b g
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*) 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00001cbe T loop
00001ae8 T loop

View File

@ -3,59 +3,71 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:25: warning: 'bool print_log_menu()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduPlane/Log.pde:745: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used autogenerated: At global scope:
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used autogenerated:34: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -83,11 +95,17 @@ autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'stat
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -96,6 +114,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -24,11 +25,9 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000001 B relay
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -58,11 +57,11 @@
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -71,6 +70,7 @@
00000004 b wp_distance 00000004 b wp_distance
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -106,8 +106,6 @@
00000004 b nav_roll 00000004 b nav_roll
00000004 b nav_pitch 00000004 b nav_pitch
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -135,7 +133,6 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 r __menu_name__planner_menu 00000008 r __menu_name__planner_menu
00000008 W AP_IMU_Shim::update()
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
@ -149,12 +146,13 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r verify_nav_wp()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
@ -162,18 +160,17 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for AP_IMU_Shim 0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r control_failsafe(unsigned int)::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
@ -182,6 +179,9 @@
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -202,6 +202,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> > 0000000e V vtable for AP_VarS<Vector3<float> >
@ -209,7 +210,7 @@
0000000e V vtable for AP_VarT<float> 0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r process_may()::__c 0000000e r control_failsafe(unsigned int)::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
@ -230,12 +231,13 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r failsafe_short_on_event()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
@ -243,15 +245,16 @@
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 t mavlink_get_channel_status
00000011 r set_next_WP(Location*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS() 00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
@ -260,34 +263,39 @@
00000012 W AP_VarT<int>::~AP_VarT() 00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<long>::~AP_VarT() 00000012 W AP_VarT<long>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const 00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r handle_no_commands()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000012 B adc
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r GCS_MAVLINK::update()::__c 00000016 B adc
00000016 B sonar 00000016 B sonar
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a t startup_IMU_ground() 0000001a t startup_IMU_ground()
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int) 0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001e t failsafe_short_off_event()
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
00000020 t gcs_send_message(ap_message)
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -296,117 +304,134 @@
00000022 W AP_VarT<float>::~AP_VarT() 00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r verify_loiter_turns()::__c
00000026 b mavlink_queue
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000028 t increment_WP_index() 00000028 t demo_servos(unsigned char)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const 00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const 00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000028 B imu 0000002a r verify_nav_command()::__c
0000002a t demo_servos(unsigned char) 0000002a t _mav_put_int8_t_array
0000002b r verify_must()::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c 00000030 t send_heartbeat(mavlink_channel_t)
00000030 r verify_may()::__c 00000030 B imu
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r init_ardupilot()::__c
00000033 b pending_status
00000034 t _MAV_RETURN_float 00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r verify_condition_command()::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003a B g_gps_driver 0000003a B g_gps_driver
0000003c t verify_loiter_turns() 0000003c t verify_RTL()
0000003c W RC_Channel::~RC_Channel() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e t verify_RTL()
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000056 t change_command(unsigned char) 00000052 W AP_IMU_Shim::update()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 B dcm 00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart 00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006e t do_RTL()
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
0000007c t failsafe_short_on_event() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000080 t do_RTL() 0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
0000008e t handle_no_commands()
0000008e t failsafe_short_on_event()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
0000009b B gcs0
0000009b B gcs3
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009d B gcs 000000a2 t verify_nav_wp()
0000009d B hil
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ab B compass 000000ab B compass
000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000be t update_events()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c4 t update_events() 000000ca t send_radio_out(mavlink_channel_t)
000000c4 t load_next_command_from_EEPROM()
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000cc t read_control_switch() 000000cc t read_control_switch()
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f4 t _mav_finalize_message_chan_send
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int) 0000010a t mavlink_delay(unsigned long)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t send_servo_out(mavlink_channel_t)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 T GCS_MAVLINK::_queued_send() 00000130 t startup_ground()
00000130 t set_wp_with_index(Location, int) 00000130 t set_cmd_with_index(Location, int)
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000014e t verify_may() 0000013e t handle_process_condition_command()
0000014e T GCS_MAVLINK::update() 00000146 t send_vfr_hud(mavlink_channel_t)
0000016a t process_must() 00000152 t verify_condition_command()
0000016a t set_guided_WP() 0000015e t set_guided_WP()
00000172 t navigate() 0000015e t handle_process_nav_cmd()
0000019e t startup_ground() 0000016c t navigate()
000001ae T init_home() 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000192 T init_home()
0000019c t do_jump()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t set_mode(unsigned char)
000001a2 T GCS_MAVLINK::update()
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001ca t mavlink_delay(unsigned long) 000001bc t set_next_WP(Location*)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001bc t send_nav_controller_output(mavlink_channel_t)
00000206 t set_next_WP(Location*) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001f4 t process_next_command()
00000208 t calc_throttle() 00000208 t calc_throttle()
0000021c t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t)
00000232 t verify_must() 00000230 t verify_nav_command()
0000024c t update_loiter() 0000024c t update_loiter()
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int) 00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
000003c0 t process_next_command() 00000494 t init_ardupilot()
000004b2 t mavlink_parse_char 00000920 W Parameters::Parameters()
00000518 t init_ardupilot() 0000092b b g
00000831 b g 0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000090a W Parameters::Parameters() 00001c82 T loop
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001aac T loop

View File

@ -3,59 +3,71 @@
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
autogenerated:25: warning: 'bool print_log_menu()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduPlane/Log.pde:745: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used autogenerated: At global scope:
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used autogenerated:34: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_RC/APM_RC.o %% libraries/APM_RC/APM_RC.o
%% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC_ADS7844.o
%% libraries/AP_ADC/AP_ADC.o %% libraries/AP_ADC/AP_ADC.o
@ -83,11 +95,17 @@ autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'stat
%% libraries/AP_GPS/AP_GPS_UBLOX.o %% libraries/AP_GPS/AP_GPS_UBLOX.o
%% libraries/AP_GPS/GPS.o %% libraries/AP_GPS/GPS.o
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_Mount/AP_Mount.o
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/AP_Relay/AP_Relay.o
%% libraries/DataFlash/DataFlash.o %% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/BetterStream.o
@ -96,6 +114,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
%% libraries/GCS_MAVLink/GCS_MAVLink.o %% libraries/GCS_MAVLink/GCS_MAVLink.o
%% libraries/ModeFilter/ModeFilter.o %% libraries/ModeFilter/ModeFilter.o
%% libraries/PID/PID.o %% libraries/PID/PID.o
%% libraries/RC_Channel/RC_Channel_aux.o
%% libraries/RC_Channel/RC_Channel.o %% libraries/RC_Channel/RC_Channel.o
%% libraries/memcheck/memcheck.o %% libraries/memcheck/memcheck.o
%% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ftoa_engine.o

View File

@ -3,20 +3,21 @@
00000001 b home_is_set 00000001 b home_is_set
00000001 b ch3_failsafe 00000001 b ch3_failsafe
00000001 b land_complete 00000001 b land_complete
00000001 b command_may_ID 00000001 b mavlink_active
00000001 b command_must_ID 00000001 b nav_command_ID
00000001 b failsafeCounter 00000001 b failsafeCounter
00000001 b counter_one_herz 00000001 b counter_one_herz
00000001 b in_mavlink_delay 00000001 b in_mavlink_delay
00000001 b slow_loopCounter 00000001 b slow_loopCounter
00000001 d takeoff_complete 00000001 d takeoff_complete
00000001 b command_may_index 00000001 b nav_command_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop 00000001 b delta_ms_fast_loop
00000001 d ground_start_count 00000001 d ground_start_count
00000001 b medium_loopCounter 00000001 b medium_loopCounter
00000001 b non_nav_command_ID
00000001 b rc_override_active 00000001 b rc_override_active
00000001 b delta_ms_medium_loop 00000001 b delta_ms_medium_loop
00000001 b non_nav_command_index
00000001 b superslow_loopCounter 00000001 b superslow_loopCounter
00000001 b event_id 00000001 b event_id
00000001 b GPS_light 00000001 b GPS_light
@ -24,11 +25,9 @@
00000001 D control_mode 00000001 D control_mode
00000001 B hindex 00000001 B hindex
00000001 B inverted_flight 00000001 B inverted_flight
00000001 B mavdelay
00000001 B n 00000001 B n
00000001 B oldSwitchPosition 00000001 B oldSwitchPosition
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) 00000001 B relay
00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
00000002 b event_value 00000002 b event_value
@ -58,11 +57,11 @@
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 d throttle_slew_limit()::last 00000002 d throttle_slew_limit()::last
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c 00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 b event_timer 00000004 b event_timer
00000004 d hold_course 00000004 d hold_course
00000004 b loiter_time 00000004 b loiter_time
@ -71,6 +70,7 @@
00000004 b wp_distance 00000004 b wp_distance
00000004 b current_amps 00000004 b current_amps
00000004 b energy_error 00000004 b energy_error
00000004 b airspeed_fbwB
00000004 b bearing_error 00000004 b bearing_error
00000004 b current_total 00000004 b current_total
00000004 b nav_loopTimer 00000004 b nav_loopTimer
@ -106,8 +106,6 @@
00000004 b nav_roll 00000004 b nav_roll
00000004 b nav_pitch 00000004 b nav_pitch
00000004 b mavlink_delay(unsigned long)::last_1hz 00000004 b mavlink_delay(unsigned long)::last_1hz
00000004 b mavlink_delay(unsigned long)::last_3hz
00000004 b mavlink_delay(unsigned long)::last_10hz
00000004 b mavlink_delay(unsigned long)::last_50hz 00000004 b mavlink_delay(unsigned long)::last_50hz
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
@ -135,7 +133,6 @@
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000008 r __menu_name__planner_menu 00000008 r __menu_name__planner_menu
00000008 W AP_IMU_Shim::update()
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c
@ -149,12 +146,13 @@
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c 00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 V Parameters::Parameters()::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a r init_home()::__c
0000000a r verify_nav_wp()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
@ -162,18 +160,17 @@
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a V Parameters::Parameters()::__c 0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
0000000a T setup 0000000a T setup
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c 0000000b V Parameters::Parameters()::__c
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) 0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
0000000c V vtable for AP_IMU_Shim 0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r control_failsafe(unsigned int)::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c
@ -182,6 +179,9 @@
0000000d r init_home()::__c 0000000d r init_home()::__c
0000000d r verify_RTL()::__c 0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c 0000000d r demo_servos(unsigned char)::__c
0000000d r control_failsafe(unsigned int)::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c
@ -202,6 +202,7 @@
0000000d B sonar_mode_filter 0000000d B sonar_mode_filter
0000000e t global destructors keyed to Serial 0000000e t global destructors keyed to Serial
0000000e t global constructors keyed to Serial 0000000e t global constructors keyed to Serial
0000000e t send_statustext(mavlink_channel_t)
0000000e V vtable for AP_Float16 0000000e V vtable for AP_Float16
0000000e V vtable for AP_VarS<Matrix3<float> > 0000000e V vtable for AP_VarS<Matrix3<float> >
0000000e V vtable for AP_VarS<Vector3<float> > 0000000e V vtable for AP_VarS<Vector3<float> >
@ -209,7 +210,7 @@
0000000e V vtable for AP_VarT<float> 0000000e V vtable for AP_VarT<float>
0000000e V vtable for AP_VarT<int> 0000000e V vtable for AP_VarT<int>
0000000e V vtable for AP_VarT<long> 0000000e V vtable for AP_VarT<long>
0000000e r process_may()::__c 0000000e r control_failsafe(unsigned int)::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
@ -230,12 +231,13 @@
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c
0000000f b current_loc 0000000f b current_loc
0000000f b next_command 0000000f b next_nav_command
0000000f b next_nonnav_command
0000000f b home 0000000f b home
0000000f b next_WP 0000000f b next_WP
0000000f b prev_WP 0000000f b prev_WP
0000000f b guided_WP 0000000f b guided_WP
0000000f r failsafe_short_on_event()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
@ -243,15 +245,16 @@
0000000f V Parameters::Parameters()::__c 0000000f V Parameters::Parameters()::__c
00000010 b rc_override 00000010 b rc_override
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 T GCS_MAVLINK::send_message(ap_message)
00000010 W AP_VarT<float>::cast_to_float() const 00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const 00000010 W AP_VarT<long>::cast_to_float() const
00000010 t mavlink_get_channel_status
00000011 r set_next_WP(Location*)::__c
00000011 r startup_ground()::__c 00000011 r startup_ground()::__c
00000011 r load_next_command_from_EEPROM()::__c 00000011 r process_next_command()::__c
00000011 r failsafe_short_on_event()::__c
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 W AP_Float16::~AP_Float16() 00000012 W AP_Float16::~AP_Float16()
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
00000012 W AP_VarS<Vector3<float> >::~AP_VarS() 00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
@ -260,34 +263,39 @@
00000012 W AP_VarT<int>::~AP_VarT() 00000012 W AP_VarT<int>::~AP_VarT()
00000012 W AP_VarT<long>::~AP_VarT() 00000012 W AP_VarT<long>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const 00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r handle_no_commands()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000012 B adc
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
00000014 W AP_VarT<signed char>::cast_to_float() const 00000014 W AP_VarT<signed char>::cast_to_float() const
00000014 W AP_VarT<int>::cast_to_float() const 00000014 W AP_VarT<int>::cast_to_float() const
00000014 r set_guided_WP()::__c
00000015 r map_baudrate(signed char, unsigned long)::__c 00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r verify_nav_wp()::__c
00000015 r init_ardupilot()::__c 00000015 r init_ardupilot()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r GCS_MAVLINK::update()::__c 00000016 B adc
00000016 B sonar 00000016 B sonar
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000019 r failsafe_long_on_event()::__c 00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c 00000019 r handle_process_nav_cmd()::__c
00000019 r handle_process_do_command()::__c
00000019 r handle_process_condition_command()::__c
00000019 r do_jump()::__c
0000001a t startup_IMU_ground() 0000001a t startup_IMU_ground()
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c 0000001a r failsafe_short_on_event()::__c
0000001a r do_jump()::__c
0000001a r do_jump()::__c
0000001b r failsafe_short_off_event()::__c 0000001b r failsafe_short_off_event()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
0000001c W AP_VarT<int>::unserialize(void*, unsigned int) 0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001e t failsafe_short_off_event()
0000001e r startup_ground()::__c 0000001e r startup_ground()::__c
00000020 t gcs_send_message(ap_message)
00000020 t byte_swap_4 00000020 t byte_swap_4
00000021 r verify_loiter_time()::__c
00000021 r process_next_command()::__c
00000022 t failsafe_short_off_event()
00000022 t reset_I() 00000022 t reset_I()
00000022 W AP_Float16::~AP_Float16() 00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -296,117 +304,134 @@
00000022 W AP_VarT<float>::~AP_VarT() 00000022 W AP_VarT<float>::~AP_VarT()
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000022 W AP_VarT<long>::~AP_VarT() 00000022 W AP_VarT<long>::~AP_VarT()
00000022 r increment_WP_index()::__c 00000022 r process_next_command()::__c
00000022 r verify_loiter_time()::__c 00000022 r process_next_command()::__c
00000023 r verify_loiter_turns()::__c
00000023 r navigate()::__c 00000023 r navigate()::__c
00000024 r verify_loiter_turns()::__c
00000026 b mavlink_queue
00000026 r init_ardupilot()::__c 00000026 r init_ardupilot()::__c
00000027 r change_command(unsigned char)::__c
00000027 r init_ardupilot()::__c 00000027 r init_ardupilot()::__c
00000028 t increment_WP_index() 00000028 t demo_servos(unsigned char)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int) 00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int) 00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const 00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const 00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000028 B imu 0000002a r verify_nav_command()::__c
0000002a t demo_servos(unsigned char) 0000002a t _mav_put_int8_t_array
0000002b r verify_must()::__c
0000002b r change_command(unsigned char)::__c 0000002b r change_command(unsigned char)::__c
0000002e t reset_control_switch() 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
0000002e r verify_nav_wp()::__c 00000030 t send_heartbeat(mavlink_channel_t)
00000030 r verify_may()::__c 00000030 B imu
00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r init_ardupilot()::__c
00000033 b pending_status
00000034 t _MAV_RETURN_float 00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const 00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send
00000035 r verify_condition_command()::__c
00000038 t send_current_waypoint(mavlink_channel_t)
00000039 r init_ardupilot()::__c 00000039 r init_ardupilot()::__c
0000003a t verify_loiter_turns()
0000003a W PID::~PID() 0000003a W PID::~PID()
0000003a B g_gps_driver 0000003a B g_gps_driver
0000003c t verify_loiter_turns() 0000003c t verify_RTL()
0000003c W RC_Channel::~RC_Channel() 0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e t verify_RTL()
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) 0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
00000040 t byte_swap_8 00000040 t byte_swap_8
00000040 t crc_accumulate
00000040 B history 00000040 B history
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000046 W RC_Channel::~RC_Channel()
00000048 t failsafe_long_on_event()
0000004a t send_meminfo(mavlink_channel_t)
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000056 t change_command(unsigned char) 00000052 W AP_IMU_Shim::update()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 B dcm 00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e T GCS_MAVLINK::_count_parameters() 0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart 00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
00000064 t mavlink_msg_param_value_send 00000064 W RC_Channel_aux::~RC_Channel_aux()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006e t do_RTL()
00000070 r init_ardupilot()::__c 00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time() 00000072 t verify_loiter_time()
0000007c t failsafe_short_on_event() 00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
00000080 t do_RTL() 0000007c t send_gps_status(mavlink_channel_t)
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000084 t change_command(unsigned char)
0000008e t failsafe_short_on_event()
00000090 t handle_no_commands()
00000092 T GCS_MAVLINK::queued_param_send()
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
0000009b B gcs0
0000009b B gcs3
0000009c t update_servo_switches() 0000009c t update_servo_switches()
0000009d B gcs 000000a2 t verify_nav_wp()
0000009d B hil
000000a4 T __vector_26 000000a4 T __vector_26
000000a4 T __vector_37 000000a4 T __vector_37
000000a4 T __vector_55 000000a4 T __vector_55
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
000000ab B compass 000000ab B compass
000000b4 t planner_gcs(unsigned char, Menu::arg const*) 000000be t update_events()
000000c0 t calc_bearing_error() 000000c0 t calc_bearing_error()
000000c4 t update_events() 000000ca t send_radio_out(mavlink_channel_t)
000000c4 t load_next_command_from_EEPROM()
000000ca t control_failsafe(unsigned int) 000000ca t control_failsafe(unsigned int)
000000cc t read_control_switch() 000000cc t read_control_switch()
000000ce t send_radio_in(mavlink_channel_t)
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000d0 t get_bearing(Location*, Location*) 000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000f0 t throttle_slew_limit() 000000f0 t throttle_slew_limit()
000000f4 t _mav_finalize_message_chan_send
00000106 t calc_nav_pitch() 00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int) 0000010a t mavlink_delay(unsigned long)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000110 t get_cmd_with_index(int)
00000112 t get_distance(Location*, Location*) 00000112 t get_distance(Location*, Location*)
00000112 t send_servo_out(mavlink_channel_t)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 T GCS_MAVLINK::_queued_send() 00000130 t startup_ground()
00000130 t set_wp_with_index(Location, int) 00000130 t set_cmd_with_index(Location, int)
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) 00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
0000013e t process_may()
0000013e t calc_nav_roll() 0000013e t calc_nav_roll()
0000014e t verify_may() 0000013e t handle_process_condition_command()
0000014e T GCS_MAVLINK::update() 00000146 t send_vfr_hud(mavlink_channel_t)
0000016a t process_must() 00000152 t verify_condition_command()
0000016a t set_guided_WP() 0000015e t set_guided_WP()
00000172 t navigate() 0000015e t handle_process_nav_cmd()
0000019e t startup_ground() 0000016c t navigate()
000001ae T init_home() 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
0000017c t send_location(mavlink_channel_t)
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000190 T init_home()
0000019a t do_jump()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t set_mode(unsigned char)
000001a2 T GCS_MAVLINK::update()
000001b2 t update_crosstrack() 000001b2 t update_crosstrack()
000001ca t mavlink_delay(unsigned long) 000001bc t set_next_WP(Location*)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001bc t send_nav_controller_output(mavlink_channel_t)
00000206 t set_next_WP(Location*) 000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
000001f4 t process_next_command()
00000208 t calc_throttle() 00000208 t calc_throttle()
0000021c t set_mode(unsigned char) 0000022a t send_gps_raw(mavlink_channel_t)
00000232 t verify_must() 00000230 t verify_nav_command()
0000024c t update_loiter() 0000024c t update_loiter()
000002d4 t handle_process_do_command()
000002e4 t read_radio() 000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int) 00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters() 0000033a W Parameters::~Parameters()
000003c0 t process_next_command() 00000492 t init_ardupilot()
000004b2 t mavlink_parse_char 00000920 W Parameters::Parameters()
00000518 t init_ardupilot() 0000092b b g
00000831 b g 0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
0000090a W Parameters::Parameters() 00001c82 T loop
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001aac T loop

View File

@ -3,14 +3,14 @@
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<name>ArduPlane V2.24 </name> <name>ArduPlane V2.251 </name>
<desc></desc> <desc></desc>
<format_version>11</format_version> <format_version>12</format_version>
</Firmware> </Firmware>
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<name>ArduPlane V2.24 HIL</name> <name>ArduPlane V2.251 HIL</name>
<desc> <desc>
#define FLIGHT_MODE_CHANNEL 8 #define FLIGHT_MODE_CHANNEL 8
#define FLIGHT_MODE_1 AUTO #define FLIGHT_MODE_1 AUTO
@ -39,14 +39,14 @@
#define AIRSPEED_CRUISE 25 #define AIRSPEED_CRUISE 25
#define THROTTLE_FAILSAFE ENABLED #define THROTTLE_FAILSAFE ENABLED
</desc> </desc>
<format_version>11</format_version> <format_version>12</format_version>
</Firmware> </Firmware>
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<name>ArduPlane V2.24 APM trunk</name> <name>ArduPlane V2.251 APM trunk</name>
<desc></desc> <desc></desc>
<format_version>11</format_version> <format_version>12</format_version>
</Firmware> </Firmware>
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>

View File

@ -1,545 +1,29 @@
From https://code.google.com/p/ardupilot-mega From https://code.google.com/p/ardupilot-mega
b0bfa54..8d3fb35 APM_Camera -> origin/APM_Camera 66cc8dd..6f4e7ec master -> origin/master
cd1bcd6..34c9a18 master -> origin/master Updating 66cc8dd..6f4e7ec
Updating cd1bcd6..34c9a18
Fast-forward Fast-forward
.gitignore | 4 +- ArduCopter/APM_Config.h | 2 +-
ArduBoat/ArduBoat.cpp | 7 +- ArduCopter/ArduCopter.pde | 18 ++-
ArduBoat/ArduBoat.pde | 2 +- ArduCopter/commands.pde | 8 +-
ArduBoat/BoatGeneric.h | 39 +- ArduCopter/commands_process.pde | 3 +-
ArduBoat/ControllerBoat.h | 157 +- ArduCopter/motors_hexa.pde | 2 +-
ArduCopter/APM_Config.h | 7 +- ArduCopter/motors_octa.pde | 2 +-
ArduCopter/ArduCopter.pde | 64 +- ArduCopter/motors_octa_quad.pde | 2 +-
ArduCopter/Attitude.pde | 54 +- ArduCopter/motors_y6.pde | 3 +-
ArduCopter/CMakeLists.txt | 165 - ArduPlane/ArduPlane.pde | 2 +-
ArduCopter/GCS.h | 7 +- ArduPlane/Log.pde | 5 +-
ArduCopter/GCS_Mavlink.pde | 23 +- ArduPlane/commands_logic.pde | 13 ++-
ArduCopter/Log.pde | 261 +- Tools/ArdupilotMegaPlanner/CurrentState.cs | 1 -
ArduCopter/Parameters.h | 12 +- Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 27 +++-
ArduCopter/config.h | 45 +- .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 149 +++++++++++++++++---
ArduCopter/control_modes.pde | 8 +- Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 14 ++-
ArduCopter/defines.h | 1 +
ArduCopter/heli.pde | 25 +
ArduCopter/motors.pde | 4 +-
ArduCopter/navigation.pde | 42 +-
ArduCopter/radio.pde | 14 +-
ArduCopter/system.pde | 36 +-
ArduPlane/.gitignore | 1 -
ArduPlane/ArduPlane.pde | 27 +-
ArduPlane/CMakeLists.txt | 168 -
ArduPlane/GCS.h | 7 +-
ArduPlane/GCS_Mavlink.pde | 464 +++-
ArduPlane/Log.pde | 10 +-
ArduPlane/Mavlink_compat.h | 172 +
ArduPlane/Parameters.h | 12 +-
ArduPlane/commands.pde | 65 +-
ArduPlane/commands_logic.pde | 152 +-
ArduPlane/commands_process.pde | 183 +-
ArduPlane/config.h | 5 +
ArduPlane/defines.h | 3 +-
ArduPlane/navigation.pde | 2 +-
ArduPlane/system.pde | 21 +-
ArduPlane/test.pde | 6 +-
ArduRover/ArduRover.cpp | 6 +-
ArduRover/ArduRover.pde | 1 +
ArduRover/CarStampede.h | 31 +-
ArduRover/ControllerCar.h | 158 +-
ArduRover/ControllerTank.h | 176 +-
ArduRover/TankGeneric.h | 16 +-
CMakeLists.txt | 9 +-
Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 9 +
Tools/ArdupilotMegaPlanner/Camera.Designer.cs | 421 +++
Tools/ArdupilotMegaPlanner/Camera.cs | 139 +
Tools/ArdupilotMegaPlanner/Camera.resx | 120 +
Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 12 +-
Tools/ArdupilotMegaPlanner/CurrentState.cs | 81 +-
.../GCSViews/Configuration.Designer.cs | 137 +-
.../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 47 +-
.../GCSViews/Configuration.resx | 2088 +++++-------
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 12 +-
.../GCSViews/FlightData.Designer.cs | 155 +-
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 164 +-
.../ArdupilotMegaPlanner/GCSViews/FlightData.resx | 604 ++--
.../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 4 +-
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 18 +-
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 7 +
Tools/ArdupilotMegaPlanner/Joystick.cs | 50 +-
.../ArdupilotMegaPlanner/JoystickSetup.Designer.cs | 276 ++-
Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 125 +-
Tools/ArdupilotMegaPlanner/JoystickSetup.resx | 763 ++++-
Tools/ArdupilotMegaPlanner/MAVLink.cs | 11 +-
Tools/ArdupilotMegaPlanner/MainV2.cs | 87 +-
Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +-
Tools/ArdupilotMegaPlanner/Program.cs | 1 +
.../Properties/AssemblyInfo.cs | 2 +- .../Properties/AssemblyInfo.cs | 2 +-
Tools/ArdupilotMegaPlanner/SerialOutput.cs | 13 +-
Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +-
Tools/ArdupilotMegaPlanner/Updater/Updater.csproj | 2 +-
.../bin/Release/ArdupilotMegaPlanner.application | 2 +- .../bin/Release/ArdupilotMegaPlanner.application | 2 +-
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194944 -> 2188288 bytes .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2195456 bytes
.../bin/Release/GCSViews/Configuration.resx | 2088 +++++-------
.../bin/Release/GCSViews/FlightData.resx | 604 ++--
.../bin/Release/JoystickSetup.resx | 763 ++++-
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes .../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes .../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
Tools/scripts/format.sh | 13 + Tools/autotest/arducopter.py | 58 ++++++---
apo/ControllerPlane.h | 329 +- Tools/autotest/common.py | 16 ++-
apo/ControllerQuad.h | 414 +-- 24 files changed, 251 insertions(+), 78 deletions(-)
apo/PlaneEasystar.h | 18 +-
apo/QuadArducopter.h | 17 +-
apo/apo.pde | 5 +-
libraries/APM_BMP085/APM_BMP085.h | 2 +-
libraries/APM_PI/APM_PI.cpp | 8 +-
libraries/APO/APO.h | 6 +-
libraries/APO/APO_DefaultSetup.h | 321 +-
libraries/APO/AP_ArmingMechanism.cpp | 14 +-
libraries/APO/AP_ArmingMechanism.h | 10 +-
libraries/APO/AP_Autopilot.cpp | 461 ++--
libraries/APO/AP_Autopilot.h | 195 +-
libraries/APO/AP_BatteryMonitor.h | 1 -
libraries/APO/AP_CommLink.cpp | 1280 ++++----
libraries/APO/AP_CommLink.h | 126 +-
libraries/APO/AP_Controller.cpp | 111 +-
libraries/APO/AP_Controller.h | 402 ++-
libraries/APO/AP_Guide.cpp | 429 ++-
libraries/APO/AP_Guide.h | 203 +-
libraries/APO/AP_HardwareAbstractionLayer.cpp | 1 +
libraries/APO/AP_HardwareAbstractionLayer.h | 258 +-
libraries/APO/AP_MavlinkCommand.cpp | 304 +-
libraries/APO/AP_MavlinkCommand.h | 654 ++--
libraries/APO/AP_Navigator.cpp | 298 +-
libraries/APO/AP_Navigator.h | 358 +-
libraries/APO/AP_RcChannel.cpp | 125 +-
libraries/APO/AP_RcChannel.h | 103 +-
libraries/APO/AP_Var_keys.h | 21 +-
libraries/APO/constants.h | 1 +
libraries/APO/examples/MavlinkTest/MavlinkTest.pde | 64 +-
libraries/APO/examples/ServoManual/ServoManual.pde | 144 +-
libraries/APO/examples/ServoSweep/ServoSweep.pde | 184 +-
libraries/AP_Common/AP_Common.h | 20 +-
libraries/AP_Common/AP_Test.h | 4 +-
libraries/AP_Common/AP_Var.cpp | 80 +-
libraries/AP_Common/AP_Var.h | 12 +-
libraries/AP_Common/c++.cpp | 22 +-
libraries/AP_Common/examples/menu/menu.pde | 22 +-
libraries/AP_Common/include/menu.h | 186 +-
libraries/AP_Common/menu.cpp | 198 +-
libraries/AP_DCM/AP_DCM_HIL.cpp | 12 +-
libraries/AP_GPS/AP_GPS_406.cpp | 72 +-
libraries/AP_GPS/AP_GPS_406.h | 8 +-
libraries/AP_GPS/AP_GPS_Auto.cpp | 316 +-
libraries/AP_GPS/AP_GPS_Auto.h | 58 +-
libraries/AP_GPS/AP_GPS_HIL.cpp | 18 +-
libraries/AP_GPS/AP_GPS_HIL.h | 10 +-
libraries/AP_GPS/AP_GPS_IMU.cpp | 294 +-
libraries/AP_GPS/AP_GPS_IMU.h | 68 +-
libraries/AP_GPS/AP_GPS_MTK.cpp | 226 +-
libraries/AP_GPS/AP_GPS_MTK.h | 74 +-
libraries/AP_GPS/AP_GPS_MTK16.cpp | 240 +-
libraries/AP_GPS/AP_GPS_MTK16.h | 78 +-
libraries/AP_GPS/AP_GPS_NMEA.cpp | 528 ++--
libraries/AP_GPS/AP_GPS_NMEA.h | 118 +-
libraries/AP_GPS/AP_GPS_None.h | 8 +-
libraries/AP_GPS/AP_GPS_SIRF.cpp | 280 +-
libraries/AP_GPS/AP_GPS_SIRF.h | 130 +-
libraries/AP_GPS/AP_GPS_Shim.h | 38 +-
libraries/AP_GPS/AP_GPS_UBLOX.cpp | 292 +-
libraries/AP_GPS/AP_GPS_UBLOX.h | 184 +-
libraries/AP_GPS/GPS.cpp | 50 +-
libraries/AP_GPS/GPS.h | 330 +-
.../AP_GPS/examples/GPS_406_test/GPS_406_test.pde | 62 +-
.../examples/GPS_AUTO_test/GPS_AUTO_test.pde | 42 +-
.../AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde | 60 +-
.../examples/GPS_NMEA_test/GPS_NMEA_test.pde | 81 +-
.../examples/GPS_UBLOX_test/GPS_UBLOX_test.pde | 60 +-
libraries/Desktop/Desktop.mk | 2 +-
libraries/Desktop/Makefile.desktop | 3 +
libraries/GCS_MAVLink/GCS_MAVLink.cpp | 6 +-
libraries/GCS_MAVLink/GCS_MAVLink.h | 18 +-
.../include/ardupilotmega/ardupilotmega.h | 74 +-
.../include/ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
.../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
.../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
.../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
.../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
.../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
.../GCS_MAVLink/include/ardupilotmega/testsuite.h | 340 ++
.../GCS_MAVLink/include/ardupilotmega/version.h | 2 +-
libraries/GCS_MAVLink/include/bittest.c | 39 -
libraries/GCS_MAVLink/include/common/common.h | 52 +-
.../mavlink_msg_attitude_controller_output.h | 169 -
.../include/common/mavlink_msg_attitude_new.h | 268 --
.../include/common/mavlink_msg_auth_key.h | 6 +-
.../common/mavlink_msg_change_operator_control.h | 6 +-
.../include/common/mavlink_msg_debug_vect.h | 6 +-
.../include/common/mavlink_msg_full_state.h | 428 ---
.../include/common/mavlink_msg_gps_status.h | 30 +-
.../include/common/mavlink_msg_named_value_float.h | 6 +-
.../include/common/mavlink_msg_named_value_int.h | 6 +-
.../common/mavlink_msg_object_detection_event.h | 6 +-
.../common/mavlink_msg_param_request_read.h | 6 +-
.../include/common/mavlink_msg_param_set.h | 6 +-
.../include/common/mavlink_msg_param_value.h | 6 +-
.../mavlink_msg_position_controller_output.h | 169 -
.../mavlink_msg_request_dynamic_gyro_calibration.h | 177 -
.../mavlink_msg_request_static_calibration.h | 138 -
.../common/mavlink_msg_set_roll_pitch_yaw.h | 184 -
.../common/mavlink_msg_set_roll_pitch_yaw_speed.h | 184 -
.../include/common/mavlink_msg_statustext.h | 6 +-
.../mavlink_msg_waypoint_set_global_reference.h | 294 --
libraries/GCS_MAVLink/include/common/testsuite.h | 30 +-
libraries/GCS_MAVLink/include/common/version.h | 2 +-
libraries/GCS_MAVLink/include/documentation.dox | 41 -
libraries/GCS_MAVLink/include/mavlink_helpers.h | 8 +-
libraries/GCS_MAVLink/include/minimal/mavlink.h | 11 -
.../include/minimal/mavlink_msg_heartbeat.h | 132 -
libraries/GCS_MAVLink/include/minimal/minimal.h | 45 -
libraries/GCS_MAVLink/include/pixhawk/mavlink.h | 11 -
.../include/pixhawk/mavlink_msg_attitude_control.h | 257 --
.../include/pixhawk/mavlink_msg_aux_status.h | 204 -
.../include/pixhawk/mavlink_msg_brief_feature.h | 249 --
.../include/pixhawk/mavlink_msg_control_status.h | 203 -
.../mavlink_msg_data_transmission_handshake.h | 174 -
.../include/pixhawk/mavlink_msg_debug_vect.h | 156 -
.../pixhawk/mavlink_msg_encapsulated_data.h | 124 -
.../pixhawk/mavlink_msg_encapsulated_image.h | 76 -
.../include/pixhawk/mavlink_msg_get_image_ack.h | 104 -
.../include/pixhawk/mavlink_msg_image_available.h | 586 ---
.../pixhawk/mavlink_msg_image_trigger_control.h | 101 -
.../include/pixhawk/mavlink_msg_image_triggered.h | 352 --
.../include/pixhawk/mavlink_msg_manual_control.h | 191 -
.../include/pixhawk/mavlink_msg_marker.h | 236 --
.../include/pixhawk/mavlink_msg_pattern_detected.h | 160 -
.../pixhawk/mavlink_msg_point_of_interest.h | 241 --
.../mavlink_msg_point_of_interest_connection.h | 307 --
.../mavlink_msg_position_control_offset_set.h | 206 -
.../mavlink_msg_position_control_setpoint.h | 192 -
.../mavlink_msg_position_control_setpoint_set.h | 226 --
.../include/pixhawk/mavlink_msg_raw_aux.h | 226 --
.../pixhawk/mavlink_msg_request_data_stream.h | 118 -
.../mavlink_msg_request_dynamic_gyro_calibration.h | 123 -
.../mavlink_msg_request_static_calibration.h | 90 -
.../include/pixhawk/mavlink_msg_set_altitude.h | 78 -
.../include/pixhawk/mavlink_msg_set_cam_shutter.h | 197 -
.../include/pixhawk/mavlink_msg_watchdog_command.h | 158 -
.../pixhawk/mavlink_msg_watchdog_heartbeat.h | 124 -
.../pixhawk/mavlink_msg_watchdog_process_info.h | 186 -
.../pixhawk/mavlink_msg_watchdog_process_status.h | 200 -
libraries/GCS_MAVLink/include/pixhawk/pixhawk.h | 79 -
libraries/GCS_MAVLink/include/protocol.h | 37 +-
libraries/GCS_MAVLink/include/slugs/mavlink.h | 11 -
.../include/slugs/mavlink_msg_air_data.h | 148 -
.../include/slugs/mavlink_msg_cpu_load.h | 138 -
.../include/slugs/mavlink_msg_ctrl_srfc_pt.h | 121 -
.../include/slugs/mavlink_msg_data_log.h | 216 --
.../include/slugs/mavlink_msg_diagnostic.h | 210 --
.../include/slugs/mavlink_msg_filtered_data.h | 216 --
.../include/slugs/mavlink_msg_gps_date_time.h | 203 -
.../include/slugs/mavlink_msg_mid_lvl_cmds.h | 167 -
.../GCS_MAVLink/include/slugs/mavlink_msg_pid.h | 130 -
.../include/slugs/mavlink_msg_pilot_console.h | 145 -
.../include/slugs/mavlink_msg_pwm_commands.h | 235 --
.../include/slugs/mavlink_msg_sensor_bias.h | 216 --
.../include/slugs/mavlink_msg_slugs_action.h | 138 -
.../include/slugs/mavlink_msg_slugs_navigation.h | 272 --
libraries/GCS_MAVLink/include/slugs/slugs.h | 56 -
libraries/GCS_MAVLink/include/ualberta/mavlink.h | 11 -
.../include/ualberta/mavlink_msg_nav_filter_bias.h | 242 --
.../ualberta/mavlink_msg_radio_calibration.h | 204 -
.../mavlink_msg_request_radio_calibration.h | 59 -
.../ualberta/mavlink_msg_request_rc_channels.h | 101 -
.../ualberta/mavlink_msg_ualberta_sys_status.h | 135 -
libraries/GCS_MAVLink/include/ualberta/ualberta.h | 79 -
.../include_v1.0/ardupilotmega/ardupilotmega.h | 122 +
.../include_v1.0/ardupilotmega/mavlink.h | 27 +
.../ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
.../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
.../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
.../ardupilotmega/mavlink_msg_meminfo.h | 166 +
.../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
.../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
.../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
.../ardupilotmega/mavlink_msg_sensor_offsets.h | 386 ++
.../ardupilotmega/mavlink_msg_set_mag_offsets.h | 232 ++
.../include_v1.0/ardupilotmega/testsuite.h | 538 +++
.../include_v1.0/ardupilotmega/version.h | 12 +
libraries/GCS_MAVLink/include_v1.0/checksum.h | 89 +
libraries/GCS_MAVLink/include_v1.0/common/common.h | 429 +++
.../GCS_MAVLink/include_v1.0/common/mavlink.h | 27 +
.../include_v1.0/common/mavlink_msg_attitude.h | 276 ++
.../common/mavlink_msg_attitude_quaternion.h | 298 ++
.../include_v1.0/common/mavlink_msg_auth_key.h | 144 +
.../common/mavlink_msg_change_operator_control.h | 204 +
.../mavlink_msg_change_operator_control_ack.h | 188 +
.../include_v1.0/common/mavlink_msg_command_ack.h | 166 +
.../include_v1.0/common/mavlink_msg_command_long.h | 364 ++
.../include_v1.0/common/mavlink_msg_data_stream.h | 188 +
.../include_v1.0/common/mavlink_msg_debug.h | 188 +
.../include_v1.0/common/mavlink_msg_debug_vect.h | 226 ++
.../common/mavlink_msg_extended_message.h | 188 +
.../common/mavlink_msg_global_position_int.h | 320 ++
.../mavlink_msg_global_position_setpoint_int.h | 232 ++
.../mavlink_msg_global_vision_position_estimate.h | 276 ++
.../common/mavlink_msg_gps_global_origin.h | 188 +
.../include_v1.0/common/mavlink_msg_gps_raw_int.h | 342 ++
.../include_v1.0/common/mavlink_msg_gps_status.h | 252 ++
.../include_v1.0/common/mavlink_msg_heartbeat.h | 251 ++
.../include_v1.0/common/mavlink_msg_hil_controls.h | 364 ++
.../common/mavlink_msg_hil_rc_inputs_raw.h | 430 +++
.../include_v1.0/common/mavlink_msg_hil_state.h | 474 +++
.../common/mavlink_msg_local_position_ned.h | 276 ++
.../common/mavlink_msg_local_position_setpoint.h | 232 ++
.../common/mavlink_msg_manual_control.h | 320 ++
.../include_v1.0/common/mavlink_msg_memory_vect.h | 204 +
.../include_v1.0/common/mavlink_msg_mission_ack.h | 188 +
.../common/mavlink_msg_mission_clear_all.h | 166 +
.../common/mavlink_msg_mission_count.h | 188 +
.../common/mavlink_msg_mission_current.h | 144 +
.../include_v1.0/common/mavlink_msg_mission_item.h | 430 +++
.../common/mavlink_msg_mission_item_reached.h | 144 +
.../common/mavlink_msg_mission_request.h | 188 +
.../common/mavlink_msg_mission_request_list.h | 166 +
.../mavlink_msg_mission_request_partial_list.h | 210 ++
.../common/mavlink_msg_mission_set_current.h | 188 +
.../mavlink_msg_mission_write_partial_list.h | 210 ++
.../common/mavlink_msg_named_value_float.h | 182 +
.../common/mavlink_msg_named_value_int.h | 182 +
.../common/mavlink_msg_nav_controller_output.h | 298 ++
.../include_v1.0/common/mavlink_msg_optical_flow.h | 254 ++
.../common/mavlink_msg_param_request_list.h | 166 +
.../common/mavlink_msg_param_request_read.h | 204 +
.../include_v1.0/common/mavlink_msg_param_set.h | 226 ++
.../include_v1.0/common/mavlink_msg_param_value.h | 226 ++
.../include_v1.0/common/mavlink_msg_ping.h | 210 ++
.../include_v1.0/common/mavlink_msg_raw_imu.h | 342 ++
.../include_v1.0/common/mavlink_msg_raw_pressure.h | 232 ++
.../common/mavlink_msg_rc_channels_override.h | 342 ++
.../common/mavlink_msg_rc_channels_raw.h | 364 ++
.../common/mavlink_msg_rc_channels_scaled.h | 364 ++
.../common/mavlink_msg_request_data_stream.h | 232 ++
...link_msg_roll_pitch_yaw_speed_thrust_setpoint.h | 232 ++
.../mavlink_msg_roll_pitch_yaw_thrust_setpoint.h | 232 ++
.../common/mavlink_msg_safety_allowed_area.h | 276 ++
.../common/mavlink_msg_safety_set_allowed_area.h | 320 ++
.../include_v1.0/common/mavlink_msg_scaled_imu.h | 342 ++
.../common/mavlink_msg_scaled_pressure.h | 210 ++
.../common/mavlink_msg_servo_output_raw.h | 342 ++
.../mavlink_msg_set_global_position_setpoint_int.h | 232 ++
.../common/mavlink_msg_set_gps_global_origin.h | 210 ++
.../mavlink_msg_set_local_position_setpoint.h | 276 ++
.../include_v1.0/common/mavlink_msg_set_mode.h | 188 +
.../mavlink_msg_set_roll_pitch_yaw_speed_thrust.h | 254 ++
.../common/mavlink_msg_set_roll_pitch_yaw_thrust.h | 254 ++
.../common/mavlink_msg_state_correction.h | 320 ++
.../include_v1.0/common/mavlink_msg_statustext.h | 160 +
.../include_v1.0/common/mavlink_msg_sys_status.h | 408 ++
.../include_v1.0/common/mavlink_msg_system_time.h | 166 +
.../include_v1.0/common/mavlink_msg_vfr_hud.h | 254 ++
.../common}/mavlink_msg_vicon_position_estimate.h | 198 +-
.../common}/mavlink_msg_vision_position_estimate.h | 198 +-
.../common}/mavlink_msg_vision_speed_estimate.h | 148 +-
.../GCS_MAVLink/include_v1.0/common/testsuite.h | 3908 ++++++++++++++++++++
.../GCS_MAVLink/include_v1.0/common/version.h | 12 +
.../GCS_MAVLink/include_v1.0/mavlink_helpers.h | 488 +++
libraries/GCS_MAVLink/include_v1.0/mavlink_types.h | 182 +
libraries/GCS_MAVLink/include_v1.0/protocol.h | 319 ++
.../message_definitions/ardupilotmega.xml | 132 +
libraries/GCS_MAVLink/message_definitions/test.xml | 31 +
.../message_definitions_v1.0/ardupilotmega.xml | 177 +
.../message_definitions_v1.0/common.xml | 1536 ++++++++
.../message_definitions_v1.0/minimal.xml | 16 +
.../message_definitions_v1.0/pixhawk.xml | 193 +
.../GCS_MAVLink/message_definitions_v1.0/slugs.xml | 144 +
.../GCS_MAVLink/message_definitions_v1.0/test.xml | 31 +
.../message_definitions_v1.0/ualberta.xml | 54 +
libraries/RC_Channel/RC_Channel.cpp | 2 +-
libraries/RC_Channel/RC_Channel.h | 8 +-
libraries/RC_Channel/RC_Channel_aux.cpp | 2 +-
libraries/RC_Channel/RC_Channel_aux.h | 1 +
355 files changed, 43388 insertions(+), 22115 deletions(-)
delete mode 100644 ArduCopter/CMakeLists.txt
delete mode 100644 ArduPlane/.gitignore
delete mode 100644 ArduPlane/CMakeLists.txt
create mode 100644 ArduPlane/Mavlink_compat.h
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.Designer.cs
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.cs
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.resx
create mode 100755 Tools/scripts/format.sh
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_configure.h
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_control.h
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_configure.h
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_control.h
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_status.h
delete mode 100644 libraries/GCS_MAVLink/include/bittest.c
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_controller_output.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_new.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_position_controller_output.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_static_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_global_reference.h
delete mode 100644 libraries/GCS_MAVLink/include/documentation.dox
delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink.h
delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h
delete mode 100644 libraries/GCS_MAVLink/include/minimal/minimal.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_attitude_control.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_aux_status.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_brief_feature.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_control_status.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_data_transmission_handshake.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_debug_vect.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_data.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_image.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_get_image_ack.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_trigger_control.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_manual_control.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_marker.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_pattern_detected.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest_connection.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_offset_set.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_raw_aux.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_data_stream.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_static_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_altitude.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_cam_shutter.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_command.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_info.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_status.h
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/pixhawk.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_filtered_data.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pid.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pilot_console.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pwm_commands.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h
delete mode 100644 libraries/GCS_MAVLink/include/slugs/slugs.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_nav_filter_bias.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_radio_calibration.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_rc_channels.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/ualberta.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_ap_adc.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_control.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_configure.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_control.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_status.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/checksum.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/common.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_partial_list.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_write_partial_list.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vicon_position_estimate.h (54%)
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_position_estimate.h (54%)
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_speed_estimate.h (57%)
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/testsuite.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/version.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_helpers.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_types.h
create mode 100644 libraries/GCS_MAVLink/include_v1.0/protocol.h
create mode 100644 libraries/GCS_MAVLink/message_definitions/test.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/common.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/test.xml
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml

View File

@ -508,7 +508,7 @@ namespace ArdupilotMega.GCSViews
ofd.AddExtension = true; ofd.AddExtension = true;
ofd.DefaultExt = ".param"; ofd.DefaultExt = ".param";
ofd.RestoreDirectory = true; ofd.RestoreDirectory = true;
ofd.Filter = "Param List|*.param"; ofd.Filter = "Param List|*.param;*.parm";
DialogResult dr = ofd.ShowDialog(); DialogResult dr = ofd.ShowDialog();
if (dr == DialogResult.OK) if (dr == DialogResult.OK)
{ {
@ -562,7 +562,7 @@ namespace ArdupilotMega.GCSViews
sfd.AddExtension = true; sfd.AddExtension = true;
sfd.DefaultExt = ".param"; sfd.DefaultExt = ".param";
sfd.RestoreDirectory = true; sfd.RestoreDirectory = true;
sfd.Filter = "Param List|*.param"; sfd.Filter = "Param List|*.param;*.parm";
DialogResult dr = sfd.ShowDialog(); DialogResult dr = sfd.ShowDialog();
if (dr == DialogResult.OK) if (dr == DialogResult.OK)
{ {
@ -1005,7 +1005,7 @@ namespace ArdupilotMega.GCSViews
ofd.AddExtension = true; ofd.AddExtension = true;
ofd.DefaultExt = ".param"; ofd.DefaultExt = ".param";
ofd.RestoreDirectory = true; ofd.RestoreDirectory = true;
ofd.Filter = "Param List|*.param"; ofd.Filter = "Param List|*.param;*.parm";
DialogResult dr = ofd.ShowDialog(); DialogResult dr = ofd.ShowDialog();
if (dr == DialogResult.OK) if (dr == DialogResult.OK)
{ {

View File

@ -514,10 +514,15 @@ namespace ArdupilotMega.GCSViews
{ {
baseurl = temp.url2560.ToString(); baseurl = temp.url2560.ToString();
} }
else else if (board == "1280")
{ {
baseurl = temp.url.ToString(); baseurl = temp.url.ToString();
} }
else
{
MessageBox.Show("Invalid Board Type");
return;
}
// Create a request using a URL that can receive a post. // Create a request using a URL that can receive a post.
WebRequest request = WebRequest.Create(baseurl); WebRequest request = WebRequest.Create(baseurl);
@ -592,6 +597,11 @@ namespace ArdupilotMega.GCSViews
if (board == "1280") if (board == "1280")
{ {
if (FLASH.Length > 126976)
{
MessageBox.Show("Firmware is to big for a 1280, Please upgrade!!");
return;
}
//port = new ArduinoSTK(); //port = new ArduinoSTK();
port.BaudRate = 57600; port.BaudRate = 57600;
} }

View File

@ -778,7 +778,16 @@ namespace ArdupilotMega.GCSViews
return; return;
} }
string alt = (100 * MainV2.cs.multiplierdist).ToString("0"); string alt = "100";
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
alt = (10 * MainV2.cs.multiplierdist).ToString("0");
}
else
{
alt = (100 * MainV2.cs.multiplierdist).ToString("0");
}
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Guided Mode Alt", ref alt)) if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Guided Mode Alt", ref alt))
return; return;
@ -815,6 +824,8 @@ namespace ArdupilotMega.GCSViews
} }
private void Zoomlevel_ValueChanged(object sender, EventArgs e) private void Zoomlevel_ValueChanged(object sender, EventArgs e)
{
try
{ {
if (gMapControl1.MaxZoom + 1 == (double)Zoomlevel.Value) if (gMapControl1.MaxZoom + 1 == (double)Zoomlevel.Value)
{ {
@ -825,6 +836,8 @@ namespace ArdupilotMega.GCSViews
gMapControl1.Zoom = (double)Zoomlevel.Value; gMapControl1.Zoom = (double)Zoomlevel.Value;
} }
} }
catch { }
}
private void gMapControl1_MouseMove(object sender, MouseEventArgs e) private void gMapControl1_MouseMove(object sender, MouseEventArgs e)
{ {

View File

@ -31,14 +31,14 @@
{ {
this.components = new System.ComponentModel.Container(); this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner)); System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner));
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle9 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle13 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle5 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle14 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle6 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle10 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle11 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle12 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle15 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle7 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle16 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle8 = new System.Windows.Forms.DataGridViewCellStyle();
this.CHK_altmode = new System.Windows.Forms.CheckBox(); this.CHK_altmode = new System.Windows.Forms.CheckBox();
this.CHK_holdalt = new System.Windows.Forms.CheckBox(); this.CHK_holdalt = new System.Windows.Forms.CheckBox();
this.Commands = new System.Windows.Forms.DataGridView(); this.Commands = new System.Windows.Forms.DataGridView();
@ -47,6 +47,9 @@
this.Param2 = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.Param2 = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Param3 = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.Param3 = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Param4 = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.Param4 = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Lat = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Lon = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Alt = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Delete = new System.Windows.Forms.DataGridViewButtonColumn(); this.Delete = new System.Windows.Forms.DataGridViewButtonColumn();
this.Up = new System.Windows.Forms.DataGridViewImageColumn(); this.Up = new System.Windows.Forms.DataGridViewImageColumn();
this.Down = new System.Windows.Forms.DataGridViewImageColumn(); this.Down = new System.Windows.Forms.DataGridViewImageColumn();
@ -86,6 +89,7 @@
this.textBox1 = new System.Windows.Forms.TextBox(); this.textBox1 = new System.Windows.Forms.TextBox();
this.panelWaypoints = new BSE.Windows.Forms.Panel(); this.panelWaypoints = new BSE.Windows.Forms.Panel();
this.splitter1 = new BSE.Windows.Forms.Splitter(); this.splitter1 = new BSE.Windows.Forms.Splitter();
this.BUT_Camera = new ArdupilotMega.MyButton();
this.BUT_grid = new ArdupilotMega.MyButton(); this.BUT_grid = new ArdupilotMega.MyButton();
this.BUT_Prefetch = new ArdupilotMega.MyButton(); this.BUT_Prefetch = new ArdupilotMega.MyButton();
this.button1 = new ArdupilotMega.MyButton(); this.button1 = new ArdupilotMega.MyButton();
@ -116,7 +120,6 @@
this.label11 = new System.Windows.Forms.Label(); this.label11 = new System.Windows.Forms.Label();
this.panelBASE = new System.Windows.Forms.Panel(); this.panelBASE = new System.Windows.Forms.Panel();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_Camera = new ArdupilotMega.MyButton();
((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit();
this.panel5.SuspendLayout(); this.panel5.SuspendLayout();
this.panel1.SuspendLayout(); this.panel1.SuspendLayout();
@ -148,37 +151,41 @@
// //
this.Commands.AllowUserToAddRows = false; this.Commands.AllowUserToAddRows = false;
resources.ApplyResources(this.Commands, "Commands"); resources.ApplyResources(this.Commands, "Commands");
dataGridViewCellStyle9.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle9.BackColor = System.Drawing.SystemColors.Control; dataGridViewCellStyle1.BackColor = System.Drawing.SystemColors.Control;
dataGridViewCellStyle9.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle9.ForeColor = System.Drawing.SystemColors.WindowText; dataGridViewCellStyle1.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle9.SelectionBackColor = System.Drawing.SystemColors.Highlight; dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle9.SelectionForeColor = System.Drawing.SystemColors.HighlightText; dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle9.WrapMode = System.Windows.Forms.DataGridViewTriState.True; dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle9; this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] { this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command, this.Command,
this.Param1, this.Param1,
this.Param2, this.Param2,
this.Param3, this.Param3,
this.Param4, this.Param4,
this.Lat,
this.Lon,
this.Alt,
this.Delete, this.Delete,
this.Up, this.Up,
this.Down}); this.Down});
this.Commands.Name = "Commands"; this.Commands.Name = "Commands";
dataGridViewCellStyle13.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; dataGridViewCellStyle5.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle13.BackColor = System.Drawing.SystemColors.Control; dataGridViewCellStyle5.BackColor = System.Drawing.SystemColors.Control;
dataGridViewCellStyle13.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); dataGridViewCellStyle5.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle13.ForeColor = System.Drawing.SystemColors.WindowText; dataGridViewCellStyle5.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle13.Format = "N0"; dataGridViewCellStyle5.Format = "N0";
dataGridViewCellStyle13.NullValue = "0"; dataGridViewCellStyle5.NullValue = "0";
dataGridViewCellStyle13.SelectionBackColor = System.Drawing.SystemColors.Highlight; dataGridViewCellStyle5.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle13.SelectionForeColor = System.Drawing.SystemColors.HighlightText; dataGridViewCellStyle5.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle13; this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle5;
dataGridViewCellStyle14.ForeColor = System.Drawing.Color.Black; dataGridViewCellStyle6.ForeColor = System.Drawing.Color.Black;
this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle14; this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle6;
this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick); this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick);
this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit); this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit);
this.Commands.DataError += new System.Windows.Forms.DataGridViewDataErrorEventHandler(this.Commands_DataError);
this.Commands.DefaultValuesNeeded += new System.Windows.Forms.DataGridViewRowEventHandler(this.Commands_DefaultValuesNeeded); this.Commands.DefaultValuesNeeded += new System.Windows.Forms.DataGridViewRowEventHandler(this.Commands_DefaultValuesNeeded);
this.Commands.EditingControlShowing += new System.Windows.Forms.DataGridViewEditingControlShowingEventHandler(this.Commands_EditingControlShowing); this.Commands.EditingControlShowing += new System.Windows.Forms.DataGridViewEditingControlShowingEventHandler(this.Commands_EditingControlShowing);
this.Commands.RowEnter += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_RowEnter); this.Commands.RowEnter += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_RowEnter);
@ -187,15 +194,16 @@
// //
// Command // Command
// //
dataGridViewCellStyle10.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); dataGridViewCellStyle2.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
dataGridViewCellStyle10.ForeColor = System.Drawing.Color.White; dataGridViewCellStyle2.ForeColor = System.Drawing.Color.White;
this.Command.DefaultCellStyle = dataGridViewCellStyle10; this.Command.DefaultCellStyle = dataGridViewCellStyle2;
this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox; this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox;
resources.ApplyResources(this.Command, "Command"); resources.ApplyResources(this.Command, "Command");
this.Command.Name = "Command"; this.Command.Name = "Command";
// //
// Param1 // Param1
// //
this.Param1.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Param1, "Param1"); resources.ApplyResources(this.Param1, "Param1");
this.Param1.Name = "Param1"; this.Param1.Name = "Param1";
this.Param1.Resizable = System.Windows.Forms.DataGridViewTriState.True; this.Param1.Resizable = System.Windows.Forms.DataGridViewTriState.True;
@ -203,6 +211,7 @@
// //
// Param2 // Param2
// //
this.Param2.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Param2, "Param2"); resources.ApplyResources(this.Param2, "Param2");
this.Param2.Name = "Param2"; this.Param2.Name = "Param2";
this.Param2.Resizable = System.Windows.Forms.DataGridViewTriState.True; this.Param2.Resizable = System.Windows.Forms.DataGridViewTriState.True;
@ -210,6 +219,7 @@
// //
// Param3 // Param3
// //
this.Param3.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Param3, "Param3"); resources.ApplyResources(this.Param3, "Param3");
this.Param3.Name = "Param3"; this.Param3.Name = "Param3";
this.Param3.Resizable = System.Windows.Forms.DataGridViewTriState.True; this.Param3.Resizable = System.Windows.Forms.DataGridViewTriState.True;
@ -217,9 +227,32 @@
// //
// Param4 // Param4
// //
this.Param4.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Param4, "Param4"); resources.ApplyResources(this.Param4, "Param4");
this.Param4.Name = "Param4"; this.Param4.Name = "Param4";
this.Param4.Resizable = System.Windows.Forms.DataGridViewTriState.True; this.Param4.Resizable = System.Windows.Forms.DataGridViewTriState.True;
this.Param4.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
//
// Lat
//
this.Lat.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Lat, "Lat");
this.Lat.Name = "Lat";
this.Lat.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
//
// Lon
//
this.Lon.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Lon, "Lon");
this.Lon.Name = "Lon";
this.Lon.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
//
// Alt
//
this.Alt.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.DisplayedCellsExceptHeader;
resources.ApplyResources(this.Alt, "Alt");
this.Alt.Name = "Alt";
this.Alt.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
// //
// Delete // Delete
// //
@ -229,7 +262,7 @@
// //
// Up // Up
// //
this.Up.DefaultCellStyle = dataGridViewCellStyle11; this.Up.DefaultCellStyle = dataGridViewCellStyle3;
resources.ApplyResources(this.Up, "Up"); resources.ApplyResources(this.Up, "Up");
this.Up.Image = global::ArdupilotMega.Properties.Resources.up; this.Up.Image = global::ArdupilotMega.Properties.Resources.up;
this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@ -237,8 +270,8 @@
// //
// Down // Down
// //
dataGridViewCellStyle12.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
this.Down.DefaultCellStyle = dataGridViewCellStyle12; this.Down.DefaultCellStyle = dataGridViewCellStyle4;
resources.ApplyResources(this.Down, "Down"); resources.ApplyResources(this.Down, "Down");
this.Down.Image = global::ArdupilotMega.Properties.Resources.down; this.Down.Image = global::ArdupilotMega.Properties.Resources.down;
this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@ -382,8 +415,8 @@
// //
// dataGridViewImageColumn1 // dataGridViewImageColumn1
// //
dataGridViewCellStyle15.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; dataGridViewCellStyle7.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle15; this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle7;
resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1"); resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1");
this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up; this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up;
this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@ -391,8 +424,8 @@
// //
// dataGridViewImageColumn2 // dataGridViewImageColumn2
// //
dataGridViewCellStyle16.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; dataGridViewCellStyle8.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle16; this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle8;
resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2"); resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2");
this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down; this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down;
this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@ -522,6 +555,14 @@
this.splitter1.Name = "splitter1"; this.splitter1.Name = "splitter1";
this.splitter1.TabStop = false; this.splitter1.TabStop = false;
// //
// BUT_Camera
//
resources.ApplyResources(this.BUT_Camera, "BUT_Camera");
this.BUT_Camera.Name = "BUT_Camera";
this.toolTip1.SetToolTip(this.BUT_Camera, resources.GetString("BUT_Camera.ToolTip"));
this.BUT_Camera.UseVisualStyleBackColor = true;
this.BUT_Camera.Click += new System.EventHandler(this.BUT_Camera_Click);
//
// BUT_grid // BUT_grid
// //
resources.ApplyResources(this.BUT_grid, "BUT_grid"); resources.ApplyResources(this.BUT_grid, "BUT_grid");
@ -790,14 +831,6 @@
resources.ApplyResources(this.panelBASE, "panelBASE"); resources.ApplyResources(this.panelBASE, "panelBASE");
this.panelBASE.Name = "panelBASE"; this.panelBASE.Name = "panelBASE";
// //
// BUT_Camera
//
resources.ApplyResources(this.BUT_Camera, "BUT_Camera");
this.BUT_Camera.Name = "BUT_Camera";
this.toolTip1.SetToolTip(this.BUT_Camera, resources.GetString("BUT_Camera.ToolTip"));
this.BUT_Camera.UseVisualStyleBackColor = true;
this.BUT_Camera.Click += new System.EventHandler(this.BUT_Camera_Click);
//
// FlightPlanner // FlightPlanner
// //
resources.ApplyResources(this, "$this"); resources.ApplyResources(this, "$this");
@ -878,14 +911,6 @@
private BSE.Windows.Forms.Splitter splitter1; private BSE.Windows.Forms.Splitter splitter1;
private System.Windows.Forms.Panel panelBASE; private System.Windows.Forms.Panel panelBASE;
private System.Windows.Forms.Label lbl_homedist; private System.Windows.Forms.Label lbl_homedist;
private System.Windows.Forms.DataGridViewComboBoxColumn Command;
private System.Windows.Forms.DataGridViewTextBoxColumn Param1;
private System.Windows.Forms.DataGridViewTextBoxColumn Param2;
private System.Windows.Forms.DataGridViewTextBoxColumn Param3;
private System.Windows.Forms.DataGridViewTextBoxColumn Param4;
private System.Windows.Forms.DataGridViewButtonColumn Delete;
private System.Windows.Forms.DataGridViewImageColumn Up;
private System.Windows.Forms.DataGridViewImageColumn Down;
private MyButton BUT_Prefetch; private MyButton BUT_Prefetch;
private MyButton BUT_grid; private MyButton BUT_grid;
private System.Windows.Forms.ContextMenuStrip contextMenuStrip1; private System.Windows.Forms.ContextMenuStrip contextMenuStrip1;
@ -906,5 +931,16 @@
private System.Windows.Forms.ToolStripSeparator toolStripSeparator1; private System.Windows.Forms.ToolStripSeparator toolStripSeparator1;
private System.Windows.Forms.ToolStripMenuItem deleteWPToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem deleteWPToolStripMenuItem;
private MyButton BUT_Camera; private MyButton BUT_Camera;
private System.Windows.Forms.DataGridViewComboBoxColumn Command;
private System.Windows.Forms.DataGridViewTextBoxColumn Param1;
private System.Windows.Forms.DataGridViewTextBoxColumn Param2;
private System.Windows.Forms.DataGridViewTextBoxColumn Param3;
private System.Windows.Forms.DataGridViewTextBoxColumn Param4;
private System.Windows.Forms.DataGridViewTextBoxColumn Lat;
private System.Windows.Forms.DataGridViewTextBoxColumn Lon;
private System.Windows.Forms.DataGridViewTextBoxColumn Alt;
private System.Windows.Forms.DataGridViewButtonColumn Delete;
private System.Windows.Forms.DataGridViewImageColumn Up;
private System.Windows.Forms.DataGridViewImageColumn Down;
} }
} }

View File

@ -25,7 +25,6 @@ namespace ArdupilotMega.GCSViews
partial class FlightPlanner : MyUserControl partial class FlightPlanner : MyUserControl
{ {
int selectedrow = 0; int selectedrow = 0;
int t7 = 10000000;
bool quickadd = false; bool quickadd = false;
bool isonline = true; bool isonline = true;
bool sethome = false; bool sethome = false;
@ -37,8 +36,7 @@ namespace ArdupilotMega.GCSViews
private TextBox textBox1; private TextBox textBox1;
private ComponentResourceManager rm = new ComponentResourceManager(typeof(FlightPlanner)); private ComponentResourceManager rm = new ComponentResourceManager(typeof(FlightPlanner));
private Dictionary<MAVLink.MAV_CMD, string> cmdNames = new Dictionary<MAVLink.MAV_CMD, string>(); private Dictionary<string, string[]> cmdParamNames = new Dictionary<string, string[]>();
private Dictionary<MAVLink.MAV_CMD, string[]> cmdParamNames = new Dictionary<MAVLink.MAV_CMD, string[]>();
/// <summary> /// <summary>
@ -154,20 +152,21 @@ namespace ArdupilotMega.GCSViews
for (int i = 0; i < matchs.Count; i++) for (int i = 0; i < matchs.Count; i++)
{ {
Locationwp temp = new Locationwp(); Locationwp temp = new Locationwp();
temp.options = 1;
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), matchs[i].Groups[1].Value.ToString().Replace("NAV_", ""), false); temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), matchs[i].Groups[1].Value.ToString().Replace("NAV_", ""), false);
temp.p1 = byte.Parse(matchs[i].Groups[2].Value.ToString()); temp.p1 = byte.Parse(matchs[i].Groups[2].Value.ToString());
if (temp.id < (byte)MAVLink.MAV_CMD.LAST) if (temp.id < (byte)MAVLink.MAV_CMD.LAST)
{ {
temp.alt = (int)(double.Parse(matchs[i].Groups[3].Value.ToString(), new System.Globalization.CultureInfo("en-US")) * 100); temp.alt = (float)(double.Parse(matchs[i].Groups[3].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
temp.lat = (int)(double.Parse(matchs[i].Groups[4].Value.ToString(), new System.Globalization.CultureInfo("en-US")) * 10000000); temp.lat = (float)(double.Parse(matchs[i].Groups[4].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
temp.lng = (int)(double.Parse(matchs[i].Groups[5].Value.ToString(), new System.Globalization.CultureInfo("en-US")) * 10000000); temp.lng = (float)(double.Parse(matchs[i].Groups[5].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
} }
else else
{ {
temp.alt = (int)(double.Parse(matchs[i].Groups[3].Value.ToString(), new System.Globalization.CultureInfo("en-US"))); temp.alt = (float)(double.Parse(matchs[i].Groups[3].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
temp.lat = (int)(double.Parse(matchs[i].Groups[4].Value.ToString(), new System.Globalization.CultureInfo("en-US"))); temp.lat = (float)(double.Parse(matchs[i].Groups[4].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
temp.lng = (int)(double.Parse(matchs[i].Groups[5].Value.ToString(), new System.Globalization.CultureInfo("en-US"))); temp.lng = (float)(double.Parse(matchs[i].Groups[5].Value.ToString(), new System.Globalization.CultureInfo("en-US")));
} }
cmds.Add(temp); cmds.Add(temp);
@ -261,26 +260,26 @@ namespace ArdupilotMega.GCSViews
return; return;
} }
DataGridViewTextBoxCell cell; DataGridViewTextBoxCell cell;
if (Commands.Columns[Param3.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][2]/*"Lat"*/)) if (Commands.Columns[Lat.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][4]/*"Lat"*/))
{ {
cell = Commands.Rows[selectedrow].Cells[3] as DataGridViewTextBoxCell; cell = Commands.Rows[selectedrow].Cells[Lat.Index] as DataGridViewTextBoxCell;
cell.Value = lat.ToString("0.0000000"); cell.Value = lat.ToString("0.0000000");
cell.DataGridView.EndEdit(); cell.DataGridView.EndEdit();
} }
if (Commands.Columns[Param4.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][3]/*"Long"*/)) if (Commands.Columns[Lon.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][5]/*"Long"*/))
{ {
cell = Commands.Rows[selectedrow].Cells[4] as DataGridViewTextBoxCell; cell = Commands.Rows[selectedrow].Cells[Lon.Index] as DataGridViewTextBoxCell;
cell.Value = lng.ToString("0.0000000"); cell.Value = lng.ToString("0.0000000");
cell.DataGridView.EndEdit(); cell.DataGridView.EndEdit();
} }
if (Commands.Columns[Param1.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][0]/*"Delay"*/)) if (Commands.Columns[Param1.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][0]/*"Delay"*/))
{ {
cell = Commands.Rows[selectedrow].Cells[1] as DataGridViewTextBoxCell; cell = Commands.Rows[selectedrow].Cells[Param1.Index] as DataGridViewTextBoxCell;
cell.Value = 0; cell.Value = 0;
} }
if (alt != -1 && Commands.Columns[Param2.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][1]/*"Alt"*/)) if (alt != -1 && Commands.Columns[Alt.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][6]/*"Alt"*/))
{ {
cell = Commands.Rows[selectedrow].Cells[2] as DataGridViewTextBoxCell; cell = Commands.Rows[selectedrow].Cells[Alt.Index] as DataGridViewTextBoxCell;
cell.Value = TXT_DefaultAlt.Text; cell.Value = TXT_DefaultAlt.Text;
@ -493,46 +492,7 @@ namespace ArdupilotMega.GCSViews
catch { } catch { }
} }
updateCMDParams();
// add first to keep order
foreach (object cmd in Enum.GetValues(typeof(MAVLink.MAV_CMD)))
{
string str = cmd.ToString();
if (!str.EndsWith("LAST") && !str.EndsWith("END"))
{
cmdNames[(MAVLink.MAV_CMD)cmd] = str;
cmdParamNames[(MAVLink.MAV_CMD)cmd] = new string[] { "setme", "setme", "setme", "setme" };
}
}
// replace with localizied text
// the command name and param names are stored in TXT_MAV_CMD, one comand per line, in following format:
// COMMAND_TYPE;COMMAND_NAME;PARAM_1_HEAD;PARAM_2_HEAD;PARAM_3_HEAD;PARAM_4_HEAD;
string[] cmds = rm.GetString("MAVCmd").Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
rm.ReleaseAllResources();
foreach (string cmd in cmds)
{
string[] field = cmd.Split(new char[] { ';' }, StringSplitOptions.RemoveEmptyEntries);
if (field.Length >= 2)
{
MAVLink.MAV_CMD type = (MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), field[0]);
cmdNames[type] = field[1];
if (field.Length == 6)
{
string[] param = new string[4];
Array.Copy(field, 2, param, 0, 4);
cmdParamNames[type] = param;
}
}
}
Command.DataSource = new List<KeyValuePair<MAVLink.MAV_CMD, string>>(cmdNames as ICollection<KeyValuePair<MAVLink.MAV_CMD, string>>)/*)*/;
Command.ValueMember = "Key";
Command.DisplayMember = "Value";
Up.Image = global::ArdupilotMega.Properties.Resources.up; Up.Image = global::ArdupilotMega.Properties.Resources.up;
Down.Image = global::ArdupilotMega.Properties.Resources.down; Down.Image = global::ArdupilotMega.Properties.Resources.down;
@ -544,6 +504,80 @@ namespace ArdupilotMega.GCSViews
} }
} }
void updateCMDParams()
{
cmdParamNames = readCMDXML();
List<string> cmds = new List<string>();
foreach (string item in cmdParamNames.Keys)
{
cmds.Add(item);
}
Command.DataSource = cmds;
}
Dictionary<string, string[]> readCMDXML()
{
Dictionary<string, string[]> cmd = new Dictionary<string, string[]>();
// do lang stuff here
string file = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "mavcmd.xml";
using (XmlReader reader = XmlReader.Create(file))
{
reader.Read();
reader.ReadStartElement("CMD");
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}
else
{
reader.ReadToFollowing("AC2");
}
XmlReader inner = reader.ReadSubtree();
inner.Read();
inner.MoveToElement();
inner.Read();
while (inner.Read())
{
inner.MoveToElement();
if (inner.IsStartElement())
{
string cmdname = inner.Name;
string[] cmdarray = new string[7];
int b = 0;
XmlReader inner2 = inner.ReadSubtree();
inner2.Read();
while (inner2.Read())
{
inner2.MoveToElement();
if (inner2.IsStartElement())
{
cmdarray[b] = inner2.ReadString();
b++;
}
}
cmd[cmdname] = cmdarray;
}
}
}
return cmd;
}
void Commands_DataError(object sender, DataGridViewDataErrorEventArgs e) void Commands_DataError(object sender, DataGridViewDataErrorEventArgs e)
{ {
Console.WriteLine(e.Exception.ToString() + " " + e.Context + " col " + e.ColumnIndex); Console.WriteLine(e.Exception.ToString() + " " + e.Context + " col " + e.ColumnIndex);
@ -606,40 +640,21 @@ namespace ArdupilotMega.GCSViews
isonline = false; isonline = false;
} }
updateCMDParams();
writeKML(); writeKML();
} }
private void ChangeColumnHeader(MAVLink.MAV_CMD command) private void ChangeColumnHeader(string command)
{ {
try try
{ {
if (cmdParamNames.ContainsKey(command)) if (cmdParamNames.ContainsKey(command))
for (int i = 1; i <= 4; i++) for (int i = 1; i <= 7; i++)
Commands.Columns[i].HeaderText = cmdParamNames[command][i - 1]; Commands.Columns[i].HeaderText = cmdParamNames[command][i - 1];
else else
for (int i = 1; i <= 4; i++) for (int i = 1; i <= 7; i++)
Commands.Columns[i].HeaderText = "setme"; Commands.Columns[i].HeaderText = "setme";
switch (command)
{
case MAVLink.MAV_CMD.WAYPOINT:
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A";
break;
case MAVLink.MAV_CMD.LAND:
Commands.Columns[1].HeaderText = "N/A";
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
{
Commands.Columns[2].HeaderText = "N/A";
Commands.Columns[3].HeaderText = "N/A";
Commands.Columns[4].HeaderText = "N/A";
}
break;
case MAVLink.MAV_CMD.TAKEOFF:
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A";
break;
}
} }
catch (Exception ex) { MessageBox.Show(ex.ToString()); } catch (Exception ex) { MessageBox.Show(ex.ToString()); }
} }
@ -656,8 +671,9 @@ namespace ArdupilotMega.GCSViews
try try
{ {
selectedrow = e.RowIndex; selectedrow = e.RowIndex;
/*string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString();*/ string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString();
MAVLink.MAV_CMD cmd = (MAVLink.MAV_CMD)Commands[0, selectedrow].Value; string cmd = Commands[0, selectedrow].Value.ToString();
Console.WriteLine("editformat " + option + " value " + cmd);
ChangeColumnHeader(cmd); ChangeColumnHeader(cmd);
} }
catch (Exception ex) { MessageBox.Show(ex.ToString()); } catch (Exception ex) { MessageBox.Show(ex.ToString()); }
@ -668,7 +684,7 @@ namespace ArdupilotMega.GCSViews
DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell; DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell;
if (cell.Value == null) if (cell.Value == null)
{ {
cell.Value = MAVLink.MAV_CMD.WAYPOINT/*"WAYPOINT"*/; cell.Value = "WAYPOINT";
Commands.Rows[e.RowIndex].Cells[Delete.Index].Value = "X"; Commands.Rows[e.RowIndex].Cells[Delete.Index].Value = "X";
if (!quickadd) if (!quickadd)
{ {
@ -684,7 +700,7 @@ namespace ArdupilotMega.GCSViews
{ {
Commands.CurrentCell = Commands.Rows[e.RowIndex].Cells[0]; Commands.CurrentCell = Commands.Rows[e.RowIndex].Cells[0];
if ((MAVLink.MAV_CMD)Commands.Rows[e.RowIndex - 1].Cells[Command.Index].Value/*.ToString()*/ == MAVLink.MAV_CMD.WAYPOINT/*"WAYPOINT"*/) if (Commands.Rows[e.RowIndex - 1].Cells[Command.Index].Value.ToString() == "WAYPOINT")
{ {
Commands.Rows[e.RowIndex].Selected = true; // highlight row Commands.Rows[e.RowIndex].Selected = true; // highlight row
} }
@ -706,7 +722,8 @@ namespace ArdupilotMega.GCSViews
{ {
DataGridViewTextBoxCell cell; DataGridViewTextBoxCell cell;
cell = Commands.Rows[selectedrow].Cells[a] as DataGridViewTextBoxCell; cell = Commands.Rows[selectedrow].Cells[a] as DataGridViewTextBoxCell;
if (Commands.Columns[a].HeaderText.Equals("N/A"))
if (Commands.Columns[a].HeaderText.Equals("") && cell != null && cell.Value == null)
{ {
cell.Value = "0"; cell.Value = "0";
} }
@ -714,10 +731,11 @@ namespace ArdupilotMega.GCSViews
{ {
if (cell != null && (cell.Value == null || cell.Value.ToString() == "")) if (cell != null && (cell.Value == null || cell.Value.ToString() == ""))
{ {
cell.Value = "I need Data"; cell.Value = "?";
} }
else else
{ {
// not a text box
} }
} }
} }
@ -740,30 +758,6 @@ namespace ArdupilotMega.GCSViews
} }
} }
/// <summary>
/// copy of ardupilot code for getting distance between WP's
/// </summary>
/// <param name="loc1"></param>
/// <param name="loc2"></param>
/// <returns></returns>
double getDistance(Locationwp loc1, Locationwp loc2)
{
if (loc1.lat == 0 || loc1.lng == 0)
return -1;
if (loc2.lat == 0 || loc2.lng == 0)
return -1;
// this is used to offset the shrinking longitude as we go towards the poles
double rads = (double)((Math.Abs(loc2.lat) / t7) * 0.0174532925);
//377,173,810 / 10,000,000 = 37.717381 * 0.0174532925 = 0.658292482926943
double scaleLongDown = Math.Cos(rads);
double scaleLongUp = 1.0f / Math.Cos(rads);
float dlat = (float)(loc2.lat - loc1.lat);
float dlong = (float)(((float)(loc2.lng - loc1.lng)) * scaleLongDown);
return Math.Sqrt(Math.Pow(dlat, 2) + Math.Pow(dlong, 2)) * .01113195;
}
/// <summary> /// <summary>
/// used to add a marker to the map display /// used to add a marker to the map display
@ -911,17 +905,16 @@ namespace ArdupilotMega.GCSViews
{ {
try try
{ {
//int command = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false); int command = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
int command = (byte)(MAVLink.MAV_CMD)Commands.Rows[a].Cells[0].Value;
if (command < (byte)MAVLink.MAV_CMD.LAST && command != (byte)MAVLink.MAV_CMD.TAKEOFF) if (command < (byte)MAVLink.MAV_CMD.LAST && command != (byte)MAVLink.MAV_CMD.TAKEOFF)
{ {
string cell2 = Commands.Rows[a].Cells[Param2.Index].Value.ToString(); // alt string cell2 = Commands.Rows[a].Cells[Alt.Index].Value.ToString(); // alt
string cell3 = Commands.Rows[a].Cells[Param3.Index].Value.ToString(); // lat string cell3 = Commands.Rows[a].Cells[Lat.Index].Value.ToString(); // lat
string cell4 = Commands.Rows[a].Cells[Param4.Index].Value.ToString(); // lng string cell4 = Commands.Rows[a].Cells[Lon.Index].Value.ToString(); // lng
if (cell4 == "0" || cell3 == "0") if (cell4 == "0" || cell3 == "0")
continue; continue;
if (cell4 == "I need Data" || cell3 == "I need Data") if (cell4 == "?" || cell3 == "?")
continue; continue;
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString())); pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
@ -951,11 +944,11 @@ namespace ArdupilotMega.GCSViews
float range = 4000; float range = 4000;
Locationwp loc1 = new Locationwp(); Locationwp loc1 = new Locationwp();
loc1.lat = (int)(minlat * t7); loc1.lat = (float)(minlat);
loc1.lng = (int)(minlong * t7); loc1.lng = (float)(minlong);
Locationwp loc2 = new Locationwp(); Locationwp loc2 = new Locationwp();
loc2.lat = (int)(maxlat * t7); loc2.lat = (float)(maxlat);
loc2.lng = (int)(maxlong * t7); loc2.lng = (float)(maxlong);
//double distance = getDistance(loc1, loc2); // same code as ardupilot //double distance = getDistance(loc1, loc2); // same code as ardupilot
double distance = 2000; double distance = 2000;
@ -1019,8 +1012,8 @@ namespace ArdupilotMega.GCSViews
private void savewaypoints() private void savewaypoints()
{ {
SaveFileDialog fd = new SaveFileDialog(); SaveFileDialog fd = new SaveFileDialog();
fd.Filter = "Ardupilot Mission (*.h)|*.*"; fd.Filter = "Ardupilot Mission (*.txt)|*.*";
fd.DefaultExt = ".h"; fd.DefaultExt = ".txt";
DialogResult result = fd.ShowDialog(); DialogResult result = fd.ShowDialog();
string file = fd.FileName; string file = fd.FileName;
if (file != "") if (file != "")
@ -1028,26 +1021,33 @@ namespace ArdupilotMega.GCSViews
try try
{ {
StreamWriter sw = new StreamWriter(file); StreamWriter sw = new StreamWriter(file);
sw.WriteLine("#define WP_RADIUS " + TXT_WPRad.Text.ToString() + " // What is the minimum distance to reach a waypoint?"); sw.WriteLine("QGC WPL 110");
sw.WriteLine("#define LOITER_RADIUS " + TXT_loiterrad.Text.ToString() + " // How close to Loiter?"); try
sw.WriteLine("#define HOLD_CURRENT_ALT 0 // 1 = hold the current altitude, 0 = use the defined altitude to for RTL"); {
sw.WriteLine("#define ALT_TO_HOLD " + TXT_DefaultAlt.Text); sw.WriteLine("0\t1\t0\t16\t0\t0\t0\t0\t" + double.Parse(TXT_homelat.Text).ToString("0.000000", new System.Globalization.CultureInfo("en-US")) + "\t" + double.Parse(TXT_homelng.Text).ToString("0.000000", new System.Globalization.CultureInfo("en-US")) + "\t" + double.Parse(TXT_homealt.Text).ToString("0.000000", new System.Globalization.CultureInfo("en-US")) + "\t1");
sw.WriteLine(""); }
sw.WriteLine("float mission[][5] = {"); catch
{
sw.WriteLine("0\t1\t0\t0\t0\t0\t0\t0\t0\t0\t0\t1");
}
for (int a = 0; a < Commands.Rows.Count - 0; a++) for (int a = 0; a < Commands.Rows.Count - 0; a++)
{ {
sw.Write("{" + Commands.Rows[a].Cells[0].Value.ToString() + ","); byte mode = (byte)(MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[0].Value.ToString());
sw.Write(Commands.Rows[a].Cells[1].Value.ToString() + ",");
sw.Write(double.Parse(Commands.Rows[a].Cells[2].Value.ToString()).ToString(new System.Globalization.CultureInfo("en-US")) + ","); sw.Write((a + 1)); // seq
sw.Write(double.Parse(Commands.Rows[a].Cells[3].Value.ToString()).ToString(new System.Globalization.CultureInfo("en-US")) + ","); sw.Write("\t" + 0); // current
sw.Write(double.Parse(Commands.Rows[a].Cells[4].Value.ToString()).ToString(new System.Globalization.CultureInfo("en-US")) + "}"); sw.Write("\t" + (CHK_altmode.Checked == true ? (byte)MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL : (byte)MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT)); //frame
//if (a < Commands.Rows.Count - 2) sw.Write("\t" + mode);
//{ sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write(","); sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
//} sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + (double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + 1);
sw.WriteLine(""); sw.WriteLine("");
} }
sw.WriteLine("};");
sw.Close(); sw.Close();
} }
catch (Exception) { MessageBox.Show("Error writing file"); } catch (Exception) { MessageBox.Show("Error writing file"); }
@ -1183,9 +1183,9 @@ namespace ArdupilotMega.GCSViews
try try
{ {
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT; home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
home.lat = (int)(float.Parse(TXT_homelat.Text) * 10000000); home.lat = (float.Parse(TXT_homelat.Text));
home.lng = (int)(float.Parse(TXT_homelng.Text) * 10000000); home.lng = (float.Parse(TXT_homelng.Text));
home.alt = (int)(float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist * 100); // use saved home home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
} }
catch { throw new Exception("Your home location is invalid"); } catch { throw new Exception("Your home location is invalid"); }
@ -1199,8 +1199,8 @@ namespace ArdupilotMega.GCSViews
for (int a = 0; a < Commands.Rows.Count - 0; a++) for (int a = 0; a < Commands.Rows.Count - 0; a++)
{ {
Locationwp temp = new Locationwp(); Locationwp temp = new Locationwp();
temp.id = (byte)(MAVLink.MAV_CMD)Commands.Rows[a].Cells[0].Value;// (int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[0].Value.ToString(), false); temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
temp.p1 = byte.Parse(Commands.Rows[a].Cells[1].Value.ToString()); temp.p1 = float.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString());
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME) if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
{ {
if (CHK_altmode.Checked) if (CHK_altmode.Checked)
@ -1211,25 +1211,15 @@ namespace ArdupilotMega.GCSViews
{ {
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT; frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
} }
temp.alt = (int)(double.Parse(Commands.Rows[a].Cells[2].Value.ToString()) / MainV2.cs.multiplierdist * 100);
temp.lat = (int)(double.Parse(Commands.Rows[a].Cells[3].Value.ToString()) * 10000000);
temp.lng = (int)(double.Parse(Commands.Rows[a].Cells[4].Value.ToString()) * 10000000);
} }
else
{
frame = MAVLink.MAV_FRAME.MAV_FRAME_MISSION;
temp.alt = (int)(double.Parse(Commands.Rows[a].Cells[2].Value.ToString())); temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
temp.lat = (int)(double.Parse(Commands.Rows[a].Cells[3].Value.ToString())); temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
temp.lng = (int)(double.Parse(Commands.Rows[a].Cells[4].Value.ToString())); temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
if (temp.id == (byte)MAVLink.MAV_CMD.CONDITION_CHANGE_ALT && !CHK_altmode.Checked) temp.p2 = (float)(double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()));
{ temp.p3 = (float)(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()));
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT; temp.p4 = (float)(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()));
temp.alt = (int)(double.Parse(Commands.Rows[a].Cells[2].Value.ToString()) / MainV2.cs.multiplierdist);
}
}
port.setWP(temp, (ushort)(a + 1), frame, 0); port.setWP(temp, (ushort)(a + 1), frame, 0);
} }
@ -1294,6 +1284,7 @@ namespace ArdupilotMega.GCSViews
foreach (Locationwp temp in cmds) foreach (Locationwp temp in cmds)
{ {
i++; i++;
//Console.WriteLine("FP processToScreen " + i);
if (temp.id == 0 && i != 0) // 0 and not home if (temp.id == 0 && i != 0) // 0 and not home
break; break;
if (temp.id == 255 && i != 0) // bad record - never loaded any WP's - but have started the board up. if (temp.id == 255 && i != 0) // bad record - never loaded any WP's - but have started the board up.
@ -1307,19 +1298,19 @@ namespace ArdupilotMega.GCSViews
DataGridViewTextBoxCell cell; DataGridViewTextBoxCell cell;
DataGridViewComboBoxCell cellcmd; DataGridViewComboBoxCell cellcmd;
cellcmd = Commands.Rows[i].Cells[Command.Index] as DataGridViewComboBoxCell; cellcmd = Commands.Rows[i].Cells[Command.Index] as DataGridViewComboBoxCell;
cellcmd.Value = temp.id == 0 ? MAVLink.MAV_CMD.WAYPOINT : (MAVLink.MAV_CMD)temp.id; // treat home as a waypoint to avoid data error. cellcmd.Value = "WAYPOINT";
/*foreach (object value in Enum.GetValues(typeof(MAVLink.MAV_CMD)))
foreach (object value in Enum.GetValues(typeof(MAVLink.MAV_CMD)))
{ {
if ((int)value == temp.id) if ((int)value == temp.id)
{ {
cellcmd.Value = value.ToString(); cellcmd.Value = value.ToString();
break; break;
} }
}*/ }
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME) if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
{ {
int alt = temp.alt;
if ((temp.options & 0x1) == 0 && i != 0) // home is always abs if ((temp.options & 0x1) == 0 && i != 0) // home is always abs
{ {
CHK_altmode.Checked = true; CHK_altmode.Checked = true;
@ -1329,31 +1320,32 @@ namespace ArdupilotMega.GCSViews
CHK_altmode.Checked = false; CHK_altmode.Checked = false;
} }
}
int alt = (int)temp.alt;
cell = Commands.Rows[i].Cells[Alt.Index] as DataGridViewTextBoxCell;
cell.Value = (int)((double)alt * MainV2.cs.multiplierdist);
cell = Commands.Rows[i].Cells[Lat.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lat;
cell = Commands.Rows[i].Cells[Lon.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lng;
cell = Commands.Rows[i].Cells[Param1.Index] as DataGridViewTextBoxCell; cell = Commands.Rows[i].Cells[Param1.Index] as DataGridViewTextBoxCell;
cell.Value = temp.p1; cell.Value = temp.p1;
cell = Commands.Rows[i].Cells[Param2.Index] as DataGridViewTextBoxCell; cell = Commands.Rows[i].Cells[Param2.Index] as DataGridViewTextBoxCell;
cell.Value = (int)((double)alt * MainV2.cs.multiplierdist / 100); cell.Value = temp.p2;
cell = Commands.Rows[i].Cells[Param3.Index] as DataGridViewTextBoxCell; cell = Commands.Rows[i].Cells[Param3.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lat / 10000000; cell.Value = temp.p3;
cell = Commands.Rows[i].Cells[Param4.Index] as DataGridViewTextBoxCell; cell = Commands.Rows[i].Cells[Param4.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lng / 10000000; cell.Value = temp.p4;
}
else
{
cell = Commands.Rows[i].Cells[Param1.Index] as DataGridViewTextBoxCell;
cell.Value = temp.p1;
cell = Commands.Rows[i].Cells[Param2.Index] as DataGridViewTextBoxCell;
cell.Value = temp.alt;
cell = Commands.Rows[i].Cells[Param3.Index] as DataGridViewTextBoxCell;
cell.Value = temp.lat;
cell = Commands.Rows[i].Cells[Param4.Index] as DataGridViewTextBoxCell;
cell.Value = temp.lng;
}
} }
try try
{ {
DataGridViewTextBoxCell cellhome; DataGridViewTextBoxCell cellhome;
cellhome = Commands.Rows[0].Cells[Param3.Index] as DataGridViewTextBoxCell; cellhome = Commands.Rows[0].Cells[Lat.Index] as DataGridViewTextBoxCell;
if (cellhome.Value != null) if (cellhome.Value != null)
{ {
if (cellhome.Value.ToString() != TXT_homelat.Text) if (cellhome.Value.ToString() != TXT_homelat.Text)
@ -1363,9 +1355,9 @@ namespace ArdupilotMega.GCSViews
if (dr == DialogResult.Yes) if (dr == DialogResult.Yes)
{ {
TXT_homelat.Text = (double.Parse(cellhome.Value.ToString())).ToString(); TXT_homelat.Text = (double.Parse(cellhome.Value.ToString())).ToString();
cellhome = Commands.Rows[0].Cells[Param4.Index] as DataGridViewTextBoxCell; cellhome = Commands.Rows[0].Cells[Lon.Index] as DataGridViewTextBoxCell;
TXT_homelng.Text = (double.Parse(cellhome.Value.ToString())).ToString(); TXT_homelng.Text = (double.Parse(cellhome.Value.ToString())).ToString();
cellhome = Commands.Rows[0].Cells[Param2.Index] as DataGridViewTextBoxCell; cellhome = Commands.Rows[0].Cells[Alt.Index] as DataGridViewTextBoxCell;
TXT_homealt.Text = (double.Parse(cellhome.Value.ToString()) * MainV2.cs.multiplierdist).ToString(); TXT_homealt.Text = (double.Parse(cellhome.Value.ToString()) * MainV2.cs.multiplierdist).ToString();
} }
} }
@ -1598,14 +1590,104 @@ namespace ArdupilotMega.GCSViews
private void BUT_loadwpfile_Click(object sender, EventArgs e) private void BUT_loadwpfile_Click(object sender, EventArgs e)
{ {
OpenFileDialog fd = new OpenFileDialog(); OpenFileDialog fd = new OpenFileDialog();
fd.Filter = "Ardupilot Mission (*.h)|*.*"; fd.Filter = "Ardupilot Mission (*.txt)|*.*";
fd.DefaultExt = ".h"; fd.DefaultExt = ".txt";
DialogResult result = fd.ShowDialog(); DialogResult result = fd.ShowDialog();
string file = fd.FileName; string file = fd.FileName;
if (file != "") if (file != "")
{
if (file.ToLower().EndsWith(".h"))
{ {
readwaypointwritterfile(file); readwaypointwritterfile(file);
} }
else
{
readQGC110wpfile(file);
}
}
}
void readQGC110wpfile(string file)
{
int wp_count = 0;
bool error = false;
List<Locationwp> cmds = new List<Locationwp>();
try
{
StreamReader sr = new StreamReader(file); //"defines.h"
string header = sr.ReadLine();
if (header == null || !header.Contains("QGC WPL 110"))
{
MessageBox.Show("Invalid Waypoint file");
return;
}
while (!error && !sr.EndOfStream)
{
string line = sr.ReadLine();
// waypoints
if (line.StartsWith("#"))
continue;
string[] items = line.Split(new char[] { (char)'\t', ' ' }, StringSplitOptions.RemoveEmptyEntries);
if (items.Length <= 9)
continue;
try
{
Locationwp temp = new Locationwp();
if (items[2] == "3")
{ // abs MAV_FRAME_GLOBAL_RELATIVE_ALT=3
temp.options = 1;
}
else
{
temp.options = 0;
}
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), items[3], false);
temp.p1 = float.Parse(items[4], new System.Globalization.CultureInfo("en-US"));
if (temp.id == 99)
temp.id = 0;
temp.alt = (float)(double.Parse(items[10], new System.Globalization.CultureInfo("en-US")));
temp.lat = (float)(double.Parse(items[8], new System.Globalization.CultureInfo("en-US")));
temp.lng = (float)(double.Parse(items[9], new System.Globalization.CultureInfo("en-US")));
temp.p2 = (float)(double.Parse(items[5], new System.Globalization.CultureInfo("en-US")));
temp.p3 = (float)(double.Parse(items[6], new System.Globalization.CultureInfo("en-US")));
temp.p4 = (float)(double.Parse(items[7], new System.Globalization.CultureInfo("en-US")));
cmds.Add(temp);
wp_count++;
}
catch { MessageBox.Show("Line invalid\n" + line); }
if (wp_count == byte.MaxValue)
{
MessageBox.Show("To many Waypoints!!!");
break;
}
}
sr.Close();
processToScreen(cmds);
writeKML();
MainMap.ZoomAndCenterMarkers("objects");
}
catch (Exception ex)
{
MessageBox.Show("Can't open file! " + ex.ToString());
}
} }
private void trackBar1_ValueChanged(object sender, EventArgs e) private void trackBar1_ValueChanged(object sender, EventArgs e)
@ -1721,7 +1803,7 @@ namespace ArdupilotMega.GCSViews
{ {
if (CurentRectMarker.InnerMarker.Tag.ToString().Contains("grid")) if (CurentRectMarker.InnerMarker.Tag.ToString().Contains("grid"))
{ {
drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid","")) - 1] = new PointLatLng(end.Lat,end.Lng); drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", "")) - 1] = new PointLatLng(end.Lat, end.Lng);
MainMap.UpdatePolygonLocalPosition(drawnpolygon); MainMap.UpdatePolygonLocalPosition(drawnpolygon);
} }
else else
@ -1990,7 +2072,7 @@ namespace ArdupilotMega.GCSViews
{ {
// update row headers // update row headers
((ComboBox)sender).ForeColor = Color.White; ((ComboBox)sender).ForeColor = Color.White;
ChangeColumnHeader((MAVLink.MAV_CMD)((ComboBox)sender).SelectedValue); ChangeColumnHeader(((ComboBox)sender).Text);
} }
/// <summary> /// <summary>
/// Get the Google earth ALT for a given coord /// Get the Google earth ALT for a given coord
@ -2244,7 +2326,7 @@ namespace ArdupilotMega.GCSViews
double x = bottomleft.Lat - Math.Abs(fulllatdiff); double x = bottomleft.Lat - Math.Abs(fulllatdiff);
double y = bottomleft.Lng - Math.Abs(fulllngdiff); double y = bottomleft.Lng - Math.Abs(fulllngdiff);
Console.WriteLine("{0} < {1} {2} < {3}", x , (topright.Lat) ,y , (topright.Lng)); Console.WriteLine("{0} < {1} {2} < {3}", x, (topright.Lat), y, (topright.Lng));
while (x < (topright.Lat + Math.Abs(fulllatdiff)) && y < (topright.Lng + Math.Abs(fulllngdiff))) while (x < (topright.Lat + Math.Abs(fulllatdiff)) && y < (topright.Lng + Math.Abs(fulllngdiff)))
{ {
@ -2341,7 +2423,7 @@ namespace ArdupilotMega.GCSViews
newlatlong = FindLineIntersection(area.Points[a - 1], area.Points[a], new PointLatLng(ax, ay), new PointLatLng(bx, by)); newlatlong = FindLineIntersection(area.Points[a - 1], area.Points[a], new PointLatLng(ax, ay), new PointLatLng(bx, by));
if (!newlatlong.IsZero) if (!newlatlong.IsZero)
{ {
if (noc > MainMap.Manager.GetDistance(new PointLatLng(ax, ay),newlatlong)) if (noc > MainMap.Manager.GetDistance(new PointLatLng(ax, ay), newlatlong))
{ {
closestlatlong.Lat = newlatlong.Lat; closestlatlong.Lat = newlatlong.Lat;
closestlatlong.Lng = newlatlong.Lng; closestlatlong.Lng = newlatlong.Lng;
@ -2433,7 +2515,7 @@ namespace ArdupilotMega.GCSViews
if (startmeasure.IsZero) if (startmeasure.IsZero)
{ {
startmeasure = start; startmeasure = start;
polygons.Markers.Add( new GMapMarkerGoogleRed(start)); polygons.Markers.Add(new GMapMarkerGoogleRed(start));
MainMap.Invalidate(); MainMap.Invalidate();
} }
else else
@ -2442,14 +2524,14 @@ namespace ArdupilotMega.GCSViews
polygonPoints.Add(startmeasure); polygonPoints.Add(startmeasure);
polygonPoints.Add(start); polygonPoints.Add(start);
GMapPolygon line = new GMapPolygon(polygonPoints,"measure dist"); GMapPolygon line = new GMapPolygon(polygonPoints, "measure dist");
line.Stroke.Color = Color.Green; line.Stroke.Color = Color.Green;
polygons.Polygons.Add(line); polygons.Polygons.Add(line);
polygons.Markers.Add(new GMapMarkerGoogleRed(start)); polygons.Markers.Add(new GMapMarkerGoogleRed(start));
MainMap.Invalidate(); MainMap.Invalidate();
MessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start),true) + " AZ: " + (MainMap.Manager.GetBearing(startmeasure, start).ToString("0"))); MessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start), true) + " AZ: " + (MainMap.Manager.GetBearing(startmeasure, start).ToString("0")));
polygons.Polygons.Remove(line); polygons.Polygons.Remove(line);
polygons.Markers.Clear(); polygons.Markers.Clear();
startmeasure = new PointLatLng(); startmeasure = new PointLatLng();
@ -2459,9 +2541,10 @@ namespace ArdupilotMega.GCSViews
private void rotateMapToolStripMenuItem_Click(object sender, EventArgs e) private void rotateMapToolStripMenuItem_Click(object sender, EventArgs e)
{ {
string heading = "0"; string heading = "0";
Common.InputBox("Rotate map to heading","Enter new UP heading",ref heading); Common.InputBox("Rotate map to heading", "Enter new UP heading", ref heading);
float ans = 0; float ans = 0;
if (float.TryParse(heading,out ans)) { if (float.TryParse(heading, out ans))
{
MainMap.Bearing = ans; MainMap.Bearing = ans;
} }
} }
@ -2475,14 +2558,14 @@ namespace ArdupilotMega.GCSViews
polygongridmode = true; polygongridmode = true;
List < PointLatLng > polygonPoints = new List<PointLatLng>(); List<PointLatLng> polygonPoints = new List<PointLatLng>();
if (drawnpolygons.Polygons.Count == 0) if (drawnpolygons.Polygons.Count == 0)
{ {
drawnpolygon = new GMapPolygon(polygonPoints, "drawnpoly"); drawnpolygon = new GMapPolygon(polygonPoints, "drawnpoly");
drawnpolygon.Stroke = new Pen(Color.Red,2); drawnpolygon.Stroke = new Pen(Color.Red, 2);
drawnpolygons.Polygons.Add(drawnpolygon); drawnpolygons.Polygons.Add(drawnpolygon);
} }
drawnpolygon.Points.Add(new PointLatLng(start.Lat,start.Lng)); drawnpolygon.Points.Add(new PointLatLng(start.Lat, start.Lng));
addpolygonmarkergrid(drawnpolygon.Points.Count.ToString(), start.Lng, start.Lat, 0); addpolygonmarkergrid(drawnpolygon.Points.Count.ToString(), start.Lng, start.Lat, 0);
@ -2514,7 +2597,7 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_UNLIM; Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_UNLIM;
setfromGE(end.Lat,end.Lng,(int)float.Parse(TXT_DefaultAlt.Text)); setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
} }
private void jumpstartToolStripMenuItem_Click(object sender, EventArgs e) private void jumpstartToolStripMenuItem_Click(object sender, EventArgs e)
@ -2534,7 +2617,7 @@ namespace ArdupilotMega.GCSViews
private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e) private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e)
{ {
string wp = "1"; string wp = "1";
Common.InputBox("WP No", "Jump to WP no?",ref wp); Common.InputBox("WP No", "Jump to WP no?", ref wp);
string repeat = "5"; string repeat = "5";
Common.InputBox("Jump repeat", "Number of times to Repeat", ref repeat); Common.InputBox("Jump repeat", "Number of times to Repeat", ref repeat);

File diff suppressed because it is too large Load Diff

View File

@ -112,7 +112,7 @@ namespace ArdupilotMega.HIL
double pitch_accel = (m[2] - m[3]) * 5000.0; double pitch_accel = (m[2] - m[3]) * 5000.0;
double yaw_accel = -((m[2] + m[3]) - (m[0] + m[1])) * 400.0; double yaw_accel = -((m[2] + m[3]) - (m[0] + m[1])) * 400.0;
// Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll); //Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
//# update rotational rates //# update rotational rates
roll_rate += roll_accel * delta_time.TotalSeconds; roll_rate += roll_accel * delta_time.TotalSeconds;
@ -225,12 +225,20 @@ namespace ArdupilotMega.HIL
#else #else
gps.alt = ((float)(altitude)); gps.alt = ((float)(altitude));
gps.fix_type = 3; gps.fix_type = 3;
gps.v = ((float)Math.Sqrt((velocity.X * velocity.X) + (velocity.Y * velocity.Y)));
gps.hdg = (float)(((Math.Atan2(velocity.Y, velocity.X) * rad2deg) + 360) % 360); ;
gps.lat = ((float)latitude); gps.lat = ((float)latitude);
gps.lon = ((float)longitude); gps.lon = ((float)longitude);
gps.usec = ((ulong)DateTime.Now.Ticks); gps.usec = ((ulong)DateTime.Now.Ticks);
//Random rand = new Random();
//gps.alt += (rand.Next(100) - 50) / 100.0f;
//gps.lat += (float)((rand.NextDouble() - 0.5) * 0.00005);
//gps.lon += (float)((rand.NextDouble() - 0.5) * 0.00005);
//gps.v += (float)(rand.NextDouble() - 0.5) * 1.0f;
gps.v = ((float)Math.Sqrt((velocity.X * velocity.X) + (velocity.Y * velocity.Y)));
gps.hdg = (float)(((Math.Atan2(velocity.Y, velocity.X) * rad2deg) + 360) % 360); ;
asp.airspeed = gps.v; asp.airspeed = gps.v;
#endif #endif
@ -244,7 +252,7 @@ namespace ArdupilotMega.HIL
MainV2.comPort.sendPacket(asp); MainV2.comPort.sendPacket(asp);
if (framecount % 10 == 0) if (framecount % 12 == 0)
{// 50 / 10 = 5 hz {// 50 / 10 = 5 hz
MainV2.comPort.sendPacket(gps); MainV2.comPort.sendPacket(gps);
//Console.WriteLine(DateTime.Now.Millisecond + " GPS" ); //Console.WriteLine(DateTime.Now.Millisecond + " GPS" );

View File

@ -348,16 +348,22 @@ namespace ArdupilotMega
public void sendPacket(object indata) public void sendPacket(object indata)
{ {
bool run = false;
byte a = 0; byte a = 0;
foreach (Type ty in mavstructs) foreach (Type ty in mavstructs)
{ {
if (ty == indata.GetType()) if (ty == indata.GetType())
{ {
run = true;
generatePacket(a, indata); generatePacket(a, indata);
return; return;
} }
a++; a++;
} }
if (!run)
{
Console.WriteLine("Mavlink : NOT VALID PACKET sendPacket() " + indata.GetType().ToString());
}
} }
/// <summary> /// <summary>
@ -491,7 +497,7 @@ namespace ArdupilotMega
#if MAVLINK10 #if MAVLINK10
Array.Resize(ref temp, 16); Array.Resize(ref temp, 16);
#else #else
Array.Resize(ref temp, 15); Array.Resize(ref temp, 15);
#endif #endif
req.param_id = temp; req.param_id = temp;
req.param_value = (value); req.param_value = (value);
@ -1176,7 +1182,7 @@ Array.Resize(ref temp, 15);
} }
} }
} }
#else #else
__mavlink_waypoint_request_list_t req = new __mavlink_waypoint_request_list_t(); __mavlink_waypoint_request_list_t req = new __mavlink_waypoint_request_list_t();
@ -1223,7 +1229,7 @@ Array.Resize(ref temp, 15);
} }
} }
#endif #endif
} }
/// <summary> /// <summary>
/// Gets specfied WP /// Gets specfied WP
@ -1337,30 +1343,27 @@ Array.Resize(ref temp, 15);
loc.options = (byte)(wp.frame & 0x1); loc.options = (byte)(wp.frame & 0x1);
loc.id = (byte)(wp.command); loc.id = (byte)(wp.command);
loc.p1 = (byte)(wp.param1); loc.p1 = (wp.param1);
if (loc.id < (byte)MAV_CMD.LAST) loc.p2 = (wp.param2);
{ loc.p3 = (wp.param3);
loc.alt = (int)((wp.z) * 100); loc.p4 = (wp.param4);
loc.lat = (int)((wp.x) * 10000000);
loc.lng = (int)((wp.y) * 10000000);
}
else
{
loc.alt = (int)((wp.z));
loc.lat = (int)((wp.x));
loc.lng = (int)((wp.y));
loc.alt = ((wp.z));
loc.lat = ((wp.x));
loc.lng = ((wp.y));
/*
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
switch (loc.id) switch (loc.id)
{ // Switch to map APM command fields inot MAVLink command fields { // Switch to map APM command fields inot MAVLink command fields
case (byte)MAV_CMD.LOITER_TURNS: case (byte)MAV_CMD.LOITER_TURNS:
case (byte)MAV_CMD.TAKEOFF: case (byte)MAV_CMD.TAKEOFF:
case (byte)MAV_CMD.DO_SET_HOME: case (byte)MAV_CMD.DO_SET_HOME:
//case (byte)MAV_CMD.DO_SET_ROI: //case (byte)MAV_CMD.DO_SET_ROI:
loc.alt = (int)((wp.z) * 100); loc.alt = (float)((wp.z));
loc.lat = (int)((wp.x) * 10000000); loc.lat = (float)((wp.x));
loc.lng = (int)((wp.y) * 10000000); loc.lng = (float)((wp.y));
loc.p1 = (byte)wp.param1; loc.p1 = (float)wp.param1;
break; break;
case (byte)MAV_CMD.CONDITION_CHANGE_ALT: case (byte)MAV_CMD.CONDITION_CHANGE_ALT:
@ -1411,7 +1414,7 @@ Array.Resize(ref temp, 15);
break; break;
} }
} }
*/
Console.WriteLine("getWP {0} {1} {2} {3} {4} opt {5}", loc.id, loc.p1, loc.alt, loc.lat, loc.lng, loc.options); Console.WriteLine("getWP {0} {1} {2} {3} {4} opt {5}", loc.id, loc.p1, loc.alt, loc.lat, loc.lng, loc.options);
break; break;
@ -1632,11 +1635,11 @@ Array.Resize(ref temp, 15);
public void setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current) public void setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current)
{ {
MainV2.givecomport = true; MainV2.givecomport = true;
#if MAVLINK10 #if MAVLINK10
__mavlink_mission_item_t req = new __mavlink_mission_item_t(); __mavlink_mission_item_t req = new __mavlink_mission_item_t();
#else #else
__mavlink_waypoint_t req = new __mavlink_waypoint_t(); __mavlink_waypoint_t req = new __mavlink_waypoint_t();
#endif #endif
req.target_system = sysid; req.target_system = sysid;
req.target_component = compid; // MAVLINK_MSG_ID_MISSION_ITEM req.target_component = compid; // MAVLINK_MSG_ID_MISSION_ITEM
@ -1646,20 +1649,18 @@ Array.Resize(ref temp, 15);
req.current = current; req.current = current;
if (loc.id < (byte)MAV_CMD.LAST)
{
req.frame = (byte)frame; req.frame = (byte)frame;
req.y = (float)(loc.lng / 10000000.0);
req.x = (float)(loc.lat / 10000000.0);
req.z = (float)(loc.alt / 100.0);
}
else
{
req.frame = (byte)MAVLink.MAV_FRAME.MAV_FRAME_MISSION; // mission
req.y = (float)(loc.lng); req.y = (float)(loc.lng);
req.x = (float)(loc.lat); req.x = (float)(loc.lat);
req.z = (float)(loc.alt); req.z = (float)(loc.alt);
req.param1 = loc.p1;
req.param2 = loc.p2;
req.param3 = loc.p3;
req.param4 = loc.p4;
/*
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
switch (loc.id) switch (loc.id)
{ // Switch to map APM command fields inot MAVLink command fields { // Switch to map APM command fields inot MAVLink command fields
case (byte)MAV_CMD.LOITER_TURNS: case (byte)MAV_CMD.LOITER_TURNS:
@ -1667,9 +1668,6 @@ Array.Resize(ref temp, 15);
req.param1 = loc.p1; req.param1 = loc.p1;
break; break;
case (byte)MAV_CMD.DO_SET_HOME: case (byte)MAV_CMD.DO_SET_HOME:
req.y = (float)(loc.lng / 10000000.0);
req.x = (float)(loc.lat / 10000000.0);
req.z = (float)(loc.alt / 100.0);
req.param1 = loc.p1; req.param1 = loc.p1;
break; break;
@ -1711,16 +1709,17 @@ Array.Resize(ref temp, 15);
break; break;
} }
} }
*/
req.seq = index; req.seq = index;
Console.WriteLine("setWP {6} frame {0} cmd {1} p1 {2} x {3} y {4} z {5}", req.frame, req.command, req.param1, req.x, req.y, req.z, index); Console.WriteLine("setWP {6} frame {0} cmd {1} p1 {2} x {3} y {4} z {5}", req.frame, req.command, req.param1, req.x, req.y, req.z, index);
// request // request
#if MAVLINK10 #if MAVLINK10
generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req); generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req);
#else #else
generatePacket(MAVLINK_MSG_ID_WAYPOINT, req); generatePacket(MAVLINK_MSG_ID_WAYPOINT, req);
#endif #endif
DateTime start = DateTime.Now; DateTime start = DateTime.Now;
int retrys = 6; int retrys = 6;
@ -1732,11 +1731,11 @@ Array.Resize(ref temp, 15);
if (retrys > 0) if (retrys > 0)
{ {
Console.WriteLine("setWP Retry " + retrys); Console.WriteLine("setWP Retry " + retrys);
#if MAVLINK10 #if MAVLINK10
generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req); generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req);
#else #else
generatePacket(MAVLINK_MSG_ID_WAYPOINT, req); generatePacket(MAVLINK_MSG_ID_WAYPOINT, req);
#endif #endif
start = DateTime.Now; start = DateTime.Now;
retrys--; retrys--;
continue; continue;
@ -1747,7 +1746,7 @@ Array.Resize(ref temp, 15);
byte[] buffer = readPacket(); byte[] buffer = readPacket();
if (buffer.Length > 5) if (buffer.Length > 5)
{ {
#if MAVLINK10 #if MAVLINK10
if (buffer[5] == MAVLINK_MSG_ID_MISSION_ACK) if (buffer[5] == MAVLINK_MSG_ID_MISSION_ACK)
{ {
__mavlink_mission_ack_t ans = new __mavlink_mission_ack_t(); __mavlink_mission_ack_t ans = new __mavlink_mission_ack_t();
@ -1787,7 +1786,7 @@ Array.Resize(ref temp, 15);
{ {
//Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]); //Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]);
} }
#else #else
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK) if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK)
{ //__mavlink_waypoint_request_t { //__mavlink_waypoint_request_t
Console.WriteLine("set wp " + index + " ACK 47 : " + buffer[5]); Console.WriteLine("set wp " + index + " ACK 47 : " + buffer[5]);
@ -1821,7 +1820,7 @@ Array.Resize(ref temp, 15);
{ {
//Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]); //Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]);
} }
#endif #endif
} }
} }
} }

View File

@ -305,20 +305,6 @@ namespace ArdupilotMega
}; };
public const byte MAVLINK_MSG_ID_ATTITUDE_NEW = 30;
[StructLayout(LayoutKind.Sequential,Pack=1)]
public struct __mavlink_attitude_new_t
{
public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
public float roll; /// Roll angle (rad)
public float pitch; /// Pitch angle (rad)
public float yaw; /// Yaw angle (rad)
public float rollspeed; /// Roll angular speed (rad/s)
public float pitchspeed; /// Pitch angular speed (rad/s)
public float yawspeed; /// Yaw angular speed (rad/s)
};
public const byte MAVLINK_MSG_ID_AUTH_KEY = 7; public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
[StructLayout(LayoutKind.Sequential,Pack=1)] [StructLayout(LayoutKind.Sequential,Pack=1)]
public struct __mavlink_auth_key_t public struct __mavlink_auth_key_t
@ -1486,7 +1472,7 @@ namespace ArdupilotMega
MAV_FRAME_LOCAL_ENU = 4 MAV_FRAME_LOCAL_ENU = 4
}; };
Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_new_t ) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_waypoint_set_global_reference_t ) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,typeof( __mavlink_attitude_controller_output_t ) ,typeof( __mavlink_position_controller_output_t ) ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_request_dynamic_gyro_calibration_t ) ,typeof( __mavlink_request_static_calibration_t ) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,}; Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t ) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_waypoint_set_global_reference_t ) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,typeof( __mavlink_attitude_controller_output_t ) ,typeof( __mavlink_position_controller_output_t ) ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_request_dynamic_gyro_calibration_t ) ,typeof( __mavlink_request_static_calibration_t ) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
} }
#endif #endif

View File

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

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below: // by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")] // [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")] [assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.0.90")] [assembly: AssemblyFileVersion("1.0.94")]
[assembly: NeutralResourcesLanguageAttribute("")] [assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -113,18 +113,42 @@
this.pictureBoxQuad = new System.Windows.Forms.PictureBox(); this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
this.BUT_levelac2 = new ArdupilotMega.MyButton(); this.BUT_levelac2 = new ArdupilotMega.MyButton();
this.tabHeli = new System.Windows.Forms.TabPage(); this.tabHeli = new System.Windows.Forms.TabPage();
this.label27 = new System.Windows.Forms.Label(); this.groupBox3 = new System.Windows.Forms.GroupBox();
this.GYR_GAIN_ = new System.Windows.Forms.TextBox(); this.label46 = new System.Windows.Forms.Label();
this.label45 = new System.Windows.Forms.Label();
this.GYR_ENABLE_ = new System.Windows.Forms.CheckBox(); this.GYR_ENABLE_ = new System.Windows.Forms.CheckBox();
this.GYR_GAIN_ = new System.Windows.Forms.TextBox();
this.label44 = new System.Windows.Forms.Label();
this.label43 = new System.Windows.Forms.Label();
this.label42 = new System.Windows.Forms.Label();
this.BUT_HS4save = new ArdupilotMega.MyButton();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.label24 = new System.Windows.Forms.Label();
this.HS4_MIN = new System.Windows.Forms.TextBox();
this.HS4_MAX = new System.Windows.Forms.TextBox();
this.label40 = new System.Windows.Forms.Label();
this.BUT_swash_manual = new ArdupilotMega.MyButton();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.label41 = new System.Windows.Forms.Label();
this.label21 = new System.Windows.Forms.Label();
this.COL_MIN_ = new System.Windows.Forms.TextBox();
this.COL_MID_ = new System.Windows.Forms.TextBox();
this.COL_MAX_ = new System.Windows.Forms.TextBox();
this.BUT_0collective = new ArdupilotMega.MyButton();
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
this.HS1_TRIM = new System.Windows.Forms.NumericUpDown();
this.label39 = new System.Windows.Forms.Label();
this.label38 = new System.Windows.Forms.Label();
this.label37 = new System.Windows.Forms.Label();
this.label36 = new System.Windows.Forms.Label();
this.label26 = new System.Windows.Forms.Label(); this.label26 = new System.Windows.Forms.Label();
this.PIT_MAX_ = new System.Windows.Forms.TextBox(); this.PIT_MAX_ = new System.Windows.Forms.TextBox();
this.label25 = new System.Windows.Forms.Label(); this.label25 = new System.Windows.Forms.Label();
this.ROL_MAX_ = new System.Windows.Forms.TextBox(); this.ROL_MAX_ = new System.Windows.Forms.TextBox();
this.label24 = new System.Windows.Forms.Label();
this.COL_MID_ = new System.Windows.Forms.Label();
this.label23 = new System.Windows.Forms.Label(); this.label23 = new System.Windows.Forms.Label();
this.label22 = new System.Windows.Forms.Label(); this.label22 = new System.Windows.Forms.Label();
this.label21 = new System.Windows.Forms.Label();
this.HS4_REV = new System.Windows.Forms.CheckBox(); this.HS4_REV = new System.Windows.Forms.CheckBox();
this.label20 = new System.Windows.Forms.Label(); this.label20 = new System.Windows.Forms.Label();
this.label19 = new System.Windows.Forms.Label(); this.label19 = new System.Windows.Forms.Label();
@ -136,14 +160,8 @@
this.HS2_REV = new System.Windows.Forms.CheckBox(); this.HS2_REV = new System.Windows.Forms.CheckBox();
this.HS1_REV = new System.Windows.Forms.CheckBox(); this.HS1_REV = new System.Windows.Forms.CheckBox();
this.label17 = new System.Windows.Forms.Label(); this.label17 = new System.Windows.Forms.Label();
this.BUT_saveheliconfig = new ArdupilotMega.MyButton(); this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
this.BUT_0collective = new ArdupilotMega.MyButton();
this.HS4 = new ArdupilotMega.VerticalProgressBar2();
this.HS3 = new ArdupilotMega.VerticalProgressBar2(); this.HS3 = new ArdupilotMega.VerticalProgressBar2();
this.HS4_TRIM = new ArdupilotMega.MyTrackBar();
this.HS3_TRIM = new ArdupilotMega.MyTrackBar();
this.HS2_TRIM = new ArdupilotMega.MyTrackBar();
this.HS1_TRIM = new ArdupilotMega.MyTrackBar();
this.Gservoloc = new AGaugeApp.AGauge(); this.Gservoloc = new AGaugeApp.AGauge();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.tabControl1.SuspendLayout(); this.tabControl1.SuspendLayout();
@ -161,6 +179,9 @@
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
this.tabHeli.SuspendLayout(); this.tabHeli.SuspendLayout();
this.groupBox3.SuspendLayout();
this.groupBox2.SuspendLayout();
this.groupBox1.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
@ -849,18 +870,28 @@
// //
// tabHeli // tabHeli
// //
this.tabHeli.Controls.Add(this.label27); this.tabHeli.Controls.Add(this.groupBox3);
this.tabHeli.Controls.Add(this.GYR_GAIN_); this.tabHeli.Controls.Add(this.label44);
this.tabHeli.Controls.Add(this.GYR_ENABLE_); this.tabHeli.Controls.Add(this.label43);
this.tabHeli.Controls.Add(this.label42);
this.tabHeli.Controls.Add(this.BUT_HS4save);
this.tabHeli.Controls.Add(this.groupBox2);
this.tabHeli.Controls.Add(this.BUT_swash_manual);
this.tabHeli.Controls.Add(this.groupBox1);
this.tabHeli.Controls.Add(this.HS4_TRIM);
this.tabHeli.Controls.Add(this.HS3_TRIM);
this.tabHeli.Controls.Add(this.HS2_TRIM);
this.tabHeli.Controls.Add(this.HS1_TRIM);
this.tabHeli.Controls.Add(this.label39);
this.tabHeli.Controls.Add(this.label38);
this.tabHeli.Controls.Add(this.label37);
this.tabHeli.Controls.Add(this.label36);
this.tabHeli.Controls.Add(this.label26); this.tabHeli.Controls.Add(this.label26);
this.tabHeli.Controls.Add(this.PIT_MAX_); this.tabHeli.Controls.Add(this.PIT_MAX_);
this.tabHeli.Controls.Add(this.label25); this.tabHeli.Controls.Add(this.label25);
this.tabHeli.Controls.Add(this.ROL_MAX_); this.tabHeli.Controls.Add(this.ROL_MAX_);
this.tabHeli.Controls.Add(this.label24);
this.tabHeli.Controls.Add(this.COL_MID_);
this.tabHeli.Controls.Add(this.label23); this.tabHeli.Controls.Add(this.label23);
this.tabHeli.Controls.Add(this.label22); this.tabHeli.Controls.Add(this.label22);
this.tabHeli.Controls.Add(this.label21);
this.tabHeli.Controls.Add(this.HS4_REV); this.tabHeli.Controls.Add(this.HS4_REV);
this.tabHeli.Controls.Add(this.label20); this.tabHeli.Controls.Add(this.label20);
this.tabHeli.Controls.Add(this.label19); this.tabHeli.Controls.Add(this.label19);
@ -872,29 +903,33 @@
this.tabHeli.Controls.Add(this.HS2_REV); this.tabHeli.Controls.Add(this.HS2_REV);
this.tabHeli.Controls.Add(this.HS1_REV); this.tabHeli.Controls.Add(this.HS1_REV);
this.tabHeli.Controls.Add(this.label17); this.tabHeli.Controls.Add(this.label17);
this.tabHeli.Controls.Add(this.BUT_saveheliconfig);
this.tabHeli.Controls.Add(this.BUT_0collective);
this.tabHeli.Controls.Add(this.HS4); this.tabHeli.Controls.Add(this.HS4);
this.tabHeli.Controls.Add(this.HS3); this.tabHeli.Controls.Add(this.HS3);
this.tabHeli.Controls.Add(this.HS4_TRIM);
this.tabHeli.Controls.Add(this.HS3_TRIM);
this.tabHeli.Controls.Add(this.HS2_TRIM);
this.tabHeli.Controls.Add(this.HS1_TRIM);
this.tabHeli.Controls.Add(this.Gservoloc); this.tabHeli.Controls.Add(this.Gservoloc);
resources.ApplyResources(this.tabHeli, "tabHeli"); resources.ApplyResources(this.tabHeli, "tabHeli");
this.tabHeli.Name = "tabHeli"; this.tabHeli.Name = "tabHeli";
this.tabHeli.UseVisualStyleBackColor = true; this.tabHeli.UseVisualStyleBackColor = true;
this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click);
// //
// label27 // groupBox3
// //
resources.ApplyResources(this.label27, "label27"); this.groupBox3.Controls.Add(this.label46);
this.label27.Name = "label27"; this.groupBox3.Controls.Add(this.label45);
this.groupBox3.Controls.Add(this.GYR_ENABLE_);
this.groupBox3.Controls.Add(this.GYR_GAIN_);
resources.ApplyResources(this.groupBox3, "groupBox3");
this.groupBox3.Name = "groupBox3";
this.groupBox3.TabStop = false;
// //
// GYR_GAIN_ // label46
// //
resources.ApplyResources(this.GYR_GAIN_, "GYR_GAIN_"); resources.ApplyResources(this.label46, "label46");
this.GYR_GAIN_.Name = "GYR_GAIN_"; this.label46.Name = "label46";
this.GYR_GAIN_.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); //
// label45
//
resources.ApplyResources(this.label45, "label45");
this.label45.Name = "label45";
// //
// GYR_ENABLE_ // GYR_ENABLE_
// //
@ -903,6 +938,232 @@
this.GYR_ENABLE_.UseVisualStyleBackColor = true; this.GYR_ENABLE_.UseVisualStyleBackColor = true;
this.GYR_ENABLE_.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged); this.GYR_ENABLE_.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
// //
// GYR_GAIN_
//
resources.ApplyResources(this.GYR_GAIN_, "GYR_GAIN_");
this.GYR_GAIN_.Name = "GYR_GAIN_";
this.GYR_GAIN_.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
//
// label44
//
resources.ApplyResources(this.label44, "label44");
this.label44.Name = "label44";
//
// label43
//
resources.ApplyResources(this.label43, "label43");
this.label43.Name = "label43";
//
// label42
//
resources.ApplyResources(this.label42, "label42");
this.label42.Name = "label42";
//
// BUT_HS4save
//
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
this.BUT_HS4save.Name = "BUT_HS4save";
this.BUT_HS4save.UseVisualStyleBackColor = true;
this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
//
// groupBox2
//
this.groupBox2.Controls.Add(this.label24);
this.groupBox2.Controls.Add(this.HS4_MIN);
this.groupBox2.Controls.Add(this.HS4_MAX);
this.groupBox2.Controls.Add(this.label40);
resources.ApplyResources(this.groupBox2, "groupBox2");
this.groupBox2.Name = "groupBox2";
this.groupBox2.TabStop = false;
//
// label24
//
resources.ApplyResources(this.label24, "label24");
this.label24.Name = "label24";
//
// HS4_MIN
//
resources.ApplyResources(this.HS4_MIN, "HS4_MIN");
this.HS4_MIN.Name = "HS4_MIN";
this.HS4_MIN.Enter += new System.EventHandler(this.HS4_MIN_Enter);
this.HS4_MIN.Leave += new System.EventHandler(this.HS4_MIN_Leave);
this.HS4_MIN.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// HS4_MAX
//
resources.ApplyResources(this.HS4_MAX, "HS4_MAX");
this.HS4_MAX.Name = "HS4_MAX";
this.HS4_MAX.Enter += new System.EventHandler(this.HS4_MAX_Enter);
this.HS4_MAX.Leave += new System.EventHandler(this.HS4_MAX_Leave);
this.HS4_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// label40
//
resources.ApplyResources(this.label40, "label40");
this.label40.Name = "label40";
//
// BUT_swash_manual
//
resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
this.BUT_swash_manual.Name = "BUT_swash_manual";
this.BUT_swash_manual.UseVisualStyleBackColor = true;
this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
//
// groupBox1
//
this.groupBox1.Controls.Add(this.label41);
this.groupBox1.Controls.Add(this.label21);
this.groupBox1.Controls.Add(this.COL_MIN_);
this.groupBox1.Controls.Add(this.COL_MID_);
this.groupBox1.Controls.Add(this.COL_MAX_);
this.groupBox1.Controls.Add(this.BUT_0collective);
resources.ApplyResources(this.groupBox1, "groupBox1");
this.groupBox1.Name = "groupBox1";
this.groupBox1.TabStop = false;
//
// label41
//
resources.ApplyResources(this.label41, "label41");
this.label41.Name = "label41";
//
// label21
//
resources.ApplyResources(this.label21, "label21");
this.label21.Name = "label21";
//
// COL_MIN_
//
resources.ApplyResources(this.COL_MIN_, "COL_MIN_");
this.COL_MIN_.Name = "COL_MIN_";
this.COL_MIN_.Enter += new System.EventHandler(this.COL_MIN__Enter);
this.COL_MIN_.Leave += new System.EventHandler(this.COL_MIN__Leave);
this.COL_MIN_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// COL_MID_
//
resources.ApplyResources(this.COL_MID_, "COL_MID_");
this.COL_MID_.Name = "COL_MID_";
this.COL_MID_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// COL_MAX_
//
resources.ApplyResources(this.COL_MAX_, "COL_MAX_");
this.COL_MAX_.Name = "COL_MAX_";
this.COL_MAX_.Enter += new System.EventHandler(this.COL_MAX__Enter);
this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave);
this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// BUT_0collective
//
resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
this.BUT_0collective.Name = "BUT_0collective";
this.BUT_0collective.UseVisualStyleBackColor = true;
this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
//
// HS4_TRIM
//
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
this.HS4_TRIM.Maximum = new decimal(new int[] {
2000,
0,
0,
0});
this.HS4_TRIM.Minimum = new decimal(new int[] {
1000,
0,
0,
0});
this.HS4_TRIM.Name = "HS4_TRIM";
this.HS4_TRIM.Value = new decimal(new int[] {
1500,
0,
0,
0});
this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged);
//
// HS3_TRIM
//
resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM");
this.HS3_TRIM.Maximum = new decimal(new int[] {
2000,
0,
0,
0});
this.HS3_TRIM.Minimum = new decimal(new int[] {
1000,
0,
0,
0});
this.HS3_TRIM.Name = "HS3_TRIM";
this.HS3_TRIM.Value = new decimal(new int[] {
1500,
0,
0,
0});
this.HS3_TRIM.ValueChanged += new System.EventHandler(this.HS3_TRIM_ValueChanged);
//
// HS2_TRIM
//
resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM");
this.HS2_TRIM.Maximum = new decimal(new int[] {
2000,
0,
0,
0});
this.HS2_TRIM.Minimum = new decimal(new int[] {
1000,
0,
0,
0});
this.HS2_TRIM.Name = "HS2_TRIM";
this.HS2_TRIM.Value = new decimal(new int[] {
1500,
0,
0,
0});
this.HS2_TRIM.ValueChanged += new System.EventHandler(this.HS2_TRIM_ValueChanged);
//
// HS1_TRIM
//
resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM");
this.HS1_TRIM.Maximum = new decimal(new int[] {
2000,
0,
0,
0});
this.HS1_TRIM.Minimum = new decimal(new int[] {
1000,
0,
0,
0});
this.HS1_TRIM.Name = "HS1_TRIM";
this.HS1_TRIM.Value = new decimal(new int[] {
1500,
0,
0,
0});
this.HS1_TRIM.ValueChanged += new System.EventHandler(this.HS1_TRIM_ValueChanged);
//
// label39
//
resources.ApplyResources(this.label39, "label39");
this.label39.Name = "label39";
//
// label38
//
resources.ApplyResources(this.label38, "label38");
this.label38.Name = "label38";
//
// label37
//
resources.ApplyResources(this.label37, "label37");
this.label37.Name = "label37";
//
// label36
//
resources.ApplyResources(this.label36, "label36");
this.label36.Name = "label36";
//
// label26 // label26
// //
resources.ApplyResources(this.label26, "label26"); resources.ApplyResources(this.label26, "label26");
@ -925,16 +1186,6 @@
this.ROL_MAX_.Name = "ROL_MAX_"; this.ROL_MAX_.Name = "ROL_MAX_";
this.ROL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); this.ROL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
// //
// label24
//
resources.ApplyResources(this.label24, "label24");
this.label24.Name = "label24";
//
// COL_MID_
//
resources.ApplyResources(this.COL_MID_, "COL_MID_");
this.COL_MID_.Name = "COL_MID_";
//
// label23 // label23
// //
resources.ApplyResources(this.label23, "label23"); resources.ApplyResources(this.label23, "label23");
@ -945,11 +1196,6 @@
resources.ApplyResources(this.label22, "label22"); resources.ApplyResources(this.label22, "label22");
this.label22.Name = "label22"; this.label22.Name = "label22";
// //
// label21
//
resources.ApplyResources(this.label21, "label21");
this.label21.Name = "label21";
//
// HS4_REV // HS4_REV
// //
resources.ApplyResources(this.HS4_REV, "HS4_REV"); resources.ApplyResources(this.HS4_REV, "HS4_REV");
@ -1016,20 +1262,6 @@
resources.ApplyResources(this.label17, "label17"); resources.ApplyResources(this.label17, "label17");
this.label17.Name = "label17"; this.label17.Name = "label17";
// //
// BUT_saveheliconfig
//
resources.ApplyResources(this.BUT_saveheliconfig, "BUT_saveheliconfig");
this.BUT_saveheliconfig.Name = "BUT_saveheliconfig";
this.BUT_saveheliconfig.UseVisualStyleBackColor = true;
this.BUT_saveheliconfig.Click += new System.EventHandler(this.BUT_saveheliconfig_Click);
//
// BUT_0collective
//
resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
this.BUT_0collective.Name = "BUT_0collective";
this.BUT_0collective.UseVisualStyleBackColor = true;
this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
//
// HS4 // HS4
// //
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
@ -1044,6 +1276,7 @@
this.HS4.Name = "HS4"; this.HS4.Name = "HS4";
this.HS4.Value = 1500; this.HS4.Value = 1500;
this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
this.HS4.Paint += new System.Windows.Forms.PaintEventHandler(this.HS4_Paint);
// //
// HS3 // HS3
// //
@ -1059,54 +1292,7 @@
this.HS3.Name = "HS3"; this.HS3.Name = "HS3";
this.HS3.Value = 1500; this.HS3.Value = 1500;
this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
// this.HS3.Paint += new System.Windows.Forms.PaintEventHandler(this.HS3_Paint);
// HS4_TRIM
//
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
this.HS4_TRIM.LargeChange = 1000;
this.HS4_TRIM.Maximum = 2000D;
this.HS4_TRIM.Minimum = 1000D;
this.HS4_TRIM.Name = "HS4_TRIM";
this.HS4_TRIM.SmallChange = 1000;
this.HS4_TRIM.TickFrequency = 2000;
this.HS4_TRIM.Value = 1500D;
this.HS4_TRIM.Scroll += new System.EventHandler(this.HS4_TRIM_Scroll);
//
// HS3_TRIM
//
resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM");
this.HS3_TRIM.LargeChange = 1000;
this.HS3_TRIM.Maximum = 2000D;
this.HS3_TRIM.Minimum = 1000D;
this.HS3_TRIM.Name = "HS3_TRIM";
this.HS3_TRIM.SmallChange = 1000;
this.HS3_TRIM.TickFrequency = 2000;
this.HS3_TRIM.Value = 1500D;
this.HS3_TRIM.Scroll += new System.EventHandler(this.HS3_TRIM_Scroll);
//
// HS2_TRIM
//
resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM");
this.HS2_TRIM.LargeChange = 1000;
this.HS2_TRIM.Maximum = 2000D;
this.HS2_TRIM.Minimum = 1000D;
this.HS2_TRIM.Name = "HS2_TRIM";
this.HS2_TRIM.SmallChange = 1000;
this.HS2_TRIM.TickFrequency = 2000;
this.HS2_TRIM.Value = 1500D;
this.HS2_TRIM.Scroll += new System.EventHandler(this.HS2_TRIM_Scroll);
//
// HS1_TRIM
//
resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM");
this.HS1_TRIM.LargeChange = 1000;
this.HS1_TRIM.Maximum = 2000D;
this.HS1_TRIM.Minimum = 1000D;
this.HS1_TRIM.Name = "HS1_TRIM";
this.HS1_TRIM.SmallChange = 1000;
this.HS1_TRIM.TickFrequency = 2000;
this.HS1_TRIM.Value = 1500D;
this.HS1_TRIM.Scroll += new System.EventHandler(this.HS1_TRIM_Scroll);
// //
// Gservoloc // Gservoloc
// //
@ -1280,6 +1466,12 @@
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
this.tabHeli.ResumeLayout(false); this.tabHeli.ResumeLayout(false);
this.tabHeli.PerformLayout(); this.tabHeli.PerformLayout();
this.groupBox3.ResumeLayout(false);
this.groupBox3.PerformLayout();
this.groupBox2.ResumeLayout(false);
this.groupBox2.PerformLayout();
this.groupBox1.ResumeLayout(false);
this.groupBox1.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
@ -1355,26 +1547,17 @@
private System.Windows.Forms.TextBox SV2_POS_; private System.Windows.Forms.TextBox SV2_POS_;
private System.Windows.Forms.TextBox SV1_POS_; private System.Windows.Forms.TextBox SV1_POS_;
private System.Windows.Forms.CheckBox HS4_REV; private System.Windows.Forms.CheckBox HS4_REV;
private System.Windows.Forms.Label label21;
private System.Windows.Forms.Label label22; private System.Windows.Forms.Label label22;
private MyTrackBar HS1_TRIM;
private MyTrackBar HS4_TRIM;
private MyTrackBar HS3_TRIM;
private MyTrackBar HS2_TRIM;
private System.Windows.Forms.Label label23; private System.Windows.Forms.Label label23;
private VerticalProgressBar2 HS4; private HorizontalProgressBar2 HS4;
private VerticalProgressBar2 HS3; private VerticalProgressBar2 HS3;
private MyButton BUT_0collective; private MyButton BUT_0collective;
private MyButton BUT_saveheliconfig;
private System.Windows.Forms.Label label24;
private System.Windows.Forms.Label COL_MID_;
private System.Windows.Forms.Label label25; private System.Windows.Forms.Label label25;
private System.Windows.Forms.TextBox ROL_MAX_; private System.Windows.Forms.TextBox ROL_MAX_;
private System.Windows.Forms.Label label26; private System.Windows.Forms.Label label26;
private System.Windows.Forms.TextBox PIT_MAX_; private System.Windows.Forms.TextBox PIT_MAX_;
private System.Windows.Forms.TextBox GYR_GAIN_; private System.Windows.Forms.TextBox GYR_GAIN_;
private System.Windows.Forms.CheckBox GYR_ENABLE_; private System.Windows.Forms.CheckBox GYR_ENABLE_;
private System.Windows.Forms.Label label27;
private System.Windows.Forms.Label label28; private System.Windows.Forms.Label label28;
private MyButton BUT_levelac2; private MyButton BUT_levelac2;
private System.Windows.Forms.ToolTip toolTip1; private System.Windows.Forms.ToolTip toolTip1;
@ -1406,6 +1589,33 @@
private System.Windows.Forms.Label label34; private System.Windows.Forms.Label label34;
private System.Windows.Forms.Label label33; private System.Windows.Forms.Label label33;
private System.Windows.Forms.Label label32; private System.Windows.Forms.Label label32;
private System.Windows.Forms.NumericUpDown HS1_TRIM;
private System.Windows.Forms.Label label39;
private System.Windows.Forms.Label label38;
private System.Windows.Forms.Label label37;
private System.Windows.Forms.Label label36;
private System.Windows.Forms.NumericUpDown HS3_TRIM;
private System.Windows.Forms.NumericUpDown HS2_TRIM;
private System.Windows.Forms.NumericUpDown HS4_TRIM;
private System.Windows.Forms.GroupBox groupBox1;
private MyButton BUT_swash_manual;
private System.Windows.Forms.TextBox COL_MIN_;
private System.Windows.Forms.TextBox COL_MID_;
private System.Windows.Forms.TextBox COL_MAX_;
private System.Windows.Forms.Label label41;
private System.Windows.Forms.Label label21;
private MyButton BUT_HS4save;
private System.Windows.Forms.GroupBox groupBox2;
private System.Windows.Forms.Label label24;
private System.Windows.Forms.TextBox HS4_MIN;
private System.Windows.Forms.TextBox HS4_MAX;
private System.Windows.Forms.Label label40;
private System.Windows.Forms.Label label42;
private System.Windows.Forms.Label label44;
private System.Windows.Forms.Label label43;
private System.Windows.Forms.GroupBox groupBox3;
private System.Windows.Forms.Label label46;
private System.Windows.Forms.Label label45;
} }
} }

View File

@ -15,6 +15,8 @@ namespace ArdupilotMega.Setup
bool run = false; bool run = false;
bool startup = false; bool startup = false;
bool inpwmdetect = false;
const float rad2deg = (float)(180 / Math.PI); const float rad2deg = (float)(180 / Math.PI);
const float deg2rad = (float)(1.0 / rad2deg); const float deg2rad = (float)(1.0 / rad2deg);
@ -73,6 +75,9 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabHeli) if (tabControl1.SelectedTab == tabHeli)
{ {
if (MainV2.comPort.param["HSV_MAN"].ToString() == "0")
return;
if (HS3.minline == 0) if (HS3.minline == 0)
HS3.minline = 2200; HS3.minline = 2200;
@ -84,6 +89,23 @@ namespace ArdupilotMega.Setup
HS4.minline = Math.Min(HS4.minline, (int)MainV2.cs.ch4in); HS4.minline = Math.Min(HS4.minline, (int)MainV2.cs.ch4in);
HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.cs.ch4in); HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.cs.ch4in);
if (!inpwmdetect)
{
HS3_Paint(null, null);
HS4_Paint(null, null);
}
else
{
try
{
HS3.minline = int.Parse(COL_MIN_.Text);
HS3.maxline = int.Parse(COL_MAX_.Text);
HS4.maxline = int.Parse(HS4_MIN.Text);
HS4.minline = int.Parse(HS4_MAX.Text);
}
catch { }
}
} }
} }
@ -442,6 +464,12 @@ namespace ArdupilotMega.Setup
} }
} }
} }
HS1_REV.Checked = MainV2.comPort.param["HS1_REV"].ToString() == "-1";
HS2_REV.Checked = MainV2.comPort.param["HS2_REV"].ToString() == "-1";
HS3_REV.Checked = MainV2.comPort.param["HS3_REV"].ToString() == "-1";
HS4_REV.Checked = MainV2.comPort.param["HS4_REV"].ToString() == "-1";
} }
catch { } catch { }
startup = false; startup = false;
@ -848,7 +876,10 @@ namespace ArdupilotMega.Setup
try try
{ {
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test); MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
} }
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); } catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
@ -868,7 +899,10 @@ namespace ArdupilotMega.Setup
try try
{ {
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test); MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
} }
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); } catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
} }
@ -887,7 +921,10 @@ namespace ArdupilotMega.Setup
try try
{ {
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test); MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
} }
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); } catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
} }
@ -910,56 +947,57 @@ namespace ArdupilotMega.Setup
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f); MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
} }
private void HS2_REV_CheckedChanged(object sender, EventArgs e) private void HS2_REV_CheckedChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f); MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
} }
private void HS3_REV_CheckedChanged(object sender, EventArgs e) private void HS3_REV_CheckedChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f); MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
} }
private void HS4_REV_CheckedChanged(object sender, EventArgs e) private void HS4_REV_CheckedChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f); MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
HS4.reverse = !HS4.reverse;
} }
private void HS1_TRIM_Scroll(object sender, EventArgs e) private void HS1_TRIM_ValueChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((MyTrackBar)sender).Name, (float)((MyTrackBar)sender).Value); MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
} }
private void HS2_TRIM_Scroll(object sender, EventArgs e) private void HS2_TRIM_ValueChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((MyTrackBar)sender).Name, (float)((MyTrackBar)sender).Value); MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
} }
private void HS3_TRIM_Scroll(object sender, EventArgs e) private void HS3_TRIM_ValueChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((MyTrackBar)sender).Name, (float)((MyTrackBar)sender).Value); MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
} }
private void HS4_TRIM_Scroll(object sender, EventArgs e) private void HS4_TRIM_ValueChanged(object sender, EventArgs e)
{ {
if (startup) if (startup)
return; return;
MainV2.comPort.setParam(((MyTrackBar)sender).Name, (float)((MyTrackBar)sender).Value); MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
} }
private void ROL_MAX__Validating(object sender, CancelEventArgs e) private void ROL_MAX__Validating(object sender, CancelEventArgs e)
@ -1012,19 +1050,6 @@ namespace ArdupilotMega.Setup
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : 0.0f); MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : 0.0f);
} }
private void BUT_saveheliconfig_Click(object sender, EventArgs e)
{
try
{
MainV2.comPort.setParam("COL_MIN_", HS3.minline);
MainV2.comPort.setParam("COL_MAX_", HS3.maxline);
MainV2.comPort.setParam("HS4_MIN", HS4.minline);
MainV2.comPort.setParam("HS4_MAX", HS4.maxline);
}
catch { MessageBox.Show("Failed to set min/max"); }
}
private void BUT_levelac2_Click(object sender, EventArgs e) private void BUT_levelac2_Click(object sender, EventArgs e)
{ {
try try
@ -1107,5 +1132,127 @@ namespace ArdupilotMega.Setup
{ {
reverseChannel("RC4_REV", ((CheckBox)sender).Checked, BARyaw); reverseChannel("RC4_REV", ((CheckBox)sender).Checked, BARyaw);
} }
private void BUT_swash_manual_Click(object sender, EventArgs e)
{
try
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("COL_MIN_", int.Parse(COL_MIN_.Text));
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX_.Text));
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
BUT_swash_manual.Text = "Manual";
}
else
{
COL_MAX_.Text = "1500";
COL_MIN_.Text = "1500";
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
BUT_swash_manual.Text = "Save";
}
}
catch { MessageBox.Show("Failed to set HSV_MAN"); }
}
private void BUT_HS4save_Click(object sender, EventArgs e)
{
try
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
BUT_HS4save.Text = "Manual";
}
else
{
HS4_MIN.Text = "1500";
HS4_MAX.Text = "1500";
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
BUT_HS4save.Text = "Save";
}
}
catch { MessageBox.Show("Failed to set HSV_MAN"); }
}
private void tabHeli_Click(object sender, EventArgs e)
{
}
private void HS4_Paint(object sender, PaintEventArgs e)
{
try
{
if (int.Parse(HS4_MIN.Text) > HS4.minline)
HS4_MIN.Text = HS4.minline.ToString();
if (int.Parse(HS4_MAX.Text) < HS4.maxline)
HS4_MAX.Text = HS4.maxline.ToString();
} catch {}
}
private void HS3_Paint(object sender, PaintEventArgs e)
{
try
{
if (int.Parse(COL_MIN_.Text) > HS3.minline)
COL_MIN_.Text = HS3.minline.ToString();
if (int.Parse(COL_MAX_.Text) < HS3.maxline)
COL_MAX_.Text = HS3.maxline.ToString();
}
catch { }
}
private void COL_MAX__Enter(object sender, EventArgs e)
{
inpwmdetect = true;
}
private void COL_MIN__Enter(object sender, EventArgs e)
{
inpwmdetect = true;
}
private void COL_MAX__Leave(object sender, EventArgs e)
{
inpwmdetect = false;
}
private void COL_MIN__Leave(object sender, EventArgs e)
{
inpwmdetect = false;
}
private void HS4_MIN_Enter(object sender, EventArgs e)
{
inpwmdetect = true;
}
private void HS4_MIN_Leave(object sender, EventArgs e)
{
inpwmdetect = false;
}
private void HS4_MAX_Enter(object sender, EventArgs e)
{
inpwmdetect = true;
}
private void HS4_MAX_Leave(object sender, EventArgs e)
{
inpwmdetect = false;
}
private void PWM_Validating(object sender, CancelEventArgs e)
{
Control temp = (Control)(sender);
if (int.Parse(temp.Text) < 900)
temp.Text = "900";
if (int.Parse(temp.Text) > 2100)
temp.Text = "2100";
}
} }
} }

File diff suppressed because it is too large Load Diff

View File

@ -4,14 +4,14 @@
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" /> <description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
<deployment install="true" /> <deployment install="true" />
<dependency> <dependency>
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="18145"> <dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="18547">
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" /> <assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
<hash> <hash>
<dsig:Transforms> <dsig:Transforms>
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" /> <dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms> </dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" /> <dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>asA4p3xM8idcyyuyecIXR3bVsug=</dsig:DigestValue> <dsig:DigestValue>N43U7y77mNy6nfkD9v5DNdwNLps=</dsig:DigestValue>
</hash> </hash>
</dependentAssembly> </dependentAssembly>
</dependency> </dependency>

File diff suppressed because it is too large Load Diff

View File

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

View File

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

View File

@ -24,9 +24,9 @@ RC7_TRIM 1500.000000
RC8_MAX 2000.000000 RC8_MAX 2000.000000
RC8_MIN 1000.000000 RC8_MIN 1000.000000
RC8_TRIM 1500.000000 RC8_TRIM 1500.000000
FLTMODE1 3 FLTMODE1 7
FLTMODE2 1 FLTMODE2 1
FLTMODE3 2 FLTMODE3 2
FLTMODE4 6 FLTMODE4 3
FLTMODE5 5 FLTMODE5 5
FLTMODE6 0 FLTMODE6 0

View File

@ -0,0 +1,38 @@
LOG_BITMASK 4095
SWITCH_ENABLE 0
RC2_REV -1
RC1_MAX 2000
RC1_MIN 1000
RC1_TRIM 1500
RC2_MAX 2000
RC2_MIN 1000
RC2_TRIM 1500
RC3_MAX 2000
RC3_MIN 1000
RC3_TRIM 1500
RC4_MAX 2000
RC4_MIN 1000
RC4_TRIM 1500
RC5_MAX 2000
RC5_MIN 1000
RC5_TRIM 1500
RC6_MAX 2000
RC6_MIN 1000
RC6_TRIM 1500
RC7_MAX 2000
RC7_MIN 1000
RC7_TRIM 1500
RC8_MAX 2000
RC8_MIN 1000
RC8_TRIM 1500
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 2
FLTMODE6 0
FLTMODE_CH 8
PTCH2SRV_P 2
RLL2SRV_I 0.1
RLL2SRV_P 1.2
INVERTEDFLT_CH 7

7
Tools/autotest/ap1.txt Normal file
View File

@ -0,0 +1,7 @@
QGC WPL 110
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361553 149.163956 120.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364540 149.162857 120.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361721 149.161835 120.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364170 149.164627 120.000000 1
5 0 3 20 0.000000 0.000000 0.000000 0.000000 -35.363289 149.165253 50.000000 1

View File

@ -1,94 +1,24 @@
# fly ArduCopter in SIL # fly ArduCopter in SIL
import util, pexpect, sys, time, math, shutil, os import util, pexpect, sys, time, math, shutil, os
from common import *
# get location of scripts # get location of scripts
testdir=os.path.dirname(os.path.realpath(__file__)) testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink')) sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil import mavutil, mavwp
HOME_LOCATION='-35.362938,149.165085,584,270' HOME_LOCATION='-35.362938,149.165085,584,270'
homeloc = None homeloc = None
num_wp = 0
# a list of pexpect objects to read while waiting for def arm_motors(mavproxy, mav):
# messages. This keeps the output to stdout flowing
expect_list = []
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
global expect_list
if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
print(msg)
for p in expect_list:
try:
p.read_nonblocking(100, timeout=0)
except pexpect.TIMEOUT:
pass
def expect_callback(e):
'''called when waiting for a expect pattern'''
global expect_list
for p in expect_list:
if p == e:
continue
try:
while p.read_nonblocking(100, timeout=0):
pass
except pexpect.TIMEOUT:
pass
class location(object):
'''represent a GPS coordinate'''
def __init__(self, lat, lng, alt=0):
self.lat = lat
self.lng = lng
self.alt = alt
def get_distance(loc1, loc2):
'''get ground distance between two locations'''
dlat = loc2.lat - loc1.lat
dlong = loc2.lng - loc1.lng
return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e5
def get_bearing(loc1, loc2):
'''get bearing from loc1 to loc2'''
off_x = loc2.lng - loc1.lng
off_y = loc2.lat - loc1.lat
bearing = 90.00 + math.atan2(-off_y, off_x) * 57.2957795
if bearing < 0:
bearing += 360.00
return bearing;
def current_location(mav):
'''return current location'''
# ensure we have a position
mav.recv_match(type='VFR_HUD', blocking=True)
mav.recv_match(type='GPS_RAW', blocking=True)
return location(mav.messages['GPS_RAW'].lat,
mav.messages['GPS_RAW'].lon,
mav.messages['VFR_HUD'].alt)
def wait_altitude(mav, alt_min, alt_max, timeout=30):
'''wait for a given altitude range'''
tstart = time.time()
print("Waiting for altitude between %u and %u" % (alt_min, alt_max))
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Altitude %u" % m.alt)
if m.alt >= alt_min and m.alt <= alt_max:
return True
print("Failed to attain altitude range")
return False
def arm_motors(mavproxy):
'''arm motors''' '''arm motors'''
print("Arming motors") print("Arming motors")
mavproxy.send('switch 6\n') # stabilize mode mavproxy.send('switch 6\n') # stabilize mode
mavproxy.expect('STABILIZE>') wait_mode(mav, 'STABILIZE')
mavproxy.send('rc 3 1000\n') mavproxy.send('rc 3 1000\n')
mavproxy.send('rc 4 2000\n') mavproxy.send('rc 4 2000\n')
mavproxy.expect('APM: ARMING MOTORS') mavproxy.expect('APM: ARMING MOTORS')
@ -96,7 +26,7 @@ def arm_motors(mavproxy):
print("MOTORS ARMED OK") print("MOTORS ARMED OK")
return True return True
def disarm_motors(mavproxy): def disarm_motors(mavproxy, mav):
'''disarm motors''' '''disarm motors'''
print("Disarming motors") print("Disarming motors")
mavproxy.send('switch 6\n') # stabilize mode mavproxy.send('switch 6\n') # stabilize mode
@ -111,7 +41,7 @@ def disarm_motors(mavproxy):
def takeoff(mavproxy, mav): def takeoff(mavproxy, mav):
'''takeoff get to 30m altitude''' '''takeoff get to 30m altitude'''
mavproxy.send('switch 6\n') # stabilize mode mavproxy.send('switch 6\n') # stabilize mode
mavproxy.expect('STABILIZE>') wait_mode(mav, 'STABILIZE')
mavproxy.send('rc 3 1500\n') mavproxy.send('rc 3 1500\n')
wait_altitude(mav, 30, 40) wait_altitude(mav, 30, 40)
print("TAKEOFF COMPLETE") print("TAKEOFF COMPLETE")
@ -121,9 +51,7 @@ def takeoff(mavproxy, mav):
def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60): def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60):
'''hold loiter position''' '''hold loiter position'''
mavproxy.send('switch 5\n') # loiter mode mavproxy.send('switch 5\n') # loiter mode
mavproxy.expect('LOITER>') wait_mode(mav, 'LOITER')
mavproxy.send('status\n')
mavproxy.expect('>')
m = mav.recv_match(type='VFR_HUD', blocking=True) m = mav.recv_match(type='VFR_HUD', blocking=True)
start_altitude = m.alt start_altitude = m.alt
tstart = time.time() tstart = time.time()
@ -141,58 +69,17 @@ def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60):
return False return False
def wait_heading(mav, heading, accuracy=5, timeout=30):
'''wait for a given heading'''
tstart = time.time()
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Heading %u" % m.heading)
if math.fabs(m.heading - heading) <= accuracy:
return True
print("Failed to attain heading %u" % heading)
return False
def wait_distance(mav, distance, accuracy=5, timeout=30):
'''wait for flight of a given distance'''
tstart = time.time()
start = current_location(mav)
while time.time() < tstart + timeout:
m = mav.recv_match(type='GPS_RAW', blocking=True)
pos = current_location(mav)
delta = get_distance(start, pos)
print("Distance %.2f meters" % delta)
if math.fabs(delta - distance) <= accuracy:
return True
print("Failed to attain distance %u" % distance)
return False
def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height_accuracy=-1):
'''wait for arrival at a location'''
tstart = time.time()
if target_altitude is None:
target_altitude = loc.alt
while time.time() < tstart + timeout:
m = mav.recv_match(type='GPS_RAW', blocking=True)
pos = current_location(mav)
delta = get_distance(loc, pos)
print("Distance %.2f meters" % delta)
if delta <= accuracy:
if height_accuracy != -1 and math.fabs(pos.alt - target_altitude) > height_accuracy:
continue
print("Reached location (%.2f meters)" % delta)
return True
print("Failed to attain location")
return False
def fly_square(mavproxy, mav, side=50, timeout=120): def fly_square(mavproxy, mav, side=50, timeout=120):
'''fly a square, flying N then E''' '''fly a square, flying N then E'''
mavproxy.send('switch 6\n') mavproxy.send('switch 6\n')
mavproxy.expect('STABILIZE>') wait_mode(mav, 'STABILIZE')
tstart = time.time() tstart = time.time()
failed = False failed = False
print("Save WP 1")
save_wp(mavproxy, mav)
print("turn")
mavproxy.send('rc 3 1430\n') mavproxy.send('rc 3 1430\n')
mavproxy.send('rc 4 1610\n') mavproxy.send('rc 4 1610\n')
if not wait_heading(mav, 0): if not wait_heading(mav, 0):
@ -205,23 +92,37 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
failed = True failed = True
mavproxy.send('rc 2 1500\n') mavproxy.send('rc 2 1500\n')
print("Save WP 2")
save_wp(mavproxy, mav)
print("Going east %u meters" % side) print("Going east %u meters" % side)
mavproxy.send('rc 1 1610\n') mavproxy.send('rc 1 1610\n')
if not wait_distance(mav, side): if not wait_distance(mav, side):
failed = True failed = True
mavproxy.send('rc 1 1500\n') mavproxy.send('rc 1 1500\n')
print("Save WP 3")
save_wp(mavproxy, mav)
print("Going south %u meters" % side) print("Going south %u meters" % side)
mavproxy.send('rc 2 1610\n') mavproxy.send('rc 2 1610\n')
if not wait_distance(mav, side): if not wait_distance(mav, side):
failed = True failed = True
mavproxy.send('rc 2 1500\n') mavproxy.send('rc 2 1500\n')
mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True)
print("Save WP 4")
save_wp(mavproxy, mav)
print("Going west %u meters" % side) print("Going west %u meters" % side)
mavproxy.send('rc 1 1390\n') mavproxy.send('rc 1 1390\n')
if not wait_distance(mav, side): if not wait_distance(mav, side):
failed = True failed = True
mavproxy.send('rc 1 1500\n') mavproxy.send('rc 1 1500\n')
print("Save WP 5")
save_wp(mavproxy, mav)
return not failed return not failed
@ -231,9 +132,7 @@ def land(mavproxy, mav, timeout=60):
'''land the quad''' '''land the quad'''
print("STARTING LANDING") print("STARTING LANDING")
mavproxy.send('switch 6\n') mavproxy.send('switch 6\n')
mavproxy.expect('STABILIZE>') wait_mode(mav, 'STABILIZE')
mavproxy.send('status\n')
mavproxy.expect('>')
# start by dropping throttle till we have lost 5m # start by dropping throttle till we have lost 5m
mavproxy.send('rc 3 1380\n') mavproxy.send('rc 3 1380\n')
@ -243,29 +142,78 @@ def land(mavproxy, mav, timeout=60):
# now let it settle gently # now let it settle gently
mavproxy.send('rc 3 1400\n') mavproxy.send('rc 3 1400\n')
tstart = time.time() tstart = time.time()
if wait_altitude(mav, -5, 0):
print("LANDING OK") ret = wait_altitude(mav, -5, 0)
print("LANDING: ok=%s" % ret)
return ret
def circle(mavproxy, mav, maxaltchange=10, holdtime=90, timeout=35):
'''fly circle'''
print("FLY CIRCLE")
mavproxy.send('switch 1\n') # CIRCLE mode
wait_mode(mav, 'CIRCLE')
m = mav.recv_match(type='VFR_HUD', blocking=True)
start_altitude = m.alt
tstart = time.time()
tholdstart = time.time()
print("Circle at %u meters for %u seconds" % (start_altitude, holdtime))
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("heading %u" % m.heading)
print("CIRCLE OK for %u seconds" % holdtime)
return True return True
else:
print("LANDING FAILED")
return False
def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=None): def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None):
'''fly a mission from a file''' '''fly a mission from a file'''
global homeloc global homeloc
global num_wp
print("test: Fly a mission from 0 to %u" % num_wp)
mavproxy.send('wp set 0\n')
mavproxy.send('switch 4\n') # auto mode
wait_mode(mav, 'AUTO')
#wait_altitude(mav, 30, 40)
ret = wait_waypoint(mav, 0, num_wp, timeout=90)
print("test: MISSION COMPLETE: passed=%s" % ret)
# wait here until ready
mavproxy.send('switch 5\n')
wait_mode(mav, 'LOITER')
return ret
#if not wait_distance(mav, 30, timeout=120):
# return False
#if not wait_location(mav, homeloc, timeout=600, target_altitude=target_altitude, height_accuracy=height_accuracy):
# return False
def load_mission_from_file(mavproxy, mav, filename):
'''load a mission from a file'''
global num_wp
wploader = mavwp.MAVWPLoader()
wploader.load(filename)
num_wp = wploader.count()
print("loaded mission with %u waypoints" % num_wp)
return True
def upload_mission_from_file(mavproxy, mav, filename):
'''Upload a mission from a file to APM'''
global num_wp
mavproxy.send('wp load %s\n' % filename) mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('flight plan received') mavproxy.expect('flight plan received')
mavproxy.send('wp list\n') mavproxy.send('wp list\n')
mavproxy.expect('Requesting [0-9]+ waypoints') mavproxy.expect('Requesting [0-9]+ waypoints')
mavproxy.send('switch 1\n') # auto mode
mavproxy.expect('AUTO>')
if not wait_distance(mav, 30, timeout=120):
return False
if not wait_location(mav, homeloc, timeout=600, target_altitude=target_altitude, height_accuracy=height_accuracy):
return False
return True return True
def save_mission_to_file(mavproxy, mav, filename):
global num_wp
mavproxy.send('wp save %s\n' % filename)
mavproxy.expect('Saved ([0-9]+) waypoints')
num_wp = int(mavproxy.match.group(1))
print("num_wp: %d" % num_wp)
return True
def setup_rc(mavproxy): def setup_rc(mavproxy):
'''setup RC override control''' '''setup RC override control'''
@ -275,8 +223,12 @@ def setup_rc(mavproxy):
mavproxy.send('rc 3 1000\n') mavproxy.send('rc 3 1000\n')
def fly_ArduCopter(): def fly_ArduCopter(viewerip=None):
'''fly ArduCopter in SIL''' '''fly ArduCopter in SIL
you can pass viewerip as an IP address to optionally send fg and
mavproxy packets too for local viewing of the flight in real time
'''
global expect_list, homeloc global expect_list, homeloc
sil = util.start_SIL('ArduCopter', wipe=True) sil = util.start_SIL('ArduCopter', wipe=True)
@ -295,12 +247,13 @@ def fly_ArduCopter():
mavproxy.expect('Loaded [0-9]+ parameters') mavproxy.expect('Loaded [0-9]+ parameters')
# reboot with new parameters # reboot with new parameters
print("CLOSING")
util.pexpect_close(mavproxy) util.pexpect_close(mavproxy)
util.pexpect_close(sil) util.pexpect_close(sil)
print("CLOSED THEM")
sil = util.start_SIL('ArduCopter') sil = util.start_SIL('ArduCopter')
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --out=192.168.2.15:14550 --quadcopter --streamrate=1') options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
if viewerip:
options += ' --out=%s:14550' % viewerip
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
mavproxy.expect('Logging to (\S+)') mavproxy.expect('Logging to (\S+)')
logfile = mavproxy.match.group(1) logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile) print("LOGFILE %s" % logfile)
@ -317,8 +270,10 @@ def fly_ArduCopter():
util.expect_setup_callback(mavproxy, expect_callback) util.expect_setup_callback(mavproxy, expect_callback)
# start hil_quad.py # start hil_quad.py
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --fgrate=200 --home=%s' % HOME_LOCATION, cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%s' % HOME_LOCATION
logfile=sys.stdout, timeout=10) if viewerip:
cmd += ' --fgout=192.168.2.15:9123'
hquad = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad) util.pexpect_autoclose(hquad)
hquad.expect('Starting at') hquad.expect('Starting at')
@ -332,28 +287,65 @@ def fly_ArduCopter():
raise raise
mav.message_hooks.append(message_hook) mav.message_hooks.append(message_hook)
failed = False failed = False
e = 'None'
try: try:
mav.wait_heartbeat() mav.wait_heartbeat()
mav.recv_match(type='GPS_RAW', blocking=True) mav.recv_match(type='GPS_RAW', blocking=True)
setup_rc(mavproxy) setup_rc(mavproxy)
homeloc = current_location(mav) homeloc = current_location(mav)
if not arm_motors(mavproxy): if not arm_motors(mavproxy, mav):
failed = True failed = True
if not takeoff(mavproxy, mav): if not takeoff(mavproxy, mav):
failed = True failed = True
print("# Fly A square")
if not fly_square(mavproxy, mav): if not fly_square(mavproxy, mav):
failed = True failed = True
# save the stored mission
print("# Save out the C7 mission")
if not save_mission_to_file(mavproxy, mav, os.path.join(testdir, "ch7_mission.txt")):
failed = True
# Loiter for 10 seconds
print("# Loiter for 10 seconds")
if not loiter(mavproxy, mav): if not loiter(mavproxy, mav):
failed = True failed = True
#Fly a circle for 60 seconds
print("# Fly a Circle")
if not circle(mavproxy, mav):
failed = True
# save the stored mission
print("# Fly CH 7 saved mission")
if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10):
failed = True
print("# Upload mission1")
if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")):
failed = True
# this grabs our mission count
print("# store mission1 locally")
if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")):
failed = True
print("# Fly mission 1")
if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10):
failed = True
else:
print("Flew mission1 OK")
print("# Land")
if not land(mavproxy, mav): if not land(mavproxy, mav):
failed = True failed = True
#fly_mission(mavproxy, mav, os.path.join(testdir, "mission_ttt.txt"), height_accuracy=0.2)
if not fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt"), height_accuracy = 0.5, target_altitude=10): print("# disarm motors")
failed = True if not disarm_motors(mavproxy, mav):
if not land(mavproxy, mav):
failed = True
if not disarm_motors(mavproxy):
failed = True failed = True
except pexpect.TIMEOUT, e: except pexpect.TIMEOUT, e:
failed = True failed = True

332
Tools/autotest/arduplane.py Normal file
View File

@ -0,0 +1,332 @@
# fly ArduPlane in SIL
import util, pexpect, sys, time, math, shutil, os
from common import *
# get location of scripts
testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil
HOME_LOCATION='-35.362938,149.165085,584,270'
homeloc = None
def takeoff(mavproxy, mav):
'''takeoff get to 30m altitude'''
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
# some rudder to counteract the prop torque
mavproxy.send('rc 4 1600\n')
# get it moving a bit first to avoid bad fgear ground physics
mavproxy.send('rc 3 1150\n')
mav.recv_match(condition='VFR_HUD.groundspeed>3', blocking=True)
# a bit faster
mavproxy.send('rc 3 1600\n')
mav.recv_match(condition='VFR_HUD.groundspeed>10', blocking=True)
# hit the gas harder now, and give it some elevator
mavproxy.send('rc 4 1500\n')
mavproxy.send('rc 2 1200\n')
mavproxy.send('rc 3 1800\n')
# gain a bit of altitude
wait_altitude(mav, homeloc.alt+30, homeloc.alt+40, timeout=30)
# level off
mavproxy.send('rc 2 1500\n')
print("TAKEOFF COMPLETE")
return True
def fly_left_circuit(mavproxy, mav):
'''fly a left circuit, 200m on a side'''
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
wait_level_flight(mavproxy, mav)
print("Flying left circuit")
# do 4 turns
for i in range(0,4):
# hard left
print("Starting turn %u" % i)
mavproxy.send('rc 1 1000\n')
wait_heading(mav, 270 - (90*i))
mavproxy.send('rc 1 1500\n')
print("Starting leg %u" % i)
wait_distance(mav, 100)
print("Circuit complete")
return True
def fly_RTL(mavproxy, mav):
'''fly to home'''
mavproxy.send('switch 2\n')
wait_mode(mav, 'RTL')
wait_location(mav, homeloc, accuracy=30,
target_altitude=100, height_accuracy=10)
print("RTL Complete")
return True
def fly_LOITER(mavproxy, mav):
'''loiter where we are'''
mavproxy.send('switch 3\n')
wait_mode(mav, 'LOITER')
while True:
wait_heading(mav, 0)
wait_heading(mav, 180)
return True
def wait_level_flight(mavproxy, mav, accuracy=5, timeout=30):
'''wait for level flight'''
tstart = time.time()
while time.time() < tstart + timeout:
m = mav.recv_match(type='ATTITUDE', blocking=True)
roll = math.degrees(m.roll)
pitch = math.degrees(m.pitch)
print("Roll=%.1f Pitch=%.1f" % (roll, pitch))
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
return True
print("Failed to attain level flight")
return False
def change_altitude(mavproxy, mav, altitude, accuracy=10):
'''get to a given altitude'''
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
alt_error = mav.messages['VFR_HUD'].alt - altitude
if alt_error > 0:
mavproxy.send('rc 2 2000\n')
else:
mavproxy.send('rc 2 1000\n')
wait_altitude(mav, altitude-accuracy/2, altitude+accuracy/2)
mavproxy.send('rc 2 1500\n')
print("Reached target altitude at %u" % mav.messages['VFR_HUD'].alt)
return wait_level_flight(mavproxy, mav)
def axial_left_roll(mavproxy, mav, count=1):
'''fly a left axial roll'''
# full throttle!
mavproxy.send('rc 3 2000\n')
change_altitude(mavproxy, mav, homeloc.alt+200)
# fly the roll in manual
mavproxy.send('switch 6\n')
wait_mode(mav, 'MANUAL')
while count > 0:
print("Starting roll")
mavproxy.send('rc 1 1000\n')
wait_roll(mav, -150, accuracy=20)
wait_roll(mav, 150, accuracy=20)
wait_roll(mav, 0, accuracy=20)
count -= 1
# back to FBWA
mavproxy.send('rc 1 1500\n')
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
mavproxy.send('rc 3 1700\n')
return wait_level_flight(mavproxy, mav)
def inside_loop(mavproxy, mav, count=1):
'''fly a inside loop'''
# full throttle!
mavproxy.send('rc 3 2000\n')
change_altitude(mavproxy, mav, homeloc.alt+200)
# fly the loop in manual
mavproxy.send('switch 6\n')
wait_mode(mav, 'MANUAL')
while count > 0:
print("Starting loop")
mavproxy.send('rc 2 1000\n')
wait_pitch(mav, 80, accuracy=20)
wait_pitch(mav, 0, accuracy=20)
count -= 1
# back to FBWA
mavproxy.send('rc 2 1500\n')
mavproxy.send('switch 4\n')
wait_mode(mav, 'FBWA')
mavproxy.send('rc 3 1700\n')
return wait_level_flight(mavproxy, mav)
def setup_rc(mavproxy):
'''setup RC override control'''
for chan in [1,2,4,5,6,7]:
mavproxy.send('rc %u 1500\n' % chan)
mavproxy.send('rc 3 1000\n')
mavproxy.send('rc 8 1800\n')
def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=None):
'''fly a mission from a file'''
global homeloc
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('flight plan received')
mavproxy.send('wp list\n')
mavproxy.expect('Requesting [0-9]+ waypoints')
mavproxy.send('switch 1\n') # auto mode
wait_mode(mav, 'AUTO')
if not wait_distance(mav, 30, timeout=120):
return False
if not wait_location(mav, homeloc, accuracy=50, timeout=600, target_altitude=target_altitude, height_accuracy=height_accuracy):
return False
print("Mission OK")
return True
def fly_ArduPlane(viewerip=None):
'''fly ArduPlane in SIL
you can pass viewerip as an IP address to optionally send fg and
mavproxy packets too for local viewing of the flight in real time
'''
global expect_list, homeloc
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
if viewerip:
options += ' --out=%s:14550' % viewerip
sil = util.start_SIL('ArduPlane', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send("param load %s/ArduPlane.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')
# restart with new parms
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduPlane')
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
mavproxy.expect('Logging to (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/ArduPlane-test.mavlog")
print("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
os.link(logfile, buildlog)
mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(mavproxy, expect_callback)
fg_scenery = os.getenv("FG_SCENERY")
if not fg_scenery:
raise RuntimeError("You must set the FG_SCENERY environment variable")
fgear_options = '''
--generic=socket,in,25,,5502,udp,MAVLink \
--generic=socket,out,50,,5501,udp,MAVLink \
--aircraft=Rascal110-JSBSim \
--control=mouse \
--disable-intro-music \
--airport=YKRY \
--lat=-35.362851 \
--lon=149.165223 \
--heading=350 \
--altitude=0 \
--geometry=650x550 \
--jpg-httpd=5502 \
--disable-anti-alias-hud \
--disable-hud-3d \
--disable-enhanced-lighting \
--disable-distance-attenuation \
--disable-horizon-effect \
--shading-flat \
--disable-textures \
--timeofday=noon \
--fdm=jsb \
--disable-sound \
--disable-fullscreen \
--disable-random-objects \
--disable-ai-models \
--shading-flat \
--fog-disable \
--disable-specular-highlight \
--disable-skyblend \
--fg-scenery=%s \
--disable-anti-alias-hud \
--wind=0@0 \
''' % fg_scenery
# start fgear
if os.getenv('DISPLAY'):
cmd = 'fgfs %s' % fgear_options
fgear = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
else:
cmd = "xvfb-run --server-num=42 -s '-screen 0 800x600x24' fgfs --enable-wireframe %s" % fgear_options
util.kill_xvfb(42)
fgear = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
fgear.xvfb_server_num = 42
util.pexpect_autoclose(fgear)
fgear.expect('creating 3D noise', timeout=30)
expect_list.extend([fgear, sil, mavproxy])
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception, msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
failed = False
e = 'None'
try:
mav.wait_heartbeat()
setup_rc(mavproxy)
mav.recv_match(type='GPS_RAW', condition='GPS_RAW.lat != 0 and GPS_RAW.alt != 0 and VFR_HUD.alt != 0',
blocking=True)
homeloc = current_location(mav)
print("Home location: %s" % homeloc)
if not takeoff(mavproxy, mav):
print("Failed takeoff")
failed = True
if not fly_left_circuit(mavproxy, mav):
print("Failed left circuit")
failed = True
if not axial_left_roll(mavproxy, mav, 1):
print("Failed left roll")
failed = True
if not inside_loop(mavproxy, mav):
print("Failed inside loop")
failed = True
if not fly_RTL(mavproxy, mav):
print("Failed RTL")
failed = True
if not fly_mission(mavproxy, mav, os.path.join(testdir, "ap1.txt"), height_accuracy = 10,
target_altitude=homeloc.alt+100):
print("Failed mission")
failed = True
except pexpect.TIMEOUT, e:
failed = True
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
util.pexpect_close(fgear)
if os.path.exists('ArduPlane-valgrind.log'):
os.chmod('ArduPlane-valgrind.log', 0644)
shutil.copy("ArduPlane-valgrind.log", util.reltopdir("../buildlogs/ArduPlane-valgrind.log"))
if failed:
print("FAILED: %s" % e)
return False
return True

View File

@ -2,7 +2,8 @@
# APM automatic test suite # APM automatic test suite
# Andrew Tridgell, October 2011 # Andrew Tridgell, October 2011
import pexpect, os, util, sys, shutil, arducopter import pexpect, os, util, sys, shutil
import arducopter, arduplane
import optparse, fnmatch, time, glob, traceback import optparse, fnmatch, time, glob, traceback
os.putenv('TMPDIR', util.reltopdir('tmp')) os.putenv('TMPDIR', util.reltopdir('tmp'))
@ -58,7 +59,8 @@ def convert_gpx():
util.run_cmd(util.reltopdir("../pymavlink/examples/mavtogpx.py") + " --nofixcheck " + m) util.run_cmd(util.reltopdir("../pymavlink/examples/mavtogpx.py") + " --nofixcheck " + m)
gpx = m + '.gpx' gpx = m + '.gpx'
kml = m + '.kml' kml = m + '.kml'
util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1 -F %s' % (gpx, kml), checkfail=False) util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml), checkfail=False)
util.run_cmd('zip %s.kmz %s.kml' % (m, m), checkfail=False)
return True return True
@ -81,6 +83,8 @@ You can get it from git://git.samba.org/tridge/UAV/HILTest.git
parser = optparse.OptionParser("autotest") parser = optparse.OptionParser("autotest")
parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)') parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)')
parser.add_option("--list", action='store_true', default=False, help='list the available steps') parser.add_option("--list", action='store_true', default=False, help='list the available steps')
parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to')
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
opts, args = parser.parse_args() opts, args = parser.parse_args()
@ -90,6 +94,7 @@ steps = [
'build2560.ArduPlane', 'build2560.ArduPlane',
'build.ArduPlane', 'build.ArduPlane',
'defaults.ArduPlane', 'defaults.ArduPlane',
'fly.ArduPlane',
'logs.ArduPlane', 'logs.ArduPlane',
'build1280.ArduCopter', 'build1280.ArduCopter',
'build2560.ArduCopter', 'build2560.ArduCopter',
@ -147,6 +152,12 @@ def run_step(step):
if step == 'fly.ArduCopter': if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter() return arducopter.fly_ArduCopter()
if step == 'fly.ArduPlane':
if not opts.experimental:
print("DISABLED: use --experimental to enable fly.ArduPlane")
return True
return arduplane.fly_ArduPlane(viewerip=opts.viewerip)
if step == 'convertgpx': if step == 'convertgpx':
return convert_gpx() return convert_gpx()
@ -240,7 +251,7 @@ def run_tests(steps):
results.addglob('DataFlash Log', '*.flashlog') results.addglob('DataFlash Log', '*.flashlog')
results.addglob("MAVLink log", '*.mavlog') results.addglob("MAVLink log", '*.mavlog')
results.addglob("GPX track", '*.gpx') results.addglob("GPX track", '*.gpx')
results.addglob("KML track", '*.kml') results.addglob("KMZ track", '*.kmz')
results.addfile('ArduPlane build log', 'ArduPlane.txt') results.addfile('ArduPlane build log', 'ArduPlane.txt')
results.addfile('ArduPlane code size', 'ArduPlane.sizes.txt') results.addfile('ArduPlane code size', 'ArduPlane.sizes.txt')
results.addfile('ArduPlane stack sizes', 'ArduPlane.framesizes.txt') results.addfile('ArduPlane stack sizes', 'ArduPlane.framesizes.txt')

196
Tools/autotest/common.py Normal file
View File

@ -0,0 +1,196 @@
import util, pexpect, time, math
# a list of pexpect objects to read while waiting for
# messages. This keeps the output to stdout flowing
expect_list = []
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
global expect_list
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
# print(msg)
for p in expect_list:
try:
p.read_nonblocking(100, timeout=0)
except pexpect.TIMEOUT:
pass
def expect_callback(e):
'''called when waiting for a expect pattern'''
global expect_list
for p in expect_list:
if p == e:
continue
try:
while p.read_nonblocking(100, timeout=0):
pass
except pexpect.TIMEOUT:
pass
class location(object):
'''represent a GPS coordinate'''
def __init__(self, lat, lng, alt=0):
self.lat = lat
self.lng = lng
self.alt = alt
def __str__(self):
return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)
def get_distance(loc1, loc2):
'''get ground distance between two locations'''
dlat = loc2.lat - loc1.lat
dlong = loc2.lng - loc1.lng
return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e5
def get_bearing(loc1, loc2):
'''get bearing from loc1 to loc2'''
off_x = loc2.lng - loc1.lng
off_y = loc2.lat - loc1.lat
bearing = 90.00 + math.atan2(-off_y, off_x) * 57.2957795
if bearing < 0:
bearing += 360.00
return bearing;
def current_location(mav):
'''return current location'''
# ensure we have a position
mav.recv_match(type='VFR_HUD', blocking=True)
mav.recv_match(type='GPS_RAW', blocking=True)
return location(mav.messages['GPS_RAW'].lat,
mav.messages['GPS_RAW'].lon,
mav.messages['VFR_HUD'].alt)
def wait_altitude(mav, alt_min, alt_max, timeout=30):
'''wait for a given altitude range'''
tstart = time.time()
print("Waiting for altitude between %u and %u" % (alt_min, alt_max))
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Altitude %u" % m.alt)
if m.alt >= alt_min and m.alt <= alt_max:
return True
print("Failed to attain altitude range")
return False
def wait_roll(mav, roll, accuracy, timeout=30):
'''wait for a given roll in degrees'''
tstart = time.time()
print("Waiting for roll of %u" % roll)
while time.time() < tstart + timeout:
m = mav.recv_match(type='ATTITUDE', blocking=True)
r = math.degrees(m.roll)
print("Roll %u" % r)
if math.fabs(r - roll) <= accuracy:
return True
print("Failed to attain roll %u" % roll)
return False
def wait_pitch(mav, pitch, accuracy, timeout=30):
'''wait for a given pitch in degrees'''
tstart = time.time()
print("Waiting for pitch of %u" % pitch)
while time.time() < tstart + timeout:
m = mav.recv_match(type='ATTITUDE', blocking=True)
r = math.degrees(m.pitch)
print("Pitch %u" % r)
if math.fabs(r - pitch) <= accuracy:
return True
print("Failed to attain pitch %u" % pitch)
return False
def wait_heading(mav, heading, accuracy=5, timeout=30):
'''wait for a given heading'''
tstart = time.time()
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Heading %u" % m.heading)
if math.fabs(m.heading - heading) <= accuracy:
return True
print("Failed to attain heading %u" % heading)
return False
def wait_distance(mav, distance, accuracy=5, timeout=30):
'''wait for flight of a given distance'''
tstart = time.time()
start = current_location(mav)
while time.time() < tstart + timeout:
m = mav.recv_match(type='GPS_RAW', blocking=True)
pos = current_location(mav)
delta = get_distance(start, pos)
print("Distance %.2f meters" % delta)
if math.fabs(delta - distance) <= accuracy:
return True
print("Failed to attain distance %u" % distance)
return False
def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height_accuracy=-1):
'''wait for arrival at a location'''
tstart = time.time()
if target_altitude is None:
target_altitude = loc.alt
while time.time() < tstart + timeout:
m = mav.recv_match(type='GPS_RAW', blocking=True)
pos = current_location(mav)
delta = get_distance(loc, pos)
print("Distance %.2f meters" % delta)
if delta <= accuracy:
if height_accuracy != -1 and math.fabs(pos.alt - target_altitude) > height_accuracy:
continue
print("Reached location (%.2f meters)" % delta)
return True
print("Failed to attain location")
return False
def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, timeout=400):
'''wait for waypoint ranges'''
tstart = time.time()
# this message arrives after we set the current WP
m = mav.recv_match(type='WAYPOINT_CURRENT', blocking=True)
start_wp = m.seq
current_wp = start_wp
print("\ntest: wait for waypoint ranges start=%u end=%u\n\n" % (wpnum_start, wpnum_end))
# if start_wp != wpnum_start:
# print("test: Expected start waypoint %u but got %u" % (wpnum_start, start_wp))
# return False
while time.time() < tstart + timeout:
m = mav.recv_match(type='WAYPOINT_CURRENT', blocking=True)
seq = m.seq
m = mav.recv_match(type='NAV_CONTROLLER_OUTPUT', blocking=True)
wp_dist = m.wp_dist
print("test: WP %u (wp_dist=%u)" % (seq, wp_dist))
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
print("test: Starting new waypoint %u" % seq)
tstart = time.time()
current_wp = seq
# the wp_dist check is a hack until we can sort out the right seqnum
# for end of mission
if current_wp == wpnum_end or (current_wp == wpnum_end-1 and wp_dist < 2):
print("Reached final waypoint %u" % seq)
return True
if seq > current_wp+1:
print("Skipped waypoint! Got wp %u expected %u" % (seq, current_wp+1))
return False
print("Timed out waiting for waypoint %u of %u" % (wpnum_end, wpnum_end))
return False
def save_wp(mavproxy, mav):
mavproxy.send('rc 7 2000\n')
mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==2000', blocking=True)
mavproxy.send('rc 7 1000\n')
mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True)
#mavproxy.send('wp list\n')
#mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True)
def wait_mode(mav, mode):
'''wait for a flight mode to be engaged'''
mav.recv_match(condition='MAV.flightmode=="%s"' % mode, blocking=True)

View File

@ -0,0 +1,78 @@
QGC WPL 110
#s fr ac cmd p1 p2 p3 p4 lat lon alt continue
0 1 3 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582 1
# takeoff
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20 1
# MAV_CMD_NAV_WAYPOINT A
# Hold sec Hit rad empty Yaw angle lat lon alt continue
2 0 3 16 0 3 0 0 -35.363949 149.164151 20 1
# MAV_CMD_CONDITION_YAW
# delta deg sec Dir 1=CW Rel/Abs Lat lon Alt continue
3 0 3 115 640 20 1 1 0 0 0 1
# MAV_CMD_NAV_LOITER_TIME
# seconds empty rad Yaw per Lat lon Alt continue
4 0 3 19 35 20 0 1 0 0 0 1
# MAV_CMD_NAV_WAYPOINT B
# Hold sec Hit rad empty Yaw angle lat lon alt continue
5 0 3 16 0 3 0 0 -35.363287 149.164958 20 1
# MAV_CMD_NAV_LOITER_TURNS
# Turns lat lon alt continue
6 0 3 18 2 0 0 0 0 0 0 1
# MAV_CMD_DO_SET_ROI, MAV_ROI_WPNEXT = 1
# MAV_ROI WP index ROI index lat lon alt continue
7 0 3 201 1 0 0 0 0 0 0 1
# MAV_CMD_NAV_WAYPOINT C
# Hold sec Hit rad empty Yaw angle lat lon alt continue
8 0 3 16 0 3 0 0 -35.364865 149.164952 20 1
# MAV_CMD_CONDITION_DISTANCE
# meters continue
9 0 3 114 100 0 0 0 0 0 0 1
# MAV_CMD_CONDITION_CHANGE_ALT
# climb_rate alt continue
10 0 3 113 0 0 0 0 0 0 40 1
# MAV_CMD_NAV_WAYPOINT D
# Hold sec Hit rad empty Yaw angle lat lon alt continue
11 0 3 16 0 3 0 0 -35.363165 149.163905 20 1
# MAV_CMD_NAV_WAYPOINT E
# Hold sec Hit rad empty Yaw angle lat lon alt continue
12 0 3 16 0 3 0 0 -35.363611 149.163583 20 1
# MAV_CMD_DO_JUMP
# seq# repeat . . . . . continue
13 0 3 177 11 3 0 0 0 0 0 1
# MAV_CMD_NAV_RETURN_TO_LAUNCH
# . . . . alt continue
14 0 3 20 0 0 0 0 0 0 20 1
# MAV_CMD_NAV_LAND
#
15 0 3 21 0 0 0 0 0 0 0 1
# WP_total = 10
# 0 = home
# seq
# current
# frame
# command
# param1,
# param2,
# param3
# param4
# x (latitude)
# y (longitude)
# z (altitude)
# autocontinue

View File

@ -1,6 +1,6 @@
QGC WPL 110 QGC WPL 110
#s fr ac cmd p1 p2 p3 p4 lat lon alt continue #s fr ac cmd p1 p2 p3 p4 lat lon alt continue
0 1 3 0 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1 0 1 3 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20.000000 1 1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20.000000 1
2 0 3 115 360.0 10.0000 1.0 1.0 0 0 0 1 2 0 3 115 360.0 10.0000 1.0 1.0 0 0 0 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362612 149.164186 20.000000 1 3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362612 149.164186 20.000000 1
@ -8,6 +8,21 @@ QGC WPL 110
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363910 149.162632 20.000000 1 5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363910 149.162632 20.000000 1
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365215 149.164145 20.000000 1 6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365215 149.164145 20.000000 1
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362612 149.164186 20.000000 1 7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362612 149.164186 20.000000 1
8 0 3 20 0.000000 0.000000 0.000000 0.000000 -35.363228 149.161896 30.000000 1 8 0 3 20 0.000000 0.000000 0.000000 0.000000 0 0 30.000000 1
9 0 3 21 0.000000 0.000000 0.000000 0.000000 -35.363228 149.161896 0.000000 1 9 0 3 21 0.000000 0.000000 0.000000 0.000000 0 0 0.000000 1
# WP_total = 10
# 0 = home
# seq
# current
# frame
# command
# param1,
# param2,
# param3
# param4
# x (latitude)
# y (longitude)
# z (altitude)
# autocontinue

View File

@ -73,9 +73,19 @@ def pexpect_autoclose(p):
def pexpect_close(p): def pexpect_close(p):
'''close a pexpect child''' '''close a pexpect child'''
global close_list global close_list
xvfb_server_num = getattr(p, 'xvfb_server_num', None)
if xvfb_server_num is not None:
kill_xvfb(xvfb_server_num)
try:
p.close() p.close()
except Exception:
pass
time.sleep(1) time.sleep(1)
try:
p.close(force=True) p.close(force=True)
except Exception:
pass
if p in close_list: if p in close_list:
close_list.remove(p) close_list.remove(p)
@ -83,12 +93,7 @@ def pexpect_close_all():
'''close all pexpect children''' '''close all pexpect children'''
global close_list global close_list
for p in close_list[:]: for p in close_list[:]:
try: pexpect_close(p)
p.close()
time.sleep(1)
p.close(Force=True)
except Exception:
pass
def start_SIL(atype, valgrind=False, wipe=False, CLI=False): def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
'''launch a SIL instance''' '''launch a SIL instance'''
@ -111,7 +116,7 @@ def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:
'''launch mavproxy connected to a SIL instance''' '''launch mavproxy connected to a SIL instance'''
global close_list global close_list
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py') MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
cmd = MAVPROXY + ' --master=%s --fgrate=%u' % (master, fgrate) cmd = MAVPROXY + ' --master=%s --fgrate=%u --out=127.0.0.1:14550' % (master, fgrate)
if setup: if setup:
cmd += ' --setup' cmd += ' --setup'
if aircraft is None: if aircraft is None:
@ -171,3 +176,13 @@ def lock_file(fname):
except Exception: except Exception:
return None return None
return f return f
def kill_xvfb(server_num):
'''Xvfb is tricky to kill!'''
try:
import signal
pid = int(open('/tmp/.X%s-lock' % server_num).read().strip())
print("Killing Xvfb process %u" % pid)
os.kill(pid, signal.SIGINT)
except Exception, msg:
print("failed to kill Xvfb process - %s" % msg)

View File

@ -2,7 +2,7 @@
#define APM_BMP085_h #define APM_BMP085_h
#define TEMP_FILTER_SIZE 2 #define TEMP_FILTER_SIZE 2
#define PRESS_FILTER_SIZE 2 #define PRESS_FILTER_SIZE 4
#include "APM_BMP085_hil.h" #include "APM_BMP085_hil.h"

View File

@ -35,7 +35,7 @@
#include "DataFlash.h" #include "DataFlash.h"
#include <SPI.h> #include <SPI.h>
#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1 #define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwriting from page 1
// *** INTERNAL FUNCTIONS *** // *** INTERNAL FUNCTIONS ***
@ -160,6 +160,7 @@ void DataFlash_Class::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive(); dataflash_CS_inactive();
} }
void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait) void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
@ -271,10 +272,15 @@ void DataFlash_Class::ChipErase ()
void DataFlash_Class::StartWrite(int PageAdr) void DataFlash_Class::StartWrite(int PageAdr)
{ {
df_BufferNum=1; df_BufferNum=1;
df_BufferIdx=0; df_BufferIdx=4;
df_PageAdr=PageAdr; df_PageAdr=PageAdr;
df_Stop_Write=0; df_Stop_Write=0;
WaitReady(); WaitReady();
// We are starting a new page - write FileNumber and FilePage
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
} }
void DataFlash_Class::FinishWrite(void) void DataFlash_Class::FinishWrite(void)
@ -284,12 +290,12 @@ void DataFlash_Class::FinishWrite(void)
df_PageAdr++; df_PageAdr++;
if (OVERWRITE_DATA==1) if (OVERWRITE_DATA==1)
{ {
if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1; df_PageAdr = 1;
} }
else else
{ {
if (df_PageAdr>=4096) // If we reach the end of the memory, stop here if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
df_Stop_Write=1; df_Stop_Write=1;
} }
@ -308,17 +314,17 @@ void DataFlash_Class::WriteByte(byte data)
df_BufferIdx++; df_BufferIdx++;
if (df_BufferIdx >= df_PageSize) // End of buffer? if (df_BufferIdx >= df_PageSize) // End of buffer?
{ {
df_BufferIdx=0; df_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
df_PageAdr++; df_PageAdr++;
if (OVERWRITE_DATA==1) if (OVERWRITE_DATA==1)
{ {
if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1; df_PageAdr = 1;
} }
else else
{ {
if (df_PageAdr>=4096) // If we reach the end of the memory, stop here if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
df_Stop_Write=1; df_Stop_Write=1;
} }
@ -326,6 +332,12 @@ void DataFlash_Class::WriteByte(byte data)
df_BufferNum=2; df_BufferNum=2;
else else
df_BufferNum=1; df_BufferNum=1;
// We are starting a new page - write FileNumber and FilePage
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
df_FilePage++;
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
} }
} }
} }
@ -359,11 +371,19 @@ int DataFlash_Class::GetPage()
void DataFlash_Class::StartRead(int PageAdr) void DataFlash_Class::StartRead(int PageAdr)
{ {
df_Read_BufferNum=1; df_Read_BufferNum=1;
df_Read_BufferIdx=0; df_Read_BufferIdx=4;
df_Read_PageAdr=PageAdr; df_Read_PageAdr=PageAdr;
WaitReady(); WaitReady();
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer
//Serial.print(df_Read_PageAdr, DEC); Serial.print("\t");
df_Read_PageAdr++; df_Read_PageAdr++;
// We are starting a new page - read FileNumber and FilePage
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
//Serial.print(df_FileNumber, DEC); Serial.print("\t");
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
//Serial.println(df_FileNumber, DEC); Serial.print("\t");
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
} }
byte DataFlash_Class::ReadByte() byte DataFlash_Class::ReadByte()
@ -375,14 +395,19 @@ byte DataFlash_Class::ReadByte()
df_Read_BufferIdx++; df_Read_BufferIdx++;
if (df_Read_BufferIdx >= df_PageSize) // End of buffer? if (df_Read_BufferIdx >= df_PageSize) // End of buffer?
{ {
df_Read_BufferIdx=0; df_Read_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer
df_Read_PageAdr++; df_Read_PageAdr++;
if (df_Read_PageAdr>=4096) // If we reach the end of the memory, start from the begining if (df_Read_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
{ {
df_Read_PageAdr = 0; df_Read_PageAdr = 0;
df_Read_END = true; df_Read_END = true;
} }
// We are starting a new page - read FileNumber and FilePage
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
} }
return result; return result;
} }
@ -407,5 +432,23 @@ long DataFlash_Class::ReadLong()
return result; return result;
} }
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
{
return df_FilePage;
}
// make one instance for the user to use // make one instance for the user to use
DataFlash_Class DataFlash; DataFlash_Class DataFlash;

View File

@ -4,6 +4,10 @@
#ifndef DataFlash_h #ifndef DataFlash_h
#define DataFlash_h #define DataFlash_h
#include "../FastSerial/FastSerial.h"
// flash size
#define DF_LAST_PAGE 4096
// arduino mega SPI pins // arduino mega SPI pins
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define DF_DATAOUT 51 // MOSI #define DF_DATAOUT 51 // MOSI
@ -45,15 +49,24 @@ class DataFlash_Class
unsigned char df_BufferNum; unsigned char df_BufferNum;
unsigned char df_Read_BufferNum; unsigned char df_Read_BufferNum;
uint16_t df_BufferIdx; uint16_t df_BufferIdx;
uint16_t df_Read_BufferIdx; uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr; uint16_t df_PageAdr;
uint16_t df_Read_PageAdr; uint16_t df_Read_PageAdr;
unsigned char df_Read_END; unsigned char df_Read_END;
unsigned char df_Stop_Write; unsigned char df_Stop_Write;
uint16_t df_FileNumber;
uint16_t df_FilePage;
//Methods //Methods
unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr); unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr);
void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data); void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data);
void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait); void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr); void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr);
void WaitReady(); void WaitReady();
unsigned char ReadStatusReg(); unsigned char ReadStatusReg();
@ -71,20 +84,30 @@ class DataFlash_Class
void ReadManufacturerID(); void ReadManufacturerID();
int16_t GetPage(); int16_t GetPage();
int16_t GetWritePage(); int16_t GetWritePage();
void PageErase (uint16_t PageAdr); void PageErase (uint16_t PageAdr);
void ChipErase (); void ChipErase ();
// Write methods // Write methods
void StartWrite(int16_t PageAdr); void StartWrite(int16_t PageAdr);
void FinishWrite(); void FinishWrite();
void WriteByte(unsigned char data); void WriteByte(unsigned char data);
void WriteInt(int16_t data); void WriteInt(int16_t data);
void WriteLong(int32_t data); void WriteLong(int32_t data);
// Read methods // Read methods
void StartRead(int16_t PageAdr); void StartRead(int16_t PageAdr);
unsigned char ReadByte(); unsigned char ReadByte();
int16_t ReadInt(); int16_t ReadInt();
int32_t ReadLong(); int32_t ReadLong();
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFileNumber();
uint16_t GetFilePage();
}; };
extern DataFlash_Class DataFlash; extern DataFlash_Class DataFlash;

View File

@ -123,6 +123,11 @@ void DataFlash_Class::StartWrite(int16_t PageAdr)
df_BufferIdx = 0; df_BufferIdx = 0;
df_PageAdr = PageAdr; df_PageAdr = PageAdr;
df_Stop_Write = 0; df_Stop_Write = 0;
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
} }
void DataFlash_Class::FinishWrite(void) void DataFlash_Class::FinishWrite(void)
@ -145,6 +150,12 @@ void DataFlash_Class::FinishWrite(void)
df_BufferNum=2; df_BufferNum=2;
else else
df_BufferNum=1; df_BufferNum=1;
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
df_FilePage++;
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
} }
@ -255,5 +266,21 @@ int32_t DataFlash_Class::ReadLong()
return (int32_t)result; return (int32_t)result;
} }
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
{
return df_FilePage;
}
// make one instance for the user to use // make one instance for the user to use
DataFlash_Class DataFlash; DataFlash_Class DataFlash;

View File

@ -295,11 +295,15 @@ void FastSerial::flush(void)
void FastSerial::write(uint8_t c) void FastSerial::write(uint8_t c)
{ {
struct tcp_state *s = &tcp_state[_u2x]; struct tcp_state *s = &tcp_state[_u2x];
int flags = MSG_NOSIGNAL;
check_connection(s); check_connection(s);
if (!s->connected) { if (!s->connected) {
return; return;
} }
send(s->fd, &c, 1, MSG_DONTWAIT | MSG_NOSIGNAL); if (!desktop_state.slider) {
flags |= MSG_DONTWAIT;
}
send(s->fd, &c, 1, flags);
} }
// Buffer management /////////////////////////////////////////////////////////// // Buffer management ///////////////////////////////////////////////////////////