AP_Motors: removed board type define

This commit is contained in:
Andrew Tridgell 2013-01-02 15:27:58 +11:00
parent 394dccf9a8
commit f91ddf5df9
10 changed files with 16 additions and 17 deletions

View File

@ -42,8 +42,7 @@ class AP_MotorsHeli : public AP_Motors {
public:
/// Constructor
AP_MotorsHeli( uint8_t APM_version,
RC_Channel* rc_roll,
AP_MotorsHeli( RC_Channel* rc_roll,
RC_Channel* rc_pitch,
RC_Channel* rc_throttle,
RC_Channel* rc_yaw,
@ -53,7 +52,7 @@ public:
RC_Channel* swash_servo_3,
RC_Channel* yaw_servo,
uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
AP_Motors(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
_servo_1(swash_servo_1),
_servo_2(swash_servo_2),
_servo_3(swash_servo_3),

View File

@ -16,7 +16,7 @@ class AP_MotorsHexa : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsHexa( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
AP_MotorsHexa( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
};
// setup_motors - configures the motors for a quad

View File

@ -24,8 +24,8 @@ class AP_MotorsMatrix : public AP_Motors {
public:
/// Constructor
AP_MotorsMatrix( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_Motors(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
AP_MotorsMatrix( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
_num_motors(0) {
};

View File

@ -16,7 +16,7 @@ class AP_MotorsOcta : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsOcta( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
AP_MotorsOcta( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
};
// setup_motors - configures the motors for a quad

View File

@ -16,7 +16,7 @@ class AP_MotorsOctaQuad : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsOctaQuad( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
AP_MotorsOctaQuad( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
};
// setup_motors - configures the motors for a quad

View File

@ -16,7 +16,7 @@ class AP_MotorsQuad : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsQuad( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
AP_MotorsQuad( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
};
// setup_motors - configures the motors for a quad

View File

@ -19,8 +19,8 @@ class AP_MotorsTri : public AP_Motors {
public:
/// Constructor
AP_MotorsTri( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, RC_Channel* rc_tail, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_Motors(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
AP_MotorsTri( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, RC_Channel* rc_tail, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
_rc_tail(rc_tail) {
};

View File

@ -18,7 +18,7 @@ class AP_MotorsY6 : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsY6( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
AP_MotorsY6( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
};
// setup_motors - configures the motors for a quad

View File

@ -41,7 +41,7 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
};
// Constructor
AP_Motors::AP_Motors( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz ) :
AP_Motors::AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz ) :
_rc_roll(rc_roll),
_rc_pitch(rc_pitch),
_rc_throttle(rc_throttle),
@ -60,11 +60,11 @@ AP_Motors::AP_Motors( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_p
top_bottom_ratio = AP_MOTORS_TOP_BOTTOM_RATIO;
// initialise motor map
if( APM_version == AP_MOTORS_APM1 ) {
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
set_motor_to_channel_map(APM1_MOTOR_TO_CHANNEL_MAP);
} else {
#else
set_motor_to_channel_map(APM2_MOTOR_TO_CHANNEL_MAP);
}
#endif
// clear output arrays
for(i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {

View File

@ -58,7 +58,7 @@ class AP_Motors {
public:
// Constructor
AP_Motors( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
// init
virtual void Init();