Browse Source

SITL: add copter tailsitter

gps-1.3.1
IamPete1 6 years ago committed by Andrew Tridgell
parent
commit
950391df12
  1. 1
      libraries/SITL/SIM_Plane.h
  2. 14
      libraries/SITL/SIM_QuadPlane.cpp

1
libraries/SITL/SIM_Plane.h

@ -99,6 +99,7 @@ protected:
bool reverse_elevator_rudder; bool reverse_elevator_rudder;
bool ice_engine; bool ice_engine;
bool tailsitter; bool tailsitter;
bool copter_tailsitter;
bool have_launcher; bool have_launcher;
float launch_accel; float launch_accel;
float launch_time; float launch_time;

14
libraries/SITL/SIM_QuadPlane.cpp

@ -29,6 +29,8 @@ QuadPlane::QuadPlane(const char *frame_str) :
const char *frame_type = "x"; const char *frame_type = "x";
uint8_t motor_offset = 4; uint8_t motor_offset = 4;
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
if (strstr(frame_str, "-octa-quad")) { if (strstr(frame_str, "-octa-quad")) {
frame_type = "octa-quad"; frame_type = "octa-quad";
} else if (strstr(frame_str, "-octaquad")) { } else if (strstr(frame_str, "-octaquad")) {
@ -67,6 +69,11 @@ QuadPlane::QuadPlane(const char *frame_str) :
frame_type = "tilttri"; frame_type = "tilttri";
// fwd motor gives zero thrust // fwd motor gives zero thrust
thrust_scale = 0; thrust_scale = 0;
} 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); frame = Frame::find_frame(frame_type);
if (frame == nullptr) { if (frame == nullptr) {
@ -94,7 +101,6 @@ QuadPlane::QuadPlane(const char *frame_str) :
mass = frame->get_mass() * 1.5; mass = frame->get_mass() * 1.5;
frame->set_mass(mass); frame->set_mass(mass);
ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT;
lock_step_scheduled = true; lock_step_scheduled = true;
} }
@ -116,6 +122,12 @@ void QuadPlane::update(const struct sitl_input &input)
frame->calculate_forces(*this, input, quad_rot_accel, quad_accel_body, &rpm[1], false); frame->calculate_forces(*this, input, quad_rot_accel, quad_accel_body, &rpm[1], false);
// 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 // estimate voltage and current
frame->current_and_voltage(battery_voltage, battery_current); frame->current_and_voltage(battery_voltage, battery_current);

Loading…
Cancel
Save