Browse Source

AP_Motors_Coax: remove call to empty parent Init

Also rename uses of Multirotor to Multicopter
master
Randy Mackay 10 years ago
parent
commit
b1a4a6bf0a
  1. 5
      libraries/AP_Motors/AP_MotorsCoax.cpp
  2. 6
      libraries/AP_Motors/AP_MotorsCoax.h

5
libraries/AP_Motors/AP_MotorsCoax.cpp

@ -29,7 +29,7 @@ extern const AP_HAL::HAL& hal; @@ -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 = { @@ -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);

6
libraries/AP_Motors/AP_MotorsCoax.h

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#include <AP_Common.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <RC_Channel.h> // RC Channel Library
#include "AP_Motors_Multirotor.h"
#include "AP_MotorsMulticopter.h"
// feedback direction
#define AP_MOTORS_COAX_POSITIVE 1
@ -21,12 +21,12 @@ @@ -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)
{

Loading…
Cancel
Save