ardupilot/libraries/SITL/SIM_Plane.cpp

241 lines
7.9 KiB
C++

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
very simple plane simulator class. Not aerodynamically accurate,
just enough to be able to debug control logic for new frame types
*/
#include "SIM_Plane.h"
#include <stdio.h>
using namespace SITL;
Plane::Plane(const char *home_str, const char *frame_str) :
Aircraft(home_str, frame_str)
{
mass = 1.0f;
/*
scaling from motor power to Newtons. Allows the plane to hold
vertically against gravity when the motor is at hover_throttle
*/
thrust_scale = (mass * GRAVITY_MSS) / hover_throttle;
frame_height = 0.1f;
if (strstr(frame_str, "-revthrust")) {
reverse_thrust = true;
}
}
/*
the following functions are from last_letter
https://github.com/Georacer/last_letter/blob/master/last_letter/src/aerodynamicsLib.cpp
many thanks to Georacer!
*/
float Plane::liftCoeff(float alpha) const
{
const float alpha0 = coefficient.alpha_stall;
const float M = coefficient.mcoeff;
const float c_lift_0 = coefficient.c_lift_0;
const float c_lift_a0 = coefficient.c_lift_a;
double sigmoid = ( 1+exp(-M*(alpha-alpha0))+exp(M*(alpha+alpha0)) ) / (1+exp(-M*(alpha-alpha0))) / (1+exp(M*(alpha+alpha0)));
double linear = (1.0-sigmoid) * (c_lift_0 + c_lift_a0*alpha); //Lift at small AoA
double flatPlate = sigmoid*(2*copysign(1,alpha)*pow(sin(alpha),2)*cos(alpha)); //Lift beyond stall
float result = linear+flatPlate;
return result;
}
float Plane::dragCoeff(float alpha) const
{
const float b = coefficient.b;
const float s = coefficient.s;
const float c_drag_p = coefficient.c_drag_p;
const float c_lift_0 = coefficient.c_lift_0;
const float c_lift_a0 = coefficient.c_lift_a;
const float oswald = coefficient.oswald;
double AR = pow(b,2)/s;
double c_drag_a = c_drag_p + pow(c_lift_0+c_lift_a0*alpha,2)/(M_PI*oswald*AR);
return c_drag_a;
}
// Torque calculation function
Vector3f Plane::getTorque(float inputAileron, float inputElevator, float inputRudder, const Vector3f &force) const
{
const float alpha = angle_of_attack;
const float s = coefficient.s;
const float c = coefficient.c;
const float b = coefficient.b;
const float c_l_0 = coefficient.c_l_0;
const float c_l_b = coefficient.c_l_b;
const float c_l_p = coefficient.c_l_p;
const float c_l_r = coefficient.c_l_r;
const float c_l_deltaa = coefficient.c_l_deltaa;
const float c_l_deltar = coefficient.c_l_deltar;
const float c_m_0 = coefficient.c_m_0;
const float c_m_a = coefficient.c_m_a;
const float c_m_q = coefficient.c_m_q;
const float c_m_deltae = coefficient.c_m_deltae;
const float c_n_0 = coefficient.c_n_0;
const float c_n_b = coefficient.c_n_b;
const float c_n_p = coefficient.c_n_p;
const float c_n_r = coefficient.c_n_r;
const float c_n_deltaa = coefficient.c_n_deltaa;
const float c_n_deltar = coefficient.c_n_deltar;
const Vector3f &CGOffset = coefficient.CGOffset;
float rho = air_density;
//read angular rates
double p = gyro.x;
double q = gyro.y;
double r = gyro.z;
//calculate aerodynamic torque
double qbar = 1.0/2.0*rho*pow(airspeed,2)*s; //Calculate dynamic pressure
double la, na, ma;
if (is_zero(airspeed))
{
la = 0;
ma = 0;
na = 0;
}
else
{
la = qbar*b*(c_l_0 + c_l_b*beta + c_l_p*b*p/(2*airspeed) + c_l_r*b*r/(2*airspeed) + c_l_deltaa*inputAileron + c_l_deltar*inputRudder);
ma = qbar*c*(c_m_0 + c_m_a*alpha + c_m_q*c*q/(2*airspeed) + c_m_deltae*inputElevator);
na = qbar*b*(c_n_0 + c_n_b*beta + c_n_p*b*p/(2*airspeed) + c_n_r*b*r/(2*airspeed) + c_n_deltaa*inputAileron + c_n_deltar*inputRudder);
}
// Add torque to to force misalignment with CG
// r x F, where r is the distance from CoG to CoL
la += CGOffset.y * force.z - CGOffset.z * force.y;
ma += -CGOffset.x * force.z + CGOffset.z * force.x;
na += -CGOffset.y * force.x + CGOffset.x * force.y;
return Vector3f(la, ma, na);
}
// Force calculation function from last_letter
Vector3f Plane::getForce(float inputAileron, float inputElevator, float inputRudder) const
{
const float alpha = angle_of_attack;
const float c_drag_q = coefficient.c_drag_q;
const float c_lift_q = coefficient.c_lift_q;
const float s = coefficient.s;
const float c = coefficient.c;
const float b = coefficient.b;
const float c_drag_deltae = coefficient.c_drag_deltae;
const float c_lift_deltae = coefficient.c_lift_deltae;
const float c_y_0 = coefficient.c_y_0;
const float c_y_b = coefficient.c_y_b;
const float c_y_p = coefficient.c_y_p;
const float c_y_r = coefficient.c_y_r;
const float c_y_deltaa = coefficient.c_y_deltaa;
const float c_y_deltar = coefficient.c_y_deltar;
float rho = air_density;
//request lift and drag alpha-coefficients from the corresponding functions
double c_lift_a = liftCoeff(alpha);
double c_drag_a = dragCoeff(alpha);
//convert coefficients to the body frame
double c_x_a = -c_drag_a*cos(alpha)+c_lift_a*sin(alpha);
double c_x_q = -c_drag_q*cos(alpha)+c_lift_q*sin(alpha);
double c_z_a = -c_drag_a*sin(alpha)-c_lift_a*cos(alpha);
double c_z_q = -c_drag_q*sin(alpha)-c_lift_q*cos(alpha);
//read angular rates
double p = gyro.x;
double q = gyro.y;
double r = gyro.z;
//calculate aerodynamic force
double qbar = 1.0/2.0*rho*pow(airspeed,2)*s; //Calculate dynamic pressure
double ax, ay, az;
if (is_zero(airspeed))
{
ax = 0;
ay = 0;
az = 0;
}
else
{
ax = qbar*(c_x_a + c_x_q*c*q/(2*airspeed) - c_drag_deltae*cos(alpha)*fabs(inputElevator) + c_lift_deltae*sin(alpha)*inputElevator);
// split c_x_deltae to include "abs" term
ay = qbar*(c_y_0 + c_y_b*beta + c_y_p*b*p/(2*airspeed) + c_y_r*b*r/(2*airspeed) + c_y_deltaa*inputAileron + c_y_deltar*inputRudder);
az = qbar*(c_z_a + c_z_q*c*q/(2*airspeed) - c_drag_deltae*sin(alpha)*fabs(inputElevator) - c_lift_deltae*cos(alpha)*inputElevator);
// split c_z_deltae to include "abs" term
}
return Vector3f(ax, ay, az);
}
void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
{
float aileron = (input.servos[0]-1500)/500.0f;
float elevator = (input.servos[1]-1500)/500.0f;
float rudder = (input.servos[3]-1500)/500.0f;
float throttle;
if (reverse_thrust) {
throttle = constrain_float((input.servos[2]-1500)/500.0f, -1, 1);
} else {
throttle = constrain_float((input.servos[2]-1000)/1000.0f, 0, 1);
}
float thrust = throttle;
// calculate angle of attack
angle_of_attack = atan2f(velocity_bf.z, velocity_bf.x);
beta = atan2f(velocity_bf.y,velocity_bf.x);
Vector3f force = getForce(aileron, elevator, rudder);
rot_accel = getTorque(aileron, elevator, rudder, force);
// velocity in body frame
velocity_bf = dcm.transposed() * velocity_ef;
// scale thrust to newtons
thrust *= thrust_scale;
accel_body = Vector3f(thrust/mass, 0, 0);
accel_body += force;
// add some noise
add_noise(fabsf(thrust) / thrust_scale);
}
/*
update the plane simulation by one time step
*/
void Plane::update(const struct sitl_input &input)
{
Vector3f rot_accel;
calculate_forces(input, rot_accel, accel_body);
update_dynamics(rot_accel);
// update lat/lon/altitude
update_position();
}