From 8a49c84d572844a175badae8d179ffd565dbe83c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 23 Jun 2019 11:40:26 +1000 Subject: [PATCH] AP_Motors: fixed col max and min for dual heli fixes H_SV_MAN behaviour --- libraries/AP_Motors/AP_MotorsHeli.cpp | 17 ++++++++++++++--- libraries/AP_Motors/AP_MotorsHeli.h | 1 + 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index a5b327d7b6..a442cc4ab6 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -166,8 +166,9 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = { // init void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_type) { - // remember frame type + // remember frame class and type _frame_type = frame_type; + _frame_class = frame_class; // set update rate set_update_rate(_speed_hz); @@ -293,14 +294,24 @@ void AP_MotorsHeli::output_disarmed() _roll_in = 0.0f; _pitch_in = 0.0f; _throttle_filter.reset(1.0f); - _yaw_in = 1.0f; + if (_frame_class == MOTOR_FRAME_HELI_DUAL || + _frame_class == MOTOR_FRAME_HELI_QUAD) { + _yaw_in = 0; + } else { + _yaw_in = 1; + } break; case SERVO_CONTROL_MODE_MANUAL_MIN: // fixate min collective _roll_in = 0.0f; _pitch_in = 0.0f; _throttle_filter.reset(0.0f); - _yaw_in = -1.0f; + if (_frame_class == MOTOR_FRAME_HELI_DUAL || + _frame_class == MOTOR_FRAME_HELI_QUAD) { + _yaw_in = 0; + } else { + _yaw_in = -1; + } break; case SERVO_CONTROL_MODE_MANUAL_OSCILLATE: // use servo_test function from child classes diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 8abfbd81f0..6ffb074d54 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -224,4 +224,5 @@ protected: uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup motor_frame_type _frame_type; + motor_frame_class _frame_class; };