From 7ab76dbd0effe0e0aedaaf68d640b27a76821c39 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 21 Feb 2015 15:46:22 +0900 Subject: [PATCH] Motors: add loop_rate to constructor for all frames --- libraries/AP_Motors/AP_MotorsCoax.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli.h | 3 ++- libraries/AP_Motors/AP_MotorsHexa.h | 2 +- libraries/AP_Motors/AP_MotorsMatrix.h | 4 ++-- libraries/AP_Motors/AP_MotorsOcta.h | 2 +- libraries/AP_Motors/AP_MotorsOctaQuad.h | 2 +- libraries/AP_Motors/AP_MotorsQuad.h | 2 +- libraries/AP_Motors/AP_MotorsSingle.h | 4 ++-- libraries/AP_Motors/AP_MotorsTri.h | 4 ++-- libraries/AP_Motors/AP_MotorsY6.h | 2 +- 10 files changed, 15 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index 7ad66c1f15..94ae3760ef 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -25,8 +25,8 @@ class AP_MotorsCoax : public AP_Motors { public: /// Constructor - AP_MotorsCoax( RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, RC_Channel& servo1, RC_Channel& servo2, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz), + AP_MotorsCoax( RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, RC_Channel& servo1, RC_Channel& servo2, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz), _servo1(servo1), _servo2(servo2) { diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 0a4899aacb..56245b001a 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -97,8 +97,9 @@ public: RC_Channel& swash_servo_2, RC_Channel& swash_servo_3, RC_Channel& yaw_servo, + uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : - AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz), + AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz), _servo_aux(servo_aux), _servo_rsc(servo_rotor), _servo_1(swash_servo_1), diff --git a/libraries/AP_Motors/AP_MotorsHexa.h b/libraries/AP_Motors/AP_MotorsHexa.h index 2c51911a2b..2b6de1dcde 100644 --- a/libraries/AP_Motors/AP_MotorsHexa.h +++ b/libraries/AP_Motors/AP_MotorsHexa.h @@ -16,7 +16,7 @@ class AP_MotorsHexa : public AP_MotorsMatrix { public: /// Constructor - 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) { + AP_MotorsHexa(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) { }; // setup_motors - configures the motors for a quad diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 93a9b1a697..3eb5fc2527 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -19,8 +19,8 @@ class AP_MotorsMatrix : public AP_Motors { public: /// Constructor - 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) + AP_MotorsMatrix(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) {}; // init diff --git a/libraries/AP_Motors/AP_MotorsOcta.h b/libraries/AP_Motors/AP_MotorsOcta.h index 0124e428b3..a122947726 100644 --- a/libraries/AP_Motors/AP_MotorsOcta.h +++ b/libraries/AP_Motors/AP_MotorsOcta.h @@ -16,7 +16,7 @@ class AP_MotorsOcta : public AP_MotorsMatrix { public: /// Constructor - 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) { + AP_MotorsOcta(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) { }; // setup_motors - configures the motors for a quad diff --git a/libraries/AP_Motors/AP_MotorsOctaQuad.h b/libraries/AP_Motors/AP_MotorsOctaQuad.h index e00dca743e..9e8dc4b7c8 100644 --- a/libraries/AP_Motors/AP_MotorsOctaQuad.h +++ b/libraries/AP_Motors/AP_MotorsOctaQuad.h @@ -16,7 +16,7 @@ class AP_MotorsOctaQuad : public AP_MotorsMatrix { public: /// Constructor - 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) { + AP_MotorsOctaQuad(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) { }; // setup_motors - configures the motors for a quad diff --git a/libraries/AP_Motors/AP_MotorsQuad.h b/libraries/AP_Motors/AP_MotorsQuad.h index cd32ac5dfc..82327d1a1e 100644 --- a/libraries/AP_Motors/AP_MotorsQuad.h +++ b/libraries/AP_Motors/AP_MotorsQuad.h @@ -16,7 +16,7 @@ class AP_MotorsQuad : public AP_MotorsMatrix { public: /// Constructor - 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) { + AP_MotorsQuad(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) { }; // setup_motors - configures the motors for a quad diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 795b12c055..43b287c449 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -25,8 +25,8 @@ class AP_MotorsSingle : public AP_Motors { public: /// Constructor - AP_MotorsSingle( RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, RC_Channel& servo1, RC_Channel& servo2, RC_Channel& servo3, RC_Channel& servo4, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz), + AP_MotorsSingle(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, RC_Channel& servo1, RC_Channel& servo2, RC_Channel& servo3, RC_Channel& servo4, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz), _servo1(servo1), _servo2(servo2), _servo3(servo3), diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index f457069a9e..d9584e9a6b 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -19,8 +19,8 @@ class AP_MotorsTri : public AP_Motors { public: /// Constructor - 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), + AP_MotorsTri(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, RC_Channel& rc_tail, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz), _rc_tail(rc_tail) { }; diff --git a/libraries/AP_Motors/AP_MotorsY6.h b/libraries/AP_Motors/AP_MotorsY6.h index a761edf6b1..2f2a8a04b6 100644 --- a/libraries/AP_Motors/AP_MotorsY6.h +++ b/libraries/AP_Motors/AP_MotorsY6.h @@ -18,7 +18,7 @@ class AP_MotorsY6 : public AP_MotorsMatrix { public: /// Constructor - 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) { + AP_MotorsY6(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_throttle, RC_Channel& rc_yaw, uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(rc_roll, rc_pitch, rc_throttle, rc_yaw, loop_rate, speed_hz) { }; // setup_motors - configures the motors for a quad