diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 2235d948bf..6921982096 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -29,7 +29,7 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsCoax::var_info[] PROGMEM = { // variables from parent vehicle - AP_NESTEDGROUPINFO(AP_Motors_Multirotor, 0), + AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), // parameters 1 ~ 29 were reserved for tradheli // parameters 30 ~ 39 reserved for tricopter @@ -64,9 +64,6 @@ const AP_Param::GroupInfo AP_MotorsCoax::var_info[] PROGMEM = { // init void AP_MotorsCoax::Init() { - // call parent Init function to set-up throttle curve - AP_Motors::Init(); - // set update rate for the 2 motors (but not the servo on channel 1&2) set_update_rate(_speed_hz); diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index b10c3c4103..9be3527bba 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -9,7 +9,7 @@ #include #include // ArduPilot Mega Vector/Matrix math Library #include // RC Channel Library -#include "AP_Motors_Multirotor.h" +#include "AP_MotorsMulticopter.h" // feedback direction #define AP_MOTORS_COAX_POSITIVE 1 @@ -21,12 +21,12 @@ #define AP_MOTORS_COAX_SERVO_INPUT_RANGE 4500 // roll or pitch input of -4500 will cause servos to their minimum (i.e. radio_min), +4500 will move them to their maximum (i.e. radio_max) /// @class AP_MotorsSingle -class AP_MotorsCoax : public AP_Motors_Multirotor { +class AP_MotorsCoax : public AP_MotorsMulticopter { public: /// Constructor AP_MotorsCoax(RC_Channel& servo1, RC_Channel& servo2, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_Motors_Multirotor(loop_rate, speed_hz), + AP_MotorsMulticopter(loop_rate, speed_hz), _servo1(servo1), _servo2(servo2) {