Copter: split control_stabilize into land, rtl, loiter
This commit is contained in:
parent
171203370f
commit
e27f4c1c13
130
ArduCopter/control_land.pde
Normal file
130
ArduCopter/control_land.pde
Normal file
@ -0,0 +1,130 @@
|
||||
/// -*- 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) {
|
||||
// set target to current position
|
||||
wp_nav.init_loiter_target();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// land_run - runs the land controller
|
||||
// should be called at 100hz or more
|
||||
static void land_run()
|
||||
{
|
||||
int16_t target_roll, target_pitch;
|
||||
float target_yaw_rate;
|
||||
float target_climb_rate;
|
||||
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed) {
|
||||
// To-Do: reset altitude target if we're somehow not landed?
|
||||
attitude_control.init_targets();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// disarming detector
|
||||
#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();
|
||||
return;
|
||||
}
|
||||
#else
|
||||
// disarm when the landing detector says we've landed
|
||||
if (ap.land_complete) {
|
||||
init_disarm_motors();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// get pilot desired lean angles
|
||||
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
|
||||
// reset target lean angles and heading while landed
|
||||
if (ap.land_complete) {
|
||||
attitude_control.init_targets();
|
||||
// move throttle to minimum to keep us on the ground
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
}else{
|
||||
// call attitude controller
|
||||
attitude_control.angleef_rp_rateef_y(target_roll, target_pitch, target_yaw_rate);
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// call landing throttle controller
|
||||
target_climb_rate = get_throttle_land();
|
||||
|
||||
// call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
|
||||
pos_control.update_z_controller();
|
||||
}
|
||||
|
||||
// refetch angle targets for reporting
|
||||
const Vector3f angle_target = attitude_control.angle_ef_targets();
|
||||
control_roll = angle_target.x;
|
||||
control_pitch = angle_target.y;
|
||||
control_yaw = angle_target.z;
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
104
ArduCopter/control_loiter.pde
Normal file
104
ArduCopter/control_loiter.pde
Normal file
@ -0,0 +1,104 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
* control_loiter.pde - init and run calls for loiter and of_loiter (aka optical flow loiter) flight modes
|
||||
*/
|
||||
|
||||
// loiter_init - initialise loiter controller
|
||||
static bool loiter_init(bool ignore_checks)
|
||||
{
|
||||
if (GPS_ok() || ignore_checks) {
|
||||
// set target to current position
|
||||
wp_nav.init_loiter_target();
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// loiter_run - runs the loiter controller
|
||||
// should be called at 100hz or more
|
||||
static void loiter_run()
|
||||
{
|
||||
float target_yaw_rate = 0;
|
||||
float target_climb_rate = 0;
|
||||
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || !inertial_nav.position_ok()) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.init_targets();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// process pilot inputs
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
// To-Do: do we need to clear out feed forward if this is not called?
|
||||
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
|
||||
// get pilot desired climb rate
|
||||
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
|
||||
|
||||
// check for pilot requested take-off
|
||||
if (ap.land_complete && target_climb_rate > 0) {
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
}
|
||||
|
||||
// when landed reset targets and output zero throttle
|
||||
if (ap.land_complete) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.init_targets();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
}else{
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angleef_rp_rateef_y(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate,G_Dt);
|
||||
}
|
||||
|
||||
// update altitude target and call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
|
||||
pos_control.update_z_controller();
|
||||
}
|
||||
|
||||
// refetch angle targets for reporting
|
||||
const Vector3f angle_target = attitude_control.angle_ef_targets();
|
||||
control_roll = angle_target.x;
|
||||
control_pitch = angle_target.y;
|
||||
control_yaw = angle_target.z;
|
||||
}
|
||||
|
||||
// ofloiter_init - initialise ofloiter controller
|
||||
static bool ofloiter_init(bool ignore_checks)
|
||||
{
|
||||
if (g.optflow_enabled || ignore_checks) {
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// ofloiter_run - runs the optical flow loiter controller
|
||||
// should be called at 100hz or more
|
||||
static void ofloiter_run()
|
||||
{
|
||||
}
|
24
ArduCopter/control_rtl.pde
Normal file
24
ArduCopter/control_rtl.pde
Normal file
@ -0,0 +1,24 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
* control_rtl.pde - init and run calls for RTL flight mode
|
||||
*/
|
||||
|
||||
// rtl_init - initialise rtl controller
|
||||
static bool rtl_init(bool ignore_checks)
|
||||
{
|
||||
if (GPS_ok() || ignore_checks) {
|
||||
do_RTL();
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// rtl_run - runs the return-to-launch controller
|
||||
// should be called at 100hz or more
|
||||
static void rtl_run()
|
||||
{
|
||||
verify_RTL();
|
||||
}
|
||||
|
@ -1,5 +1,9 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
* control_stabilize.pde - init and run calls for acro, stabilize, althold, drift and sport flight modes
|
||||
*/
|
||||
|
||||
// acro_init - initialise acro controller
|
||||
static bool acro_init(bool ignore_checks)
|
||||
{
|
||||
@ -212,105 +216,6 @@ static void circle_run()
|
||||
//get_circle_yaw();
|
||||
}
|
||||
|
||||
// loiter_init - initialise loiter controller
|
||||
static bool loiter_init(bool ignore_checks)
|
||||
{
|
||||
if (GPS_ok() || ignore_checks) {
|
||||
// set target to current position
|
||||
wp_nav.init_loiter_target();
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// loiter_run - runs the loiter controller
|
||||
// should be called at 100hz or more
|
||||
static void loiter_run()
|
||||
{
|
||||
float target_yaw_rate = 0;
|
||||
float target_climb_rate = 0;
|
||||
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || !inertial_nav.position_ok()) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.init_targets();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// process pilot inputs
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
// To-Do: do we need to clear out feed forward if this is not called?
|
||||
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
|
||||
// get pilot desired climb rate
|
||||
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
|
||||
|
||||
// check for pilot requested take-off
|
||||
if (ap.land_complete && target_climb_rate > 0) {
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
}
|
||||
|
||||
// when landed reset targets and output zero throttle
|
||||
if (ap.land_complete) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.init_targets();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
}else{
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angleef_rp_rateef_y(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate,G_Dt);
|
||||
}
|
||||
|
||||
// update altitude target and call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
|
||||
pos_control.update_z_controller();
|
||||
}
|
||||
|
||||
// refetch angle targets for reporting
|
||||
const Vector3f angle_target = attitude_control.angle_ef_targets();
|
||||
control_roll = angle_target.x;
|
||||
control_pitch = angle_target.y;
|
||||
control_yaw = angle_target.z;
|
||||
}
|
||||
|
||||
// ofloiter_init - initialise ofloiter controller
|
||||
static bool ofloiter_init(bool ignore_checks)
|
||||
{
|
||||
if (g.optflow_enabled || ignore_checks) {
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// ofloiter_run - runs the optical flow loiter controller
|
||||
// should be called at 100hz or more
|
||||
static void ofloiter_run()
|
||||
{
|
||||
}
|
||||
|
||||
// drift_init - initialise drift controller
|
||||
static bool drift_init(bool ignore_checks)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user