diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 8633bc1117..824f1fb64b 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -25,17 +25,6 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsTri::var_info[] = { - // variables from parent vehicle - AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), - - // parameters 1 ~ 29 were reserved for tradheli - // parameters 30 ~ 39 reserved for tricopter - // parameters 40 ~ 49 for single copter and coax copter (these have identical parameter files) - - AP_GROUPEND -}; - // init void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_type) { diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 87d8c12f50..1efd27d4cb 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -21,7 +21,6 @@ public: AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMulticopter(loop_rate, speed_hz) { - AP_Param::setup_object_defaults(this, var_info); }; // init @@ -48,9 +47,6 @@ public: // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict virtual uint16_t get_motor_mask(); - // var_info for holding Parameter information - static const struct AP_Param::GroupInfo var_info[]; - protected: // output - sends commands to the motors void output_armed_stabilizing();