Browse Source

AP_MotorsMatrix: remove call to empty parent Init

Also rename uses of Multirotor to Multicopter
master
Randy Mackay 10 years ago
parent
commit
112e934072
  1. 3
      libraries/AP_Motors/AP_MotorsMatrix.cpp
  2. 6
      libraries/AP_Motors/AP_MotorsMatrix.h

3
libraries/AP_Motors/AP_MotorsMatrix.cpp

@ -27,9 +27,6 @@ extern const AP_HAL::HAL& hal;
// Init // Init
void AP_MotorsMatrix::Init() void AP_MotorsMatrix::Init()
{ {
// call parent Init function to set-up throttle curve
AP_Motors::Init();
// setup the motors // setup the motors
setup_motors(); setup_motors();

6
libraries/AP_Motors/AP_MotorsMatrix.h

@ -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"
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1 #define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1 #define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1
/// @class AP_MotorsMatrix /// @class AP_MotorsMatrix
class AP_MotorsMatrix : public AP_Motors_Multirotor { class AP_MotorsMatrix : public AP_MotorsMulticopter {
public: public:
/// Constructor /// Constructor
AP_MotorsMatrix(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(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)
{}; {};
// init // init

Loading…
Cancel
Save