ardupilot/ArduCopter/control_stabilize.cpp

64 lines
2.3 KiB
C++
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 -*-
#include "Copter.h"
/*
* control_stabilize.pde - init and run calls for stabilize flight mode
*/
// stabilize_init - initialise stabilize controller
bool Copter::stabilize_init(bool ignore_checks)
{
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (get_pilot_desired_throttle(channel_throttle->control_in) > get_non_takeoff_throttle())) {
return false;
}
// set target altitude to zero for reporting
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
void Copter::stabilize_run()
2013-12-06 02:08:11 -04:00
{
float target_roll, target_pitch;
float target_yaw_rate;
float pilot_throttle_scaled;
// if not armed set throttle to zero and exit immediately
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed
if (ap.land_complete) {
motors.slow_start(true);
}
return;
}
2013-12-06 02:08:11 -04:00
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
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(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
2013-12-06 02:08:11 -04:00
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
2013-12-06 02:08:11 -04:00
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in);
2013-12-06 02:08:11 -04:00
// call attitude controller
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
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, g.throttle_filt);
2013-12-06 02:08:11 -04:00
}