2014-01-24 02:47:42 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
2014-01-29 00:35:16 -04:00
|
|
|
* control_loiter.pde - init and run calls for loiter flight mode
|
2014-01-24 02:47:42 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
// 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();
|
2014-01-24 03:23:56 -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;
|
|
|
|
}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
|
2014-02-03 03:23:42 -04:00
|
|
|
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
2014-01-24 02:47:42 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// 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;
|
|
|
|
}
|