AP_MotorsTri: remove call to empty parent Init

Also rename uses of Multirotor to Multicopter
This commit is contained in:
Randy Mackay 2015-07-15 16:58:43 +09:00
parent f906934dfa
commit 4843be49de
2 changed files with 4 additions and 7 deletions

View File

@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_MotorsTri::var_info[] PROGMEM = { const AP_Param::GroupInfo AP_MotorsTri::var_info[] PROGMEM = {
// variables from parent vehicle // variables from parent vehicle
AP_NESTEDGROUPINFO(AP_Motors_Multirotor, 0), AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0),
// parameters 1 ~ 29 were reserved for tradheli // parameters 1 ~ 29 were reserved for tradheli
// parameters 30 ~ 39 reserved for tricopter // parameters 30 ~ 39 reserved for tricopter
@ -74,9 +74,6 @@ const AP_Param::GroupInfo AP_MotorsTri::var_info[] PROGMEM = {
// init // init
void AP_MotorsTri::Init() void AP_MotorsTri::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 for the 3 motors (but not the servo on channel 7)
set_update_rate(_speed_hz); set_update_rate(_speed_hz);

View File

@ -9,18 +9,18 @@
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library #include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <RC_Channel.h> // RC Channel Library #include <RC_Channel.h> // RC Channel Library
#include "AP_Motors_Multirotor.h" #include "AP_MotorsMulticopter.h"
// tail servo uses channel 7 // tail servo uses channel 7
#define AP_MOTORS_CH_TRI_YAW CH_7 #define AP_MOTORS_CH_TRI_YAW CH_7
/// @class AP_MotorsTri /// @class AP_MotorsTri
class AP_MotorsTri : public AP_Motors_Multirotor { class AP_MotorsTri : public AP_MotorsMulticopter {
public: public:
/// Constructor /// Constructor
AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsTri(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)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
}; };