ardupilot/ArduCopterMega/flight_control.pde

119 lines
2.5 KiB
Plaintext

/*************************************************************
throttle control
****************************************************************/
// user input:
// -----------
void output_manual_throttle()
{
rc_3.servo_out = rc_3.control_in;
rc_3.servo_out = (float)rc_3.servo_out * angle_boost();
}
// Autopilot
// ---------
void output_auto_throttle()
{
rc_3.servo_out = (float)nav_throttle * angle_boost();
rc_3.servo_out = max(rc_3.servo_out, 1);
}
void calc_nav_throttle()
{
long err = constrain (altitude_error, -150, 150); //+-1.5 meters
long temp = pid_throttle.get_pid(err, deltaMiliSeconds, 1.0);
nav_throttle = (float)(throttle_cruise + temp) * angle_boost();
}
float angle_boost()
{
//static byte flipper;
float temp = 1 / (cos(dcm.roll) * cos(dcm.pitch));
//temp *= .5;
if(temp > 1.2)
temp = 1.2;
return temp;
}
/*************************************************************
yaw control
****************************************************************/
void output_manual_yaw()
{
if(rc_3.control_in == 0){
clear_yaw_control();
} else {
// Yaw control
if(rc_4.control_in == 0){
//clear_yaw_control();
output_yaw_with_hold(true); // hold yaw
}else{
output_yaw_with_hold(false); // rate control yaw
}
}
}
void auto_yaw()
{
output_yaw_with_hold(true); // hold yaw
}
/*************************************************************
picth and roll control
****************************************************************/
// how hard to tilt towards the target
// -----------------------------------
void calc_nav_pid()
{
nav_angle = pid_nav.get_pid(wp_distance * 100, dTnav, 1.0);
nav_angle = constrain(nav_angle, -pitch_max, pitch_max);
}
// distribute the pitch angle based on our orientation
// ---------------------------------------------------
void calc_nav_pitch()
{
long b_err = bearing_error;
bool rev = false;
float roll_out;
if(b_err > 18000){
b_err -= 18000;
rev = true;
}
roll_out = abs(b_err - 18000);
roll_out = (9000.0 - roll_out) / 9000.0;
roll_out = (rev) ? roll_out : -roll_out;
nav_pitch = (float)nav_angle * roll_out;
}
// distribute the roll angle based on our orientation
// --------------------------------------------------
void calc_nav_roll()
{
long b_err = bearing_error;
bool rev = false;
float roll_out;
if(b_err > 18000){
b_err -= 18000;
rev = true;
}
roll_out = abs(b_err - 9000);
roll_out = (9000.0 - roll_out) / 9000.0;
roll_out = (rev) ? -roll_out : roll_out;
nav_roll = (float)nav_angle * roll_out;
}