Browse Source

Plane: initial hooks for tailsitter support

master
Andrew Tridgell 8 years ago
parent
commit
83f3cee99e
  1. 23
      ArduPlane/quadplane.cpp
  2. 6
      ArduPlane/quadplane.h
  3. 3
      ArduPlane/servos.cpp
  4. 37
      ArduPlane/tailsitter.cpp

23
ArduPlane/quadplane.cpp

@ -439,14 +439,27 @@ bool QuadPlane::setup(void) @@ -439,14 +439,27 @@ bool QuadPlane::setup(void)
SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
break;
case AP_Motors::MOTOR_FRAME_TAILSITTER:
break;
default:
hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get());
goto failed;
}
if (motor_class == AP_Motors::MOTOR_FRAME_TRI) {
const struct AP_Param::GroupInfo *var_info;
switch (motor_class) {
case AP_Motors::MOTOR_FRAME_TRI:
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz());
} else {
var_info = AP_MotorsTri::var_info;
break;
case AP_Motors::MOTOR_FRAME_TAILSITTER:
motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz());
var_info = AP_MotorsTailsitter::var_info;
break;
default:
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz());
var_info = AP_MotorsMatrix::var_info;
break;
}
const static char *strUnableToAllocate = "Unable to allocate";
if (!motors) {
@ -454,7 +467,7 @@ bool QuadPlane::setup(void) @@ -454,7 +467,7 @@ bool QuadPlane::setup(void)
goto failed;
}
AP_Param::load_object_from_eeprom(motors, motors->var_info);
AP_Param::load_object_from_eeprom(motors, var_info);
attitude_control = new AC_AttitudeControl_Multi(ahrs, aparm, *motors, loop_delta_t);
if (!attitude_control) {
hal.console->printf("%s attitude_control\n", strUnableToAllocate);
@ -981,7 +994,7 @@ void QuadPlane::update_transition(void) @@ -981,7 +994,7 @@ void QuadPlane::update_transition(void)
plane.control_mode == ACRO ||
plane.control_mode == TRAINING) {
// in manual modes quad motors are always off
if (!tilt.motors_active) {
if (!tilt.motors_active && !is_tailsitter()) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
motors->output();
}
@ -1080,7 +1093,7 @@ void QuadPlane::update_transition(void) @@ -1080,7 +1093,7 @@ void QuadPlane::update_transition(void)
}
case TRANSITION_DONE:
if (!tilt.motors_active) {
if (!tilt.motors_active && !is_tailsitter()) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
motors->output();
}

6
ArduPlane/quadplane.h

@ -74,6 +74,12 @@ public: @@ -74,6 +74,12 @@ public:
// see if we are flying from vtol point of view
bool is_flying_vtol(void);
// return true when flying a tailsitter
bool is_tailsitter(void);
// create outputs for tailsitters
void tailsitter_output(void);
struct PACKED log_QControl_Tuning {
LOG_PACKET_HEADER;

3
ArduPlane/servos.cpp

@ -747,6 +747,9 @@ void Plane::servos_output(void) @@ -747,6 +747,9 @@ void Plane::servos_output(void)
{
hal.rcout->cork();
// cope with tailsitters
quadplane.tailsitter_output();
// the mixers need pwm to be calculated now
SRV_Channels::calc_pwm();

37
ArduPlane/tailsitter.cpp

@ -0,0 +1,37 @@ @@ -0,0 +1,37 @@
/*
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/>.
*/
/*
control code for tailsitters. Enabled by setting Q_FRAME_CLASS=10
*/
#include "Plane.h"
/*
return true when flying a tailsitter
*/
bool QuadPlane::is_tailsitter(void)
{
return available() && frame_class == AP_Motors::MOTOR_FRAME_TAILSITTER;
}
/*
run output for tailsitters
*/
void QuadPlane::tailsitter_output(void)
{
if (is_tailsitter() && in_vtol_mode()) {
motors_output();
}
}
Loading…
Cancel
Save