ardupilot/ArduCopter/control_stabilize.pde

342 lines
11 KiB
Plaintext
Raw Normal View History

2013-12-06 02:08:11 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// acro_init - initialise acro controller
static bool acro_init(bool ignore_checks)
{
return true;
}
2013-12-06 02:08:11 -04:00
// acro_run - runs the acro controller
// should be called at 100hz or more
static void acro_run()
{
2013-12-06 09:29:00 -04:00
Vector3f rate_target; // for roll, pitch, yaw body-frame rate targets
// convert the input to the desired body frame rate
rate_target.x = g.rc_1.control_in * g.acro_rp_p;
rate_target.y = g.rc_2.control_in * g.acro_rp_p;
rate_target.z = g.rc_4.control_in * g.acro_yaw_p;
// To-Do: handle acro trainer here?
// To-Do: handle helicopter
acro_level_mix = constrain_float(1-max(max(abs(g.rc_1.control_in), abs(g.rc_2.control_in)), abs(g.rc_4.control_in))/4500.0, 0, 1)*cos_pitch_x;
// set targets for body frame rate controller
attitude_control.rate_stab_bf_targets(rate_target);
// convert stabilize rates to regular rates
attitude_control.rate_stab_bf_to_rate_bf_roll();
attitude_control.rate_stab_bf_to_rate_bf_pitch();
attitude_control.rate_stab_bf_to_rate_bf_yaw();
// pilot controlled yaw using rate controller
//get_yaw_rate_stabilized_bf(pilot_yaw);
2013-12-06 09:29:00 -04:00
// call get_acro_level_rates() here?
// To-Do: convert body-frame stabilized angles to earth frame angles and update controll_roll, pitch and yaw?
// body-frame rate controller is run directly from 100hz loop
2013-12-06 02:08:11 -04:00
}
// stabilize_init - initialise stabilize controller
static bool stabilize_init(bool ignore_checks)
{
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control.set_alt_target(0);
return true;
}
2013-12-06 02:08:11 -04:00
// stabilize_run - runs the main stabilize controller
// should be called at 100hz or more
static void stabilize_run()
{
int16_t target_roll, target_pitch;
float target_yaw_rate;
int16_t pilot_throttle_scaled;
// if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || g.rc_3.control_in <= 0) {
attitude_control.init_targets();
attitude_control.set_throttle_out(0, false);
return;
}
2013-12-06 02:08:11 -04:00
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// convert pilot input to 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);
2013-12-06 02:08:11 -04:00
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
2013-12-06 02:08:11 -04:00
// reset target lean angles and heading while landed
if (ap.land_complete) {
attitude_control.init_targets();
}else{
// call attitude controller
attitude_control.angleef_rp_rateef_y(target_roll, target_pitch, target_yaw_rate);
2013-12-06 02:08:11 -04:00
// body-frame rate controller is run directly from 100hz loop
}
2013-12-06 02:08:11 -04:00
// output pilot's throttle
attitude_control.set_throttle_out(pilot_throttle_scaled, true);
2013-12-06 02:08:11 -04:00
// 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;
// update estimate of throttle cruise
#if FRAME_CONFIG == HELI_FRAME
update_throttle_cruise(motors.get_collective_out());
#else
update_throttle_cruise(pilot_throttle_scaled);
#endif //HELI_FRAME
// update take-off complete flag
if (!ap.takeoff_complete) {
if (pilot_throttle_scaled > g.throttle_cruise) {
// we must be in the air by now
set_takeoff_complete(true);
}
}
2013-12-06 02:08:11 -04:00
}
// althold_init - initialise althold controller
static bool althold_init(bool ignore_checks)
{
2013-12-30 09:13:27 -04:00
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}
2013-12-06 02:08:11 -04:00
// althold_run - runs the althold controller
// should be called at 100hz or more
static void althold_run()
{
2013-12-29 09:08:29 -04:00
int16_t target_roll, target_pitch;
float target_yaw_rate;
2013-12-29 09:08:29 -04:00
int16_t target_climb_rate;
// if not auto armed set throttle to zero and exit immediately
2013-12-30 09:13:27 -04:00
if(!ap.auto_armed) {
// To-Do: reset altitude target if we're somehow not landed?
attitude_control.init_targets();
2013-12-29 09:08:29 -04:00
attitude_control.set_throttle_out(0, false);
return;
}
2013-12-29 09:08:29 -04:00
// 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);
2013-12-29 09:08:29 -04:00
// 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();
2013-12-29 09:08:29 -04:00
}
// reset target lean angles and heading while landed
2013-12-29 09:08:29 -04:00
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
2013-12-29 09:08:29 -04:00
// call throttle controller
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
2013-12-29 09:08:29 -04:00
// if sonar is ok, use surface tracking
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, G_Dt);
2013-12-29 09:08:29 -04:00
}
// call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
pos_control.update_z_controller();
2013-12-29 09:08:29 -04:00
}
// 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;
2013-12-06 02:08:11 -04:00
}
// circle_init - initialise circle controller
static bool circle_init(bool ignore_checks)
{
if (GPS_ok() || ignore_checks) {
return true;
}else{
return false;
}
// set yaw to point to center of circle
// yaw_look_at_WP = circle_center;
// initialise bearing to current heading
//yaw_look_at_WP_bearing = ahrs.yaw_sensor;
//yaw_initialised = true;
}
2013-12-06 02:08:11 -04:00
// circle_run - runs the circle controller
// should be called at 100hz or more
static void circle_run()
{
// if we are landed reset yaw target to current heading
//if (ap.land_complete) {
// control_yaw = ahrs.yaw_sensor;
//}
// points toward the center of the circle or does a panorama
//get_circle_yaw();
2013-12-06 02:08:11 -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();
return true;
}else{
return false;
}
}
2013-12-06 02:08:11 -04:00
// 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;
2013-12-06 02:08:11 -04:00
}
// ofloiter_init - initialise ofloiter controller
static bool ofloiter_init(bool ignore_checks)
{
if (g.optflow_enabled || ignore_checks) {
return true;
}else{
return false;
}
}
2013-12-06 02:08:11 -04:00
// 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)
{
return true;
}
2013-12-06 02:08:11 -04:00
// drift_run - runs the drift controller
// should be called at 100hz or more
static void drift_run()
{
// if we have landed reset yaw target to current heading
//if (ap.land_complete) {
// control_yaw = ahrs.yaw_sensor;
//}
//get_yaw_drift();
2013-12-06 02:08:11 -04:00
}
// sport_init - initialise sport controller
static bool sport_init(bool ignore_checks)
{
return true;
}
2013-12-06 02:08:11 -04:00
// sport_run - runs the sport controller
// should be called at 100hz or more
static void sport_run()
{
}