2014-01-24 02:47:42 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
// counter to verify landings
|
|
|
|
static uint16_t land_detector;
|
|
|
|
static bool land_with_gps;
|
|
|
|
|
|
|
|
// land_init - initialise land controller
|
|
|
|
static bool land_init(bool ignore_checks)
|
|
|
|
{
|
|
|
|
// check if we have GPS and decide which LAND we're going to do
|
|
|
|
land_with_gps = GPS_ok();
|
|
|
|
if (land_with_gps) {
|
2014-01-25 00:41:17 -04:00
|
|
|
// set target to stopping point
|
|
|
|
Vector3f stopping_point;
|
|
|
|
wp_nav.get_loiter_stopping_point_xy(stopping_point);
|
|
|
|
wp_nav.set_loiter_target(stopping_point);
|
2014-01-24 02:47:42 -04:00
|
|
|
}
|
2014-01-24 03:23:33 -04:00
|
|
|
// initialise altitude target to stopping point
|
|
|
|
pos_control.set_target_to_stopping_point_z();
|
2014-01-24 02:47:42 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// land_run - runs the land controller
|
|
|
|
// should be called at 100hz or more
|
|
|
|
static void land_run()
|
|
|
|
{
|
2014-01-24 03:23:33 -04:00
|
|
|
if (land_with_gps) {
|
|
|
|
land_gps_run();
|
|
|
|
}else{
|
|
|
|
land_nogps_run();
|
|
|
|
}
|
|
|
|
}
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// land_run - runs the land controller
|
|
|
|
// horizontal position controlled with loiter controller
|
|
|
|
// should be called at 100hz or more
|
|
|
|
static void land_gps_run()
|
|
|
|
{
|
|
|
|
int16_t roll_control = 0, pitch_control = 0;
|
|
|
|
float target_yaw_rate = 0;
|
|
|
|
|
|
|
|
// if not auto armed or landed set throttle to zero and exit immediately
|
|
|
|
if(!ap.auto_armed || ap.land_complete) {
|
2014-01-24 02:47:42 -04:00
|
|
|
attitude_control.init_targets();
|
|
|
|
attitude_control.set_throttle_out(0, false);
|
2014-01-24 03:23:33 -04:00
|
|
|
wp_nav.init_loiter_target();
|
2014-01-24 02:47:42 -04:00
|
|
|
|
|
|
|
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
|
2014-01-24 03:23:33 -04:00
|
|
|
// disarm when the landing detector says we've landed and throttle is at minimum
|
|
|
|
if (ap.land_complete && (g.rc_3.control_in == 0 || failsafe.radio)) {
|
|
|
|
init_disarm_motors();
|
|
|
|
}
|
2014-01-24 02:47:42 -04:00
|
|
|
#else
|
2014-01-24 03:23:33 -04:00
|
|
|
// disarm when the landing detector says we've landed
|
|
|
|
if (ap.land_complete) {
|
|
|
|
init_disarm_motors();
|
|
|
|
}
|
|
|
|
#endif
|
2014-01-24 02:47:42 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// process pilot inputs
|
|
|
|
if (!failsafe.radio) {
|
|
|
|
// apply SIMPLE mode transform to pilot inputs
|
|
|
|
update_simple_mode();
|
|
|
|
|
|
|
|
// process pilot's roll and pitch input
|
|
|
|
roll_control = g.rc_1.control_in;
|
|
|
|
pitch_control = g.rc_2.control_in;
|
|
|
|
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
|
|
|
}
|
|
|
|
|
|
|
|
// process roll, pitch inputs
|
|
|
|
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// run loiter controller
|
|
|
|
wp_nav.update_loiter();
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// call attitude controller
|
|
|
|
attitude_control.angleef_rp_rateef_y(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// update altitude target and call position controller
|
|
|
|
pos_control.set_alt_target_from_climb_rate(get_throttle_land(), G_Dt);
|
|
|
|
pos_control.update_z_controller();
|
|
|
|
}
|
|
|
|
|
|
|
|
// land_nogps_run - runs the land controller
|
|
|
|
// pilot controls roll and pitch angles
|
|
|
|
// should be called at 100hz or more
|
|
|
|
static void land_nogps_run()
|
|
|
|
{
|
|
|
|
int16_t target_roll = 0, target_pitch = 0;
|
|
|
|
float target_yaw_rate = 0;
|
|
|
|
|
|
|
|
// if not auto armed or landed set throttle to zero and exit immediately
|
|
|
|
if(!ap.auto_armed || ap.land_complete) {
|
2014-01-24 02:47:42 -04:00
|
|
|
attitude_control.init_targets();
|
|
|
|
attitude_control.set_throttle_out(0, false);
|
2014-01-24 03:23:33 -04:00
|
|
|
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
|
|
|
|
// disarm when the landing detector says we've landed and throttle is at minimum
|
|
|
|
if (ap.land_complete && (g.rc_3.control_in == 0 || failsafe.radio)) {
|
|
|
|
init_disarm_motors();
|
|
|
|
}
|
|
|
|
#else
|
|
|
|
// disarm when the landing detector says we've landed
|
|
|
|
if (ap.land_complete) {
|
|
|
|
init_disarm_motors();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// process pilot inputs
|
|
|
|
if (!failsafe.radio) {
|
|
|
|
// apply SIMPLE mode transform to pilot inputs
|
|
|
|
update_simple_mode();
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// get pilot desired lean angles
|
|
|
|
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// get pilot's desired yaw rate
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
2014-01-24 02:47:42 -04:00
|
|
|
}
|
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// call attitude controller
|
|
|
|
attitude_control.angleef_rp_rateef_y(target_roll, target_pitch, target_yaw_rate);
|
|
|
|
|
|
|
|
// call position controller
|
|
|
|
pos_control.set_alt_target_from_climb_rate(get_throttle_land(), G_Dt);
|
|
|
|
pos_control.update_z_controller();
|
2014-01-24 02:47:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// get_throttle_land - high level landing logic
|
|
|
|
// returns climb rate (in cm/s) which should be passed to the position controller
|
|
|
|
// should be called at 100hz or higher
|
|
|
|
static float get_throttle_land()
|
|
|
|
{
|
|
|
|
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
|
|
|
if (current_loc.alt >= LAND_START_ALT && !(g.sonar_enabled && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
|
|
|
return pos_control.get_speed_down();
|
|
|
|
}else{
|
|
|
|
return -abs(g.land_speed);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// reset_land_detector - initialises land detector
|
|
|
|
static void reset_land_detector()
|
|
|
|
{
|
|
|
|
set_land_complete(false);
|
|
|
|
land_detector = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// update_land_detector - checks if we have landed and updates the ap.land_complete flag
|
|
|
|
// returns true if we have landed
|
|
|
|
static bool update_land_detector()
|
|
|
|
{
|
|
|
|
// detect whether we have landed by watching for low climb rate and minimum throttle
|
|
|
|
if (abs(climb_rate) < 20 && motors.limit.throttle_lower) {
|
|
|
|
if (!ap.land_complete) {
|
|
|
|
// run throttle controller if accel based throttle controller is enabled and active (active means it has been given a target)
|
|
|
|
if( land_detector < LAND_DETECTOR_TRIGGER) {
|
|
|
|
land_detector++;
|
|
|
|
}else{
|
|
|
|
set_land_complete(true);
|
|
|
|
land_detector = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}else{
|
|
|
|
// we've sensed movement up or down so reset land_detector
|
|
|
|
land_detector = 0;
|
|
|
|
if(ap.land_complete) {
|
|
|
|
set_land_complete(false);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// return current state of landing
|
|
|
|
return ap.land_complete;
|
|
|
|
}
|