ardupilot/libraries/SITL/SIM_QuadPlane.cpp

158 lines
4.7 KiB
C++
Raw Normal View History

2015-12-31 23:15:27 -04:00
/*
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/>.
*/
/*
simple quadplane simulator class
*/
#include "SIM_QuadPlane.h"
#include <stdio.h>
using namespace SITL;
2019-08-15 01:01:24 -03:00
QuadPlane::QuadPlane(const char *frame_str) :
Plane(frame_str)
2015-12-31 23:15:27 -04:00
{
// default to X frame
const char *frame_type = "x";
uint8_t motor_offset = 4;
2019-04-05 15:28:09 -03:00
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
if (strstr(frame_str, "-octa-quad")) {
frame_type = "octa-quad";
} else if (strstr(frame_str, "-octaquad")) {
frame_type = "octa-quad";
} else if (strstr(frame_str, "-octa")) {
frame_type = "octa";
} else if (strstr(frame_str, "-hexax")) {
frame_type = "hexax";
} else if (strstr(frame_str, "-hexa")) {
frame_type = "hexa";
} else if (strstr(frame_str, "-plus")) {
frame_type = "+";
2016-04-21 08:11:38 -03:00
} else if (strstr(frame_str, "-y6")) {
frame_type = "y6";
2016-04-28 09:36:53 -03:00
} else if (strstr(frame_str, "-tri")) {
frame_type = "tri";
} else if (strstr(frame_str, "-tilttrivec")) {
frame_type = "tilttrivec";
// fwd motor gives zero thrust
thrust_scale = 0;
2017-08-20 16:09:59 -03:00
} else if (strstr(frame_str, "-tilthvec")) {
frame_type = "tilthvec";
} else if (strstr(frame_str, "-tilttri")) {
frame_type = "tilttri";
2016-05-01 05:06:49 -03:00
// fwd motor gives zero thrust
thrust_scale = 0;
} else if (strstr(frame_str, "firefly")) {
2016-04-21 08:11:38 -03:00
frame_type = "firefly";
// elevon style surfaces
elevons = true;
// fwd motor gives zero thrust
thrust_scale = 0;
// vtol motors start at 2
motor_offset = 2;
} else if (strstr(frame_str, "cl84")) {
frame_type = "tilttri";
// fwd motor gives zero thrust
thrust_scale = 0;
2019-04-05 15:28:09 -03:00
} else if (strstr(frame_str, "-copter_tailsitter")) {
frame_type = "+";
copter_tailsitter = true;
ground_behavior = GROUND_BEHAVIOR_TAILSITTER;
thrust_scale *= 1.5;
}
frame = Frame::find_frame(frame_type);
if (frame == nullptr) {
printf("Failed to find frame '%s'\n", frame_type);
exit(1);
}
if (strstr(frame_str, "cl84")) {
// setup retract servos at front
frame->motors[0].servo_type = Motor::SERVO_RETRACT;
frame->motors[0].servo_rate = 7*60.0/90; // 7 seconds to change
frame->motors[1].servo_type = Motor::SERVO_RETRACT;
frame->motors[1].servo_rate = 7*60.0/90; // 7 seconds to change
}
// leave first 4 servos free for plane
frame->motor_offset = motor_offset;
// we use zero terminal velocity to let the plane model handle the drag
frame->init(frame_str, &battery);
// increase mass for plane components
mass = frame->get_mass() * 1.5;
frame->set_mass(mass);
lock_step_scheduled = true;
2015-12-31 23:15:27 -04:00
}
/*
update the quadplane simulation by one time step
*/
void QuadPlane::update(const struct sitl_input &input)
{
// get wind vector setup
update_wind(input);
2015-12-31 23:15:27 -04:00
// first plane forces
Vector3f rot_accel;
calculate_forces(input, rot_accel);
2015-12-31 23:15:27 -04:00
// now quad forces
Vector3f quad_rot_accel;
Vector3f quad_accel_body;
motor_mask |= ((1U<<frame->num_motors)-1U) << frame->motor_offset;
frame->calculate_forces(*this, input, quad_rot_accel, quad_accel_body, rpm, false);
2015-12-31 23:15:27 -04:00
2019-04-05 15:28:09 -03:00
// rotate frames for copter tailsitters
if (copter_tailsitter) {
quad_rot_accel.rotate(ROTATION_PITCH_270);
quad_accel_body.rotate(ROTATION_PITCH_270);
}
// estimate voltage and current
frame->current_and_voltage(battery_voltage, battery_current);
battery.set_current(battery_current);
float throttle;
if (reverse_thrust) {
throttle = filtered_servo_angle(input, 2);
} else {
throttle = filtered_servo_range(input, 2);
}
// assume 20A at full fwd throttle
throttle = fabsf(throttle);
battery_current += 20 * throttle;
2015-12-31 23:15:27 -04:00
rot_accel += quad_rot_accel;
accel_body += quad_accel_body;
update_dynamics(rot_accel);
update_external_payload(input);
2015-12-31 23:15:27 -04:00
// update lat/lon/altitude
update_position();
time_advance();
// update magnetic field
update_mag_field_bf();
2015-12-31 23:15:27 -04:00
}