From 708e2b402ebed618dc93af9f9341b5f9bed09ac8 Mon Sep 17 00:00:00 2001 From: Fredrik Hedberg Date: Wed, 22 Jul 2015 16:04:04 +0200 Subject: [PATCH] Copter: Use AP_MotorsHeli_Single for HELI_FRAME. --- ArduCopter/Copter.h | 2 +- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/heli_control_acro.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index c76546271b..e39e371e18 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -296,7 +296,7 @@ private: #elif FRAME_CONFIG == OCTA_QUAD_FRAME #define MOTOR_CLASS AP_MotorsOctaQuad #elif FRAME_CONFIG == HELI_FRAME - #define MOTOR_CLASS AP_MotorsHeli + #define MOTOR_CLASS AP_MotorsHeli_Single #elif FRAME_CONFIG == SINGLE_FRAME #define MOTOR_CLASS AP_MotorsSingle #elif FRAME_CONFIG == COAX_FRAME diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 81b8c7688f..6204330f75 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -979,8 +979,8 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { #if FRAME_CONFIG == HELI_FRAME // @Group: H_ - // @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp - GOBJECT(motors, "H_", AP_MotorsHeli), + // @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp + GOBJECT(motors, "H_", AP_MotorsHeli_Single), #elif FRAME_CONFIG == SINGLE_FRAME // @Group: SS1_ diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index ec65e5dec0..9cc9c0a697 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -11,7 +11,7 @@ bool Copter::heli_acro_init(bool ignore_checks) { // if heli is equipped with a flybar, then tell the attitude controller to pass through controls directly to servos - attitude_control.use_flybar_passthrough(motors.has_flybar(), motors.tail_type() == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO); + attitude_control.use_flybar_passthrough(motors.has_flybar(), motors.supports_yaw_passthrough()); // always successfully enter acro return true;