2011-09-08 22:29:39 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2013-04-11 21:25:46 -03:00
|
|
|
|
|
|
|
// set the nav_controller pointer to the right controller
|
|
|
|
static void set_nav_controller(void)
|
|
|
|
{
|
|
|
|
switch ((AP_Navigation::ControllerType)g.nav_controller.get()) {
|
|
|
|
case AP_Navigation::CONTROLLER_L1:
|
|
|
|
nav_controller = &L1_controller;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
reset the total loiter angle
|
|
|
|
*/
|
|
|
|
static void loiter_angle_reset(void)
|
|
|
|
{
|
2013-04-15 08:31:11 -03:00
|
|
|
loiter.sum_cd = 0;
|
|
|
|
loiter.total_cd = 0;
|
2013-04-11 21:25:46 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update the total angle we have covered in a loiter. Used to support
|
|
|
|
commands to do N circles of loiter
|
|
|
|
*/
|
|
|
|
static void loiter_angle_update(void)
|
|
|
|
{
|
|
|
|
int32_t target_bearing_cd = nav_controller->target_bearing_cd();
|
|
|
|
int32_t loiter_delta_cd;
|
2013-04-15 08:31:11 -03:00
|
|
|
if (loiter.sum_cd == 0) {
|
|
|
|
// use 1 cd for initial delta
|
|
|
|
loiter_delta_cd = 1;
|
2013-04-11 21:25:46 -03:00
|
|
|
} else {
|
|
|
|
loiter_delta_cd = target_bearing_cd - loiter.old_target_bearing_cd;
|
|
|
|
}
|
|
|
|
loiter.old_target_bearing_cd = target_bearing_cd;
|
|
|
|
loiter_delta_cd = wrap_180_cd(loiter_delta_cd);
|
|
|
|
|
2013-04-15 08:31:11 -03:00
|
|
|
loiter.sum_cd += loiter_delta_cd;
|
2013-04-11 21:25:46 -03:00
|
|
|
}
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
//****************************************************************
|
|
|
|
// Function that will calculate the desired direction to fly and distance
|
|
|
|
//****************************************************************
|
|
|
|
static void navigate()
|
|
|
|
{
|
2013-04-11 21:25:46 -03:00
|
|
|
// allow change of nav controller mid-flight
|
|
|
|
set_nav_controller();
|
|
|
|
|
2012-08-16 21:50:15 -03:00
|
|
|
// do not navigate with corrupt data
|
|
|
|
// ---------------------------------
|
|
|
|
if (!have_position) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-04-11 21:25:46 -03:00
|
|
|
if (next_WP.lat == 0) {
|
2012-08-16 21:50:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// waypoint distance from plane
|
|
|
|
// ----------------------------
|
2013-08-04 21:30:04 -03:00
|
|
|
wp_distance = get_distance(current_loc, next_WP);
|
2012-08-16 21:50:15 -03:00
|
|
|
|
|
|
|
if (wp_distance < 0) {
|
|
|
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("WP error - distance < 0"));
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-04-11 21:25:46 -03:00
|
|
|
// update total loiter angle
|
|
|
|
loiter_angle_update();
|
2012-08-16 21:50:15 -03:00
|
|
|
|
2013-04-12 07:27:56 -03:00
|
|
|
// control mode specific updates to navigation demands
|
|
|
|
// ---------------------------------------------------
|
2012-08-16 21:50:15 -03:00
|
|
|
update_navigation();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
static void calc_airspeed_errors()
|
|
|
|
{
|
2012-07-15 22:21:50 -03:00
|
|
|
float aspeed_cm = airspeed.get_airspeed_cm();
|
|
|
|
|
2011-12-09 19:40:56 -04:00
|
|
|
// Normal airspeed target
|
2012-08-07 03:05:51 -03:00
|
|
|
target_airspeed_cm = g.airspeed_cruise_cm;
|
2011-12-09 19:40:56 -04:00
|
|
|
|
|
|
|
// FBW_B airspeed target
|
2013-07-13 07:05:53 -03:00
|
|
|
if (control_mode == FLY_BY_WIRE_B ||
|
|
|
|
control_mode == CRUISE) {
|
2013-07-17 22:58:23 -03:00
|
|
|
target_airspeed_cm = ((int32_t)(aparm.airspeed_max -
|
|
|
|
aparm.airspeed_min) *
|
2013-07-10 22:58:40 -03:00
|
|
|
channel_throttle->control_in) +
|
2013-07-17 22:58:23 -03:00
|
|
|
((int32_t)aparm.airspeed_min * 100);
|
2011-12-09 19:40:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Set target to current airspeed + ground speed undershoot,
|
|
|
|
// but only when this is faster than the target airspeed commanded
|
|
|
|
// above.
|
2012-08-07 03:05:51 -03:00
|
|
|
if (control_mode >= FLY_BY_WIRE_B && (g.min_gndspeed_cm > 0)) {
|
|
|
|
int32_t min_gnd_target_airspeed = aspeed_cm + groundspeed_undershoot;
|
|
|
|
if (min_gnd_target_airspeed > target_airspeed_cm)
|
|
|
|
target_airspeed_cm = min_gnd_target_airspeed;
|
2011-12-09 19:40:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Bump up the target airspeed based on throttle nudging
|
2012-08-07 03:05:51 -03:00
|
|
|
if (control_mode >= AUTO && airspeed_nudge_cm > 0) {
|
|
|
|
target_airspeed_cm += airspeed_nudge_cm;
|
2011-12-09 19:40:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Apply airspeed limit
|
2013-07-17 22:58:23 -03:00
|
|
|
if (target_airspeed_cm > (aparm.airspeed_max * 100))
|
|
|
|
target_airspeed_cm = (aparm.airspeed_max * 100);
|
2011-12-09 19:40:56 -04:00
|
|
|
|
2012-08-07 03:05:51 -03:00
|
|
|
airspeed_error_cm = target_airspeed_cm - aspeed_cm;
|
2011-12-09 19:40:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
static void calc_gndspeed_undershoot()
|
|
|
|
{
|
2013-04-27 03:27:37 -03:00
|
|
|
// Use the component of ground speed in the forward direction
|
|
|
|
// This prevents flyaway if wind takes plane backwards
|
2013-03-25 04:25:24 -03:00
|
|
|
if (g_gps && g_gps->status() >= GPS::GPS_OK_FIX_2D) {
|
2013-04-27 03:27:37 -03:00
|
|
|
Vector2f gndVel = ahrs.groundspeed_vector();
|
2013-05-05 02:03:05 -03:00
|
|
|
const Matrix3f &rotMat = ahrs.get_dcm_matrix();
|
2013-04-27 03:27:37 -03:00
|
|
|
Vector2f yawVect = Vector2f(rotMat.a.x,rotMat.b.x);
|
2013-05-05 02:03:05 -03:00
|
|
|
yawVect.normalize();
|
2013-04-27 03:27:37 -03:00
|
|
|
float gndSpdFwd = yawVect * gndVel;
|
|
|
|
groundspeed_undershoot = (g.min_gndspeed_cm > 0) ? (g.min_gndspeed_cm - gndSpdFwd*100) : 0;
|
2012-09-11 00:37:25 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
static void calc_altitude_error()
|
|
|
|
{
|
2013-07-13 07:05:53 -03:00
|
|
|
if (control_mode == FLY_BY_WIRE_B ||
|
|
|
|
control_mode == CRUISE) {
|
2013-06-04 00:34:58 -03:00
|
|
|
return;
|
|
|
|
}
|
2013-07-21 23:49:32 -03:00
|
|
|
if (nav_controller->reached_loiter_target()) {
|
|
|
|
// once we reach a loiter target then lock to the final
|
|
|
|
// altitude target
|
|
|
|
target_altitude_cm = next_WP.alt;
|
|
|
|
} else if (offset_altitude_cm != 0) {
|
2013-07-05 01:56:58 -03:00
|
|
|
// control climb/descent rate
|
2013-02-13 04:32:44 -04:00
|
|
|
target_altitude_cm = next_WP.alt - (offset_altitude_cm*((float)(wp_distance-30) / (float)(wp_totalDistance-30)));
|
2012-08-16 21:50:15 -03:00
|
|
|
|
|
|
|
// stay within a certain range
|
2013-07-05 01:56:58 -03:00
|
|
|
if (prev_WP.alt > next_WP.alt) {
|
2012-12-18 22:36:00 -04:00
|
|
|
target_altitude_cm = constrain_int32(target_altitude_cm, next_WP.alt, prev_WP.alt);
|
2012-08-16 21:50:15 -03:00
|
|
|
}else{
|
2012-12-18 22:36:00 -04:00
|
|
|
target_altitude_cm = constrain_int32(target_altitude_cm, prev_WP.alt, next_WP.alt);
|
2012-08-16 21:50:15 -03:00
|
|
|
}
|
|
|
|
} else if (non_nav_command_ID != MAV_CMD_CONDITION_CHANGE_ALT) {
|
|
|
|
target_altitude_cm = next_WP.alt;
|
|
|
|
}
|
|
|
|
|
2012-09-19 03:22:53 -03:00
|
|
|
altitude_error_cm = target_altitude_cm - adjusted_altitude_cm();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
static void update_loiter()
|
|
|
|
{
|
2013-04-15 08:31:11 -03:00
|
|
|
nav_controller->update_loiter(next_WP, abs(g.loiter_radius), loiter.direction);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2013-07-13 07:05:53 -03:00
|
|
|
/*
|
|
|
|
handle CRUISE mode, locking heading to GPS course when we have
|
|
|
|
sufficient ground speed, and no aileron or rudder input
|
|
|
|
*/
|
|
|
|
static void update_cruise()
|
|
|
|
{
|
|
|
|
if (!cruise_state.locked_heading &&
|
|
|
|
channel_roll->control_in == 0 &&
|
|
|
|
channel_rudder->control_in == 0 &&
|
|
|
|
g_gps && g_gps->status() >= GPS::GPS_OK_FIX_2D &&
|
|
|
|
g_gps->ground_speed_cm >= 300 &&
|
|
|
|
cruise_state.lock_timer_ms == 0) {
|
|
|
|
// user wants to lock the heading - start the timer
|
|
|
|
cruise_state.lock_timer_ms = hal.scheduler->millis();
|
|
|
|
}
|
|
|
|
if (cruise_state.lock_timer_ms != 0 &&
|
|
|
|
(hal.scheduler->millis() - cruise_state.lock_timer_ms) > 500) {
|
|
|
|
// lock the heading after 0.5 seconds of zero heading input
|
|
|
|
// from user
|
|
|
|
cruise_state.locked_heading = true;
|
|
|
|
cruise_state.lock_timer_ms = 0;
|
|
|
|
cruise_state.locked_heading_cd = g_gps->ground_course_cd;
|
|
|
|
prev_WP = current_loc;
|
|
|
|
}
|
|
|
|
if (cruise_state.locked_heading) {
|
|
|
|
next_WP = prev_WP;
|
|
|
|
// always look 1km ahead
|
2013-08-04 21:30:04 -03:00
|
|
|
location_update(next_WP,
|
2013-07-13 07:05:53 -03:00
|
|
|
cruise_state.locked_heading_cd*0.01f,
|
2013-08-04 21:30:04 -03:00
|
|
|
get_distance(prev_WP, current_loc) + 1000);
|
2013-07-13 07:05:53 -03:00
|
|
|
nav_controller->update_waypoint(prev_WP, next_WP);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle speed and height control in FBWB or CRUISE mode.
|
|
|
|
In this mode the elevator is used to change target altitude. The
|
|
|
|
throttle is used to change target airspeed or throttle
|
|
|
|
*/
|
|
|
|
static void update_fbwb_speed_height(void)
|
|
|
|
{
|
|
|
|
static float last_elevator_input;
|
|
|
|
float elevator_input;
|
|
|
|
elevator_input = channel_pitch->control_in / 4500.0f;
|
|
|
|
|
|
|
|
if (g.flybywire_elev_reverse) {
|
|
|
|
elevator_input = -elevator_input;
|
|
|
|
}
|
|
|
|
|
2013-10-11 23:30:27 -03:00
|
|
|
target_altitude_cm += g.flybywire_climb_rate * elevator_input * delta_us_fast_loop * 0.0001f;
|
2013-07-13 07:05:53 -03:00
|
|
|
|
|
|
|
if (elevator_input == 0.0f && last_elevator_input != 0.0f) {
|
|
|
|
// the user has just released the elevator, lock in
|
|
|
|
// the current altitude
|
|
|
|
target_altitude_cm = current_loc.alt;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for FBWB altitude limit
|
|
|
|
if (g.FBWB_min_altitude_cm != 0 && target_altitude_cm < home.alt + g.FBWB_min_altitude_cm) {
|
|
|
|
target_altitude_cm = home.alt + g.FBWB_min_altitude_cm;
|
|
|
|
}
|
|
|
|
altitude_error_cm = target_altitude_cm - adjusted_altitude_cm();
|
|
|
|
|
|
|
|
last_elevator_input = elevator_input;
|
|
|
|
|
|
|
|
calc_throttle();
|
|
|
|
calc_nav_pitch();
|
|
|
|
}
|
|
|
|
|
2013-07-05 01:56:58 -03:00
|
|
|
static void setup_glide_slope(void)
|
|
|
|
{
|
|
|
|
// establish the distance we are travelling to the next waypoint,
|
|
|
|
// for calculating out rate of change of altitude
|
2013-08-04 21:30:04 -03:00
|
|
|
wp_totalDistance = get_distance(current_loc, next_WP);
|
2013-07-05 01:56:58 -03:00
|
|
|
wp_distance = wp_totalDistance;
|
|
|
|
|
|
|
|
/*
|
|
|
|
work out if we will gradually change altitude, or try to get to
|
|
|
|
the new altitude as quickly as possible.
|
|
|
|
*/
|
|
|
|
switch (control_mode) {
|
|
|
|
case RTL:
|
|
|
|
case GUIDED:
|
|
|
|
/* glide down slowly if above target altitude, but ascend more
|
|
|
|
rapidly if below it. See
|
|
|
|
https://github.com/diydrones/ardupilot/issues/39
|
|
|
|
*/
|
|
|
|
if (current_loc.alt > next_WP.alt) {
|
|
|
|
offset_altitude_cm = next_WP.alt - current_loc.alt;
|
|
|
|
} else {
|
|
|
|
offset_altitude_cm = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AUTO:
|
|
|
|
if (prev_WP.id != MAV_CMD_NAV_TAKEOFF &&
|
|
|
|
prev_WP.alt != home.alt &&
|
|
|
|
(next_WP.id == MAV_CMD_NAV_WAYPOINT || next_WP.id == MAV_CMD_NAV_LAND)) {
|
|
|
|
offset_altitude_cm = next_WP.alt - prev_WP.alt;
|
|
|
|
} else {
|
|
|
|
offset_altitude_cm = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
offset_altitude_cm = 0;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2013-07-10 00:40:13 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return relative altitude in meters (relative to home)
|
|
|
|
*/
|
|
|
|
static float relative_altitude(void)
|
|
|
|
{
|
|
|
|
return (current_loc.alt - home.alt) * 0.01f;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return relative altitude in centimeters, absolute value
|
|
|
|
*/
|
|
|
|
static int32_t relative_altitude_abs_cm(void)
|
|
|
|
{
|
|
|
|
return labs(current_loc.alt - home.alt);
|
|
|
|
}
|
|
|
|
|