ardupilot/ArduPlane/commands.cpp

155 lines
4.6 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2012-02-13 17:53:54 -04:00
/*
2012-08-21 23:19:51 -03:00
* logic for dealing with the current command in the mission and home location
2012-02-13 17:53:54 -04:00
*/
2015-05-13 03:09:36 -03:00
#include "Plane.h"
/*
2014-03-17 04:45:45 -03:00
* set_next_WP - sets the target location the vehicle should fly to
2012-08-21 23:19:51 -03:00
*/
2015-05-13 03:09:36 -03:00
void Plane::set_next_WP(const struct Location &loc)
{
if (auto_state.next_wp_no_crosstrack) {
// we should not try to cross-track for this waypoint
prev_WP_loc = current_loc;
// use cross-track for the next waypoint
auto_state.next_wp_no_crosstrack = false;
auto_state.no_crosstrack = true;
} else {
// copy the current WP into the OldWP slot
prev_WP_loc = next_WP_loc;
auto_state.no_crosstrack = false;
}
2012-08-21 23:19:51 -03:00
// Load the next_WP slot
// ---------------------
2014-03-17 04:45:45 -03:00
next_WP_loc = loc;
// if lat and lon is zero, then use current lat/lon
// this allows a mission to contain a "loiter on the spot"
// command
if (next_WP_loc.lat == 0 && next_WP_loc.lng == 0) {
next_WP_loc.lat = current_loc.lat;
next_WP_loc.lng = current_loc.lng;
// additionally treat zero altitude as current altitude
if (next_WP_loc.alt == 0) {
next_WP_loc.alt = current_loc.alt;
next_WP_loc.flags.relative_alt = false;
next_WP_loc.flags.terrain_alt = false;
}
}
2014-03-04 00:54:46 -04:00
// convert relative alt to absolute alt
if (next_WP_loc.flags.relative_alt) {
next_WP_loc.flags.relative_alt = false;
next_WP_loc.alt += home.alt;
2014-03-04 00:54:46 -04:00
}
// are we already past the waypoint? This happens when we jump
// waypoints, and it can cause us to skip a waypoint. If we are
// past the waypoint when we start on a leg, then use the current
// location as the previous waypoint, to prevent immediately
// considering the waypoint complete
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
2015-11-18 15:17:50 -04:00
gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting previous waypoint");
prev_WP_loc = current_loc;
}
2012-08-21 23:19:51 -03:00
// used to control FBW and limit the rate of climb
// -----------------------------------------------
set_target_altitude_location(next_WP_loc);
2012-08-21 23:19:51 -03:00
// zero out our loiter vals to watch for missed waypoints
loiter_angle_reset();
2012-08-21 23:19:51 -03:00
setup_glide_slope();
setup_turn_angle();
2012-08-21 23:19:51 -03:00
loiter_angle_reset();
}
2015-05-13 03:09:36 -03:00
void Plane::set_guided_WP(void)
{
if (g.loiter_radius < 0 || guided_WP_loc.flags.loiter_ccw) {
loiter.direction = -1;
} else {
loiter.direction = 1;
}
2012-08-21 23:19:51 -03:00
// copy the current location into the OldWP slot
// ---------------------------------------
prev_WP_loc = current_loc;
2012-08-21 23:19:51 -03:00
// Load the next_WP slot
// ---------------------
next_WP_loc = guided_WP_loc;
2012-08-21 23:19:51 -03:00
// used to control FBW and limit the rate of climb
// -----------------------------------------------
set_target_altitude_current();
2012-08-21 23:19:51 -03:00
update_flight_stage();
setup_glide_slope();
setup_turn_angle();
2012-08-21 23:19:51 -03:00
// reset loiter start time.
loiter.start_time_ms = 0;
// start in non-VTOL mode
auto_state.vtol_loiter = false;
loiter_angle_reset();
}
// run this at setup on the ground
// -------------------------------
2015-05-13 03:09:36 -03:00
void Plane::init_home()
{
2015-11-18 15:17:50 -04:00
gcs_send_text(MAV_SEVERITY_INFO, "Init HOME");
2014-03-28 16:52:48 -03:00
ahrs.set_home(gps.location());
home_is_set = HOME_SET_NOT_LOCKED;
2015-07-05 23:01:17 -03:00
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location());
2015-11-18 15:17:50 -04:00
gcs_send_text_fmt(MAV_SEVERITY_INFO, "GPS alt: %lu", (unsigned long)home.alt);
2014-03-03 09:50:45 -04:00
// Save Home to EEPROM
mission.write_home_to_storage();
2012-08-21 23:19:51 -03:00
// Save prev loc
// -------------
next_WP_loc = prev_WP_loc = home;
}
/*
update home location from GPS
this is called as long as we have 3D lock and the arming switch is
not pushed
*/
2015-05-13 03:09:36 -03:00
void Plane::update_home()
{
if (fabsf(barometer.get_altitude()) > 2) {
// don't auto-update if we have changed barometer altitude
// significantly. This allows us to cope with slow baro drift
// but not re-do home and the baro if we have changed height
// significantly
return;
}
if (home_is_set == HOME_SET_NOT_LOCKED) {
Location loc = gps.location();
Location origin;
// if an EKF origin is available then we leave home equal to
// the height of that origin. This ensures that our relative
// height calculations are using the same origin
if (ahrs.get_origin(origin)) {
loc.alt = origin.alt;
}
ahrs.set_home(loc);
2015-07-05 23:01:17 -03:00
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location());
}
barometer.update_calibration();
}