mirror of https://github.com/ArduPilot/ardupilot
Removed last of Xtrack
This commit is contained in:
parent
7d57dfa3ec
commit
7e79612125
|
@ -316,11 +316,13 @@ static bool did_ground_start = false; // have we ground started after first ar
|
|||
// ---------------------
|
||||
static const float radius_of_earth = 6378100; // meters
|
||||
static const float gravity = 9.81; // meters/ sec^2
|
||||
static long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate
|
||||
//static long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate
|
||||
static long target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
||||
|
||||
static bool xtrack_enabled = false;
|
||||
static long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
//static bool xtrack_enabled = false;
|
||||
//static long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
//static long crosstrack_correction; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
|
||||
static int climb_rate; // m/s * 100 - For future implementation of controlled ascent/descent by rate
|
||||
static long circle_angle = 0;
|
||||
static byte wp_control; // used to control - navgation or loiter
|
||||
|
@ -349,7 +351,7 @@ static int airspeed; // m/s * 100
|
|||
|
||||
// Location Errors
|
||||
// ---------------
|
||||
static long bearing_error; // deg * 100 : 0 to 36000
|
||||
//static long bearing_error; // deg * 100 : 0 to 36000
|
||||
static long altitude_error; // meters * 100 we are off in altitude
|
||||
static long old_altitude;
|
||||
static long yaw_error; // how off are we pointed
|
||||
|
@ -674,8 +676,8 @@ static void medium_loop()
|
|||
// ------------------------------------------------------
|
||||
navigate();
|
||||
|
||||
// control mode specific updates to nav_bearing
|
||||
// --------------------------------------------
|
||||
// control mode specific updates
|
||||
// -----------------------------
|
||||
update_navigation();
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_NTUN)
|
||||
|
@ -799,7 +801,7 @@ static void fifty_hz_loop()
|
|||
#endif
|
||||
|
||||
// use Yaw to find our bearing error
|
||||
calc_bearing_error();
|
||||
//calc_bearing_error();
|
||||
|
||||
//if (throttle_slew < 0)
|
||||
// throttle_slew++;
|
||||
|
@ -1246,7 +1248,7 @@ static void update_navigation()
|
|||
wp_control = WP_MODE;
|
||||
}else{
|
||||
set_mode(LOITER);
|
||||
xtrack_enabled = false;
|
||||
//xtrack_enabled = false;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -12,7 +12,7 @@ void HIL_XPLANE::output_HIL(void)
|
|||
output_int((int)(g.rc_3.servo_out)); // 2 bytes 4, 5
|
||||
output_int((int)(g.rc_4.servo_out)); // 3 bytes 6, 7
|
||||
output_int((int)wp_distance); // 4 bytes 8,9
|
||||
output_int((int)bearing_error); // 5 bytes 10,11
|
||||
//output_int((int)bearing_error); // 5 bytes 10,11
|
||||
output_int((int)altitude_error); // 6 bytes 12, 13
|
||||
output_int((int)energy_error); // 7 bytes 14,15
|
||||
output_byte((int)g.waypoint_index); // 8 bytes 16
|
||||
|
|
|
@ -197,7 +197,7 @@ static void set_next_WP(struct Location *wp)
|
|||
|
||||
// set a new crosstrack bearing
|
||||
// ----------------------------
|
||||
crosstrack_bearing = target_bearing; // Used for track following
|
||||
//crosstrack_bearing = target_bearing; // Used for track following
|
||||
|
||||
gcs.print_current_waypoints();
|
||||
}
|
||||
|
|
|
@ -211,18 +211,19 @@ static long get_crosstrack_correction(void)
|
|||
return 0;
|
||||
}
|
||||
*/
|
||||
|
||||
/*
|
||||
static long cross_track_test()
|
||||
{
|
||||
long temp = wrap_180(target_bearing - crosstrack_bearing);
|
||||
return abs(temp);
|
||||
}
|
||||
|
||||
*/
|
||||
/*
|
||||
static void reset_crosstrack()
|
||||
{
|
||||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
||||
}
|
||||
|
||||
*/
|
||||
static long get_altitude_above_home(void)
|
||||
{
|
||||
// This is the altitude above the home location
|
||||
|
|
|
@ -41,7 +41,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
|
|||
};
|
||||
|
||||
// Create the top-level menu object.
|
||||
MENU(main_menu, "ArduCopter 2.0.42 Beta", main_menu_commands);
|
||||
MENU(main_menu, "ArduCopter 2.0.43 Beta", main_menu_commands);
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
|
@ -362,7 +362,7 @@ static void set_mode(byte mode)
|
|||
led_mode = NORMAL_LEDS;
|
||||
|
||||
// most modes do not calculate crosstrack correction
|
||||
xtrack_enabled = false;
|
||||
//xtrack_enabled = false;
|
||||
reset_nav_I();
|
||||
|
||||
switch(control_mode)
|
||||
|
@ -411,7 +411,7 @@ static void set_mode(byte mode)
|
|||
|
||||
// do crosstrack correction
|
||||
// XXX move to flight commands
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
break;
|
||||
|
||||
case CIRCLE:
|
||||
|
@ -437,7 +437,7 @@ static void set_mode(byte mode)
|
|||
roll_pitch_mode = ROLL_PITCH_AUTO;
|
||||
throttle_mode = THROTTLE_AUTO;
|
||||
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
init_throttle_cruise();
|
||||
next_WP = current_loc;
|
||||
break;
|
||||
|
@ -447,7 +447,7 @@ static void set_mode(byte mode)
|
|||
roll_pitch_mode = RTL_RP;
|
||||
throttle_mode = RTL_THR;
|
||||
|
||||
xtrack_enabled = true;
|
||||
//xtrack_enabled = true;
|
||||
init_throttle_cruise();
|
||||
do_RTL();
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue