2014-01-28 04:31:45 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
|
|
|
* control_althold.pde - init and run calls for althold, flight mode
|
|
|
|
*/
|
|
|
|
|
|
|
|
// althold_init - initialise althold controller
|
|
|
|
static bool althold_init(bool ignore_checks)
|
|
|
|
{
|
2014-03-13 14:29:38 -03:00
|
|
|
// initialize vertical speeds and leash lengths
|
|
|
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
2014-04-29 23:17:59 -03:00
|
|
|
pos_control.set_accel_z(g.pilot_accel_z);
|
2014-03-13 14:29:38 -03:00
|
|
|
|
2014-04-30 04:29:32 -03:00
|
|
|
// initialise altitude target to stopping point
|
|
|
|
pos_control.set_target_to_stopping_point_z();
|
|
|
|
|
2014-01-28 04:31:45 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// althold_run - runs the althold controller
|
|
|
|
// should be called at 100hz or more
|
|
|
|
static void althold_run()
|
|
|
|
{
|
2014-12-03 21:25:42 -04:00
|
|
|
float target_roll, target_pitch;
|
2014-01-28 04:31:45 -04:00
|
|
|
float target_yaw_rate;
|
|
|
|
int16_t target_climb_rate;
|
|
|
|
|
|
|
|
// if not auto armed set throttle to zero and exit immediately
|
|
|
|
if(!ap.auto_armed) {
|
2014-06-06 00:04:34 -03:00
|
|
|
attitude_control.relax_bf_rate_controller();
|
2014-06-06 02:45:49 -03:00
|
|
|
attitude_control.set_yaw_target_to_current_heading();
|
2014-01-28 04:31:45 -04:00
|
|
|
attitude_control.set_throttle_out(0, false);
|
2014-08-04 04:56:03 -03:00
|
|
|
pos_control.set_alt_target_to_current_alt();
|
2014-01-28 04:31:45 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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);
|
|
|
|
|
|
|
|
// 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();
|
|
|
|
}
|
|
|
|
|
|
|
|
// reset target lean angles and heading while landed
|
|
|
|
if (ap.land_complete) {
|
2014-06-06 00:04:34 -03:00
|
|
|
attitude_control.relax_bf_rate_controller();
|
2014-06-06 02:45:49 -03:00
|
|
|
attitude_control.set_yaw_target_to_current_heading();
|
2014-07-17 06:18:10 -03:00
|
|
|
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
|
|
|
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
2014-08-04 04:56:03 -03:00
|
|
|
pos_control.set_alt_target_to_current_alt();
|
2014-01-28 04:31:45 -04:00
|
|
|
}else{
|
|
|
|
// call attitude controller
|
2014-02-19 07:52:00 -04:00
|
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
2014-01-28 04:31:45 -04:00
|
|
|
// body-frame rate controller is run directly from 100hz loop
|
|
|
|
|
|
|
|
// call throttle 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-28 04:31:45 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// call position controller
|
|
|
|
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
|
|
|
|
pos_control.update_z_controller();
|
|
|
|
}
|
|
|
|
}
|