diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h
index 382578a31d..de9e2b1899 100644
--- a/ArduCopter/APM_Config.h
+++ b/ArduCopter/APM_Config.h
@@ -15,6 +15,7 @@
* OCTA_FRAME
* OCTA_QUAD_FRAME
* HELI_FRAME
+ * SINGLE_FRAME
*/
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 9d1d965e58..301bf8cf5f 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -447,6 +447,8 @@ static struct {
#define MOTOR_CLASS AP_MotorsOctaQuad
#elif FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli
+#elif FRAME_CONFIG == SINGLE_FRAME
+ #define MOTOR_CLASS AP_MotorsSingle
#else
#error Unrecognised frame type
#endif
@@ -455,6 +457,8 @@ static struct {
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_8, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4);
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_7);
+#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
+static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2, &g.single_servo_3, &g.single_servo_4);
#else
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
#endif
diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index 544360fec8..cebf553a99 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -105,6 +105,8 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
MAV_TYPE_OCTOROTOR,
#elif (FRAME_CONFIG == HELI_FRAME)
MAV_TYPE_HELICOPTER,
+#elif (FRAME_CONFIG == SINGLE_FRAME) //because mavlink did not define a singlecopter, we use a rocket
+ MAV_TYPE_ROCKET,
#else
#error Unrecognised frame type
#endif
diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index 2f9d78ada8..010d435c1a 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -261,6 +261,16 @@ public:
k_param_acro_balance_pitch,
k_param_acro_yaw_p, // 244
+
+ //
+ //245: Singlecopter
+ //
+ k_param_single_servo_1 = 245, //
+ k_param_single_servo_2,
+ k_param_single_servo_3,
+ k_param_single_servo_4,
+
+
// 254,255: reserved
};
@@ -350,6 +360,10 @@ public:
AP_Float heli_roll_ff; // roll rate feed-forward
AP_Float heli_yaw_ff; // yaw rate feed-forward
#endif
+#if FRAME_CONFIG == SINGLE_FRAME
+ // Single
+ RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
+#endif
// RC channels
RC_Channel rc_1;
@@ -406,6 +420,12 @@ public:
heli_servo_3 (CH_3),
heli_servo_4 (CH_4),
#endif
+#if FRAME_CONFIG == SINGLE_FRAME
+ single_servo_1 (CH_1),
+ single_servo_2 (CH_2),
+ single_servo_3 (CH_3),
+ single_servo_4 (CH_4),
+#endif
rc_1 (CH_1),
rc_2 (CH_2),
diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde
index e63de4db16..75ce0abaae 100644
--- a/ArduCopter/Parameters.pde
+++ b/ArduCopter/Parameters.pde
@@ -451,6 +451,23 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(heli_yaw_ff, "RATE_YAW_FF", HELI_YAW_FF),
#endif
+#if FRAME_CONFIG == SINGLE_FRAME
+ // @Group: SS1_
+ // @Path: ../libraries/RC_Channel/RC_Channel.cpp
+ GGROUP(single_servo_1, "SS1_", RC_Channel),
+ // @Group: SS2_
+ // @Path: ../libraries/RC_Channel/RC_Channel.cpp
+ GGROUP(single_servo_2, "SS2_", RC_Channel),
+ // @Group: SS3_
+ // @Path: ../libraries/RC_Channel/RC_Channel.cpp
+ GGROUP(single_servo_3, "SS3_", RC_Channel),
+ // @Group: SS4_
+ // @Path: ../libraries/RC_Channel/RC_Channel.cpp
+ GGROUP(single_servo_4, "SS4_", RC_Channel),
+
+
+#endif
+
// RC channel
//-----------
@@ -1020,6 +1037,10 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Group: H_
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
GOBJECT(motors, "H_", AP_MotorsHeli),
+#elif FRAME_CONFIG == SINGLE_FRAME
+ // @Group: H_
+ // @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
+ GOBJECT(motors, "MOT_", AP_MotorsSingle),
#else
// @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_Motors_Class.cpp
diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde
index c26411719e..3f4af9e687 100644
--- a/ArduCopter/radio.pde
+++ b/ArduCopter/radio.pde
@@ -33,6 +33,17 @@ static void init_rc_in()
g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
g.rc_2.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
g.rc_4.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
+#if FRAME_CONFIG == SINGLE_FRAME
+ // we set four servos to angle
+ g.single_servo_1.set_type(RC_CHANNEL_TYPE_ANGLE);
+ g.single_servo_2.set_type(RC_CHANNEL_TYPE_ANGLE);
+ g.single_servo_3.set_type(RC_CHANNEL_TYPE_ANGLE);
+ g.single_servo_4.set_type(RC_CHANNEL_TYPE_ANGLE);
+ g.single_servo_1.set_angle(DEFAULT_ANGLE_MAX);
+ g.single_servo_2.set_angle(DEFAULT_ANGLE_MAX);
+ g.single_servo_3.set_angle(DEFAULT_ANGLE_MAX);
+ g.single_servo_4.set_angle(DEFAULT_ANGLE_MAX);
+#endif
//set auxiliary servo ranges
g.rc_5.set_range(0,1000);
@@ -190,8 +201,8 @@ void aux_servos_update_fn()
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_10, &g.rc_11);
#endif
-// Tri's can use RC5, RC6, RC8 and higher
-#elif (FRAME_CONFIG == TRI_FRAME)
+// Tri's and Singles can use RC5, RC6, RC8 and higher
+#elif (FRAME_CONFIG == TRI_FRAME || FRAME_CONFIG == SINGLE_FRAME)
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12);
#else // APM1, APM2, SITL
diff --git a/libraries/AP_Motors/AP_Motors.h b/libraries/AP_Motors/AP_Motors.h
index b74a02a393..898df11564 100644
--- a/libraries/AP_Motors/AP_Motors.h
+++ b/libraries/AP_Motors/AP_Motors.h
@@ -12,5 +12,6 @@
#include "AP_MotorsOcta.h"
#include "AP_MotorsOctaQuad.h"
#include "AP_MotorsHeli.h"
+#include "AP_MotorsSingle.h"
#endif // __AP_MOTORS_H__
diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp
new file mode 100644
index 0000000000..f88aaf73b4
--- /dev/null
+++ b/libraries/AP_Motors/AP_MotorsSingle.cpp
@@ -0,0 +1,256 @@
+// -*- 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 .
+ */
+
+/*
+ * AP_MotorsSingle.cpp - ArduCopter motors library
+ * Code by RandyMackay. DIYDrones.com
+ *
+ */
+
+#include
+#include
+#include "AP_MotorsSingle.h"
+
+extern const AP_HAL::HAL& hal;
+
+
+const AP_Param::GroupInfo AP_MotorsSingle::var_info[] PROGMEM = {
+
+
+ // 0 was used by TB_RATIO
+
+ // @Param: TCRV_ENABLE
+ // @DisplayName: Thrust Curve Enable
+ // @Description: Controls whether a curve is used to linearize the thrust produced by the motors
+ // @Values: 0:Disabled,1:Enable
+ AP_GROUPINFO("TCRV_ENABLE", 1, AP_MotorsSingle, _throttle_curve_enabled, THROTTLE_CURVE_ENABLED),
+
+ // @Param: TCRV_MIDPCT
+ // @DisplayName: Thrust Curve mid-point percentage
+ // @Description: Set the pwm position that produces half the maximum thrust of the motors
+ // @Range: 20 80
+ AP_GROUPINFO("TCRV_MIDPCT", 2, AP_MotorsSingle, _throttle_curve_mid, THROTTLE_CURVE_MID_THRUST),
+
+ // @Param: TCRV_MAXPCT
+ // @DisplayName: Thrust Curve max thrust percentage
+ // @Description: Set to the lowest pwm position that produces the maximum thrust of the motors. Most motors produce maximum thrust below the maximum pwm value that they accept.
+ // @Range: 20 80
+ AP_GROUPINFO("TCRV_MAXPCT", 3, AP_MotorsSingle, _throttle_curve_max, THROTTLE_CURVE_MAX_THRUST),
+
+ // @Param: SPIN_ARMED
+ // @DisplayName: Motors always spin when armed
+ // @Description: Controls whether motors always spin when armed (must be below THR_MIN)
+ // @Values: 0:Do Not Spin,70:VerySlow,100:Slow,130:Medium,150:Fast
+ AP_GROUPINFO("SPIN_ARMED", 5, AP_MotorsSingle, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED),
+
+ // @Param: REV_ROLL
+ // @DisplayName: Reverse roll feedback
+ // @Description: Ensure the feedback is negative
+ // @Values: -1:Opposite direction,1:Same direction
+ AP_GROUPINFO("REV_ROLL", 6, AP_MotorsSingle, _rev_roll, POSITIVE),
+
+ // @Param: REV_PITCH
+ // @DisplayName: Reverse roll feedback
+ // @Description: Ensure the feedback is negative
+ // @Values: -1:Opposite direction,1:Same direction
+ AP_GROUPINFO("REV_PITCH", 7, AP_MotorsSingle, _rev_pitch, POSITIVE),
+
+ // @Param: REV_ROLL
+ // @DisplayName: Reverse roll feedback
+ // @Description: Ensure the feedback is negative
+ // @Values: -1:Opposite direction,1:Same direction
+ AP_GROUPINFO("REV_YAW", 8, AP_MotorsSingle, _rev_yaw, POSITIVE),
+
+ // @Param: SV_SPEED
+ // @DisplayName: Servo speed
+ // @Description: Servo update speed
+ // @Values: -1:Opposite direction,1:Same direction
+ AP_GROUPINFO("SV_SPEED", 9, AP_MotorsSingle, _servo_speed, AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS),
+
+ AP_GROUPEND
+};
+// init
+void AP_MotorsSingle::Init()
+{
+ // call parent Init function to set-up throttle curve
+ AP_Motors::Init();
+
+ // set update rate for the 3 motors (but not the servo on channel 7)
+ set_update_rate(_speed_hz);
+
+ // set the motor_enabled flag so that the ESCs can be calibrated like other frame types
+ motor_enabled[AP_MOTORS_MOT_1] = true;
+ motor_enabled[AP_MOTORS_MOT_2] = true;
+ motor_enabled[AP_MOTORS_MOT_3] = true;
+ motor_enabled[AP_MOTORS_MOT_4] = true;
+
+}
+
+// set update rate to motors - a value in hertz
+void AP_MotorsSingle::set_update_rate( uint16_t speed_hz )
+{
+ // record requested speed
+ _speed_hz = speed_hz;
+
+ // set update rate for the 3 motors (but not the servo on channel 7)
+ uint32_t mask =
+ 1U << _motor_to_channel_map[AP_MOTORS_MOT_1] |
+ 1U << _motor_to_channel_map[AP_MOTORS_MOT_2] |
+ 1U << _motor_to_channel_map[AP_MOTORS_MOT_3] |
+ 1U << _motor_to_channel_map[AP_MOTORS_MOT_4] ;
+ hal.rcout->set_freq(mask, _servo_speed);
+ uint32_t mask2 =
+ 1U << _motor_to_channel_map[AP_MOTORS_MOT_7];
+ hal.rcout->set_freq(mask2, _speed_hz);
+}
+
+// enable - starts allowing signals to be sent to motors
+void AP_MotorsSingle::enable()
+{
+ // enable output channels
+ hal.rcout->enable_ch(_motor_to_channel_map[AP_MOTORS_MOT_1]);
+ hal.rcout->enable_ch(_motor_to_channel_map[AP_MOTORS_MOT_2]);
+ hal.rcout->enable_ch(_motor_to_channel_map[AP_MOTORS_MOT_3]);
+ hal.rcout->enable_ch(_motor_to_channel_map[AP_MOTORS_MOT_4]);
+ hal.rcout->enable_ch(_motor_to_channel_map[AP_MOTORS_MOT_7]);
+}
+
+// output_min - sends minimum values out to the motor and trim values to the servos
+void AP_MotorsSingle::output_min()
+{
+ // fill the motor_out[] array for HIL use
+ motor_out[AP_MOTORS_MOT_1] = _servo1->radio_trim;
+ motor_out[AP_MOTORS_MOT_2] = _servo2->radio_trim;
+ motor_out[AP_MOTORS_MOT_3] = _servo3->radio_trim;
+ motor_out[AP_MOTORS_MOT_4] = _servo4->radio_trim;
+ motor_out[AP_MOTORS_MOT_7] = _rc_throttle->radio_min;
+
+ // send minimum value to each motor
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _servo1->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _servo2->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_3], _servo3->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _servo4->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_7], _rc_throttle->radio_min);
+}
+
+// output_armed - sends commands to the motors
+void AP_MotorsSingle::output_armed()
+{
+ int16_t out_min = _rc_throttle->radio_min + _min_throttle;
+ int16_t out_max = _rc_throttle->radio_max;
+
+ // Throttle is 0 to 1000 only
+ _rc_throttle->servo_out = constrain_int16(_rc_throttle->servo_out, 0, _max_throttle);
+
+ // capture desired throttle from receiver
+
+ _rc_throttle->calc_pwm();
+
+
+ // if we are not sending a throttle output, we cut the motors
+ if(_rc_throttle->servo_out == 0) {
+ // range check spin_when_armed
+ if (_spin_when_armed < 0) {
+ _spin_when_armed = 0;
+ }
+ if (_spin_when_armed > _min_throttle) {
+ _spin_when_armed = _min_throttle;
+ }
+
+ motor_out[AP_MOTORS_MOT_7] = _rc_throttle->radio_min + _spin_when_armed;
+ }else{
+
+ //motor
+ motor_out[AP_MOTORS_MOT_7] = _rc_throttle->radio_out;
+ //front
+ _servo1->servo_out = _rev_roll*_rc_roll->servo_out + _rev_yaw*_rc_yaw->servo_out;
+ //right
+ _servo2->servo_out = _rev_pitch*_rc_pitch->servo_out + _rev_yaw*_rc_yaw->servo_out;
+ //rear
+ _servo3->servo_out = -_rev_roll*_rc_roll->servo_out + _rev_yaw*_rc_yaw->servo_out;
+ //left
+ _servo4->servo_out = -_rev_pitch*_rc_pitch->servo_out + _rev_yaw*_rc_yaw->servo_out;
+
+ _servo1->calc_pwm();
+ _servo2->calc_pwm();
+ _servo3->calc_pwm();
+ _servo4->calc_pwm();
+
+ motor_out[AP_MOTORS_MOT_1] = _servo1->radio_out;
+ motor_out[AP_MOTORS_MOT_2] = _servo2->radio_out;
+ motor_out[AP_MOTORS_MOT_3] = _servo3->radio_out;
+ motor_out[AP_MOTORS_MOT_4] = _servo4->radio_out;
+
+
+ // adjust for throttle curve
+ if( _throttle_curve_enabled ) {
+
+ motor_out[AP_MOTORS_MOT_7] = _throttle_curve.get_y(motor_out[AP_MOTORS_MOT_7]);
+ }
+
+ // ensure motors don't drop below a minimum value and stop
+
+ motor_out[AP_MOTORS_MOT_7] = max(motor_out[AP_MOTORS_MOT_7], out_min);
+ }
+
+ // send output to each motor
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], motor_out[AP_MOTORS_MOT_1]);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], motor_out[AP_MOTORS_MOT_2]);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_3], motor_out[AP_MOTORS_MOT_3]);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], motor_out[AP_MOTORS_MOT_4]);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_7], motor_out[AP_MOTORS_MOT_7]);
+
+}
+
+// output_disarmed - sends commands to the motors
+void AP_MotorsSingle::output_disarmed()
+{
+ // fill the motor_out[] array for HIL use
+ for (unsigned char i = AP_MOTORS_MOT_1; i < AP_MOTORS_MOT_4; i++) {
+ motor_out[i] = _rc_throttle->radio_min;
+ }
+
+ // Send minimum values to all motors
+ output_min();
+}
+
+// output_disarmed - sends commands to the motors
+void AP_MotorsSingle::output_test()
+{
+ // Send minimum values to all motors
+ output_min();
+
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_7], _rc_throttle->radio_min);
+ hal.scheduler->delay(4000);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_7], _rc_throttle->radio_min + _min_throttle);
+ hal.scheduler->delay(2000);
+
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _servo1->radio_min);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _servo2->radio_min);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_3], _servo3->radio_min);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _servo4->radio_min);
+ hal.scheduler->delay(2000);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _servo1->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _servo2->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_3], _servo3->radio_trim);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _servo4->radio_trim);
+ hal.scheduler->delay(2000);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _servo1->radio_max);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _servo2->radio_max);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_3], _servo3->radio_max);
+ hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _servo4->radio_max);
+
+}
diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h
new file mode 100644
index 0000000000..f6e501cfa9
--- /dev/null
+++ b/libraries/AP_Motors/AP_MotorsSingle.h
@@ -0,0 +1,77 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+
+/// @file AP_MotorsSingle.h
+/// @brief Motor and Servo control class for Singlecopters
+
+#ifndef __AP_MOTORS_SING_H__
+#define __AP_MOTORS_SING_H__
+
+
+#include
+#include // ArduPilot Mega Vector/Matrix math Library
+#include // RC Channel Library
+#include "AP_Motors.h"
+
+// feedback direction
+#define POSITIVE 1
+#define NEGATIVE -1
+
+#define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos
+#define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos
+
+
+/// @class AP_MotorsTri
+class AP_MotorsSingle : public AP_Motors {
+public:
+
+ /// Constructor
+ AP_MotorsSingle( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, RC_Channel* servo1, RC_Channel* servo2, RC_Channel* servo3, RC_Channel* servo4, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
+ AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
+ _servo1(servo1),
+ _servo2(servo2),
+ _servo3(servo3),
+ _servo4(servo4)
+
+ {
+ AP_Param::setup_object_defaults(this, var_info);
+
+ };
+
+ // init
+ virtual void Init();
+
+ // set update rate to motors - a value in hertz
+ void set_update_rate( uint16_t speed_hz );
+
+ // enable - starts allowing signals to be sent to motors
+ virtual void enable();
+
+ // motor test
+ virtual void output_test();
+
+ // output_min - sends minimum values out to the motors
+ virtual void output_min();
+
+
+
+ // var_info for holding Parameter information
+ static const struct AP_Param::GroupInfo var_info[];
+
+protected:
+ // output - sends commands to the motors
+ virtual void output_armed();
+ virtual void output_disarmed();
+
+ AP_Int8 _rev_roll; // REV Roll feedback
+ AP_Int8 _rev_pitch; // REV pitch feedback
+ AP_Int8 _rev_yaw; // REV yaw feedback
+ AP_Int16 _servo_speed; // servo speed
+ RC_Channel* _servo1;
+ RC_Channel* _servo2;
+ RC_Channel* _servo3;
+ RC_Channel* _servo4;
+
+
+};
+
+#endif // AP_MOTORSSINGLE