From abcb845af5201178e22f01510cd36e27e4b491a8 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Fri, 27 Apr 2018 12:22:07 -0400 Subject: [PATCH] AP_Motors: refactor output_test -> output_test_seq --- libraries/AP_Motors/AP_MotorsCoax.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsCoax.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Dual.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Quad.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Single.h | 4 ++-- libraries/AP_Motors/AP_MotorsMatrix.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsMatrix.h | 4 ++-- libraries/AP_Motors/AP_MotorsSingle.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsSingle.h | 4 ++-- libraries/AP_Motors/AP_MotorsTailsitter.h | 2 +- libraries/AP_Motors/AP_MotorsTri.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsTri.h | 4 ++-- libraries/AP_Motors/AP_Motors_Class.h | 4 ++-- .../AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp | 4 ++-- 18 files changed, 35 insertions(+), 35 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 1747ba5dc7..6539612c8e 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -210,10 +210,10 @@ void AP_MotorsCoax::output_armed_stabilizing() _actuator_out[3] = -_actuator_out[1]; } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsCoax::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsCoax::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index 99110425f2..34ca0669e4 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -37,10 +37,10 @@ public: // set update rate to motors - a value in hertz void set_update_rate( uint16_t speed_hz ); - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 87542566c7..005c9472a3 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -74,10 +74,10 @@ public: // output_min - sets servos to neutral point with motors stopped void output_min(); - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override = 0; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override = 0; // // heli specific methods diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 6d56554ae4..0dd659e7c2 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -212,10 +212,10 @@ bool AP_MotorsHeli_Dual::init_outputs() return true; } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsHeli_Dual::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsHeli_Dual::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index f68e5f3cb6..35a61a4fd1 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -58,8 +58,8 @@ public: // set_update_rate - set update rate to motors void set_update_rate( uint16_t speed_hz ) override; - // output_test - spin a motor at the pwm value specified - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + // output_test_seq - spin a motor at the pwm value specified + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index dbc17f728f..7ea8f76738 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -65,10 +65,10 @@ bool AP_MotorsHeli_Quad::init_outputs() return true; } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsHeli_Quad::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsHeli_Quad::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.h b/libraries/AP_Motors/AP_MotorsHeli_Quad.h index f3118b9134..a0a773ee5f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.h @@ -33,8 +33,8 @@ public: // set_update_rate - set update rate to motors void set_update_rate( uint16_t speed_hz ) override; - // output_test - spin a motor at the pwm value specified - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + // output_test_seq - spin a motor at the pwm value specified + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 458cea351c..87d37a3c4f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -180,10 +180,10 @@ bool AP_MotorsHeli_Single::init_outputs() return true; } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsHeli_Single::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsHeli_Single::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index c3999a71d6..1eb1b46fe9 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -60,10 +60,10 @@ public: // set update rate to motors - a value in hertz void set_update_rate(uint16_t speed_hz) override; - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index cfacf881b8..542ea48ded 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -280,10 +280,10 @@ void AP_MotorsMatrix::output_armed_stabilizing() } } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsMatrix::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsMatrix::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 1c51e77501..36723ca70e 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -29,10 +29,10 @@ public: // you must have setup_motors before calling this void set_update_rate(uint16_t speed_hz); - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 7decbe2ffc..81869b9603 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -226,10 +226,10 @@ void AP_MotorsSingle::output_armed_stabilizing() } } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsSingle::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 61d689fed7..5d37f73153 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -37,10 +37,10 @@ public: // set update rate to motors - a value in hertz void set_update_rate( uint16_t speed_hz ); - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index 7ccfd2ca16..ba230c7dbb 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -21,7 +21,7 @@ public: void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) {} void set_update_rate( uint16_t speed_hz ) {} - virtual void output_test(uint8_t motor_seq, int16_t pwm) override {} + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override {} // output_to_motors - sends output to named servos void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index ad7d712292..a784fb4334 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -241,10 +241,10 @@ void AP_MotorsTri::output_armed_stabilizing() _thrust_rear = constrain_float(_thrust_rear, 0.0f, 1.0f); } -// output_test - spin a motor at the pwm value specified +// output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 -void AP_MotorsTri::output_test(uint8_t motor_seq, int16_t pwm) +void AP_MotorsTri::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index d93fa3c299..ed57cf75a3 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -32,10 +32,10 @@ public: // set update rate to motors - a value in hertz void set_update_rate( uint16_t speed_hz ); - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index cead4d367d..fad6694aaa 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -136,10 +136,10 @@ public: // output_min - sends minimum values out to the motors virtual void output_min() = 0; - // output_test - spin a motor at the pwm value specified + // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0; + virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) = 0; // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 1d495a5e17..ed80d28c3d 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -112,9 +112,9 @@ void motor_order_test() motors.armed(true); for (int8_t i=1; i <= AP_MOTORS_MAX_NUM_MOTORS; i++) { hal.console->printf("Motor %d\n",(int)i); - motors.output_test(i, 1150); + motors.output_test_seq(i, 1150); hal.scheduler->delay(300); - motors.output_test(i, 1000); + motors.output_test_seq(i, 1000); hal.scheduler->delay(2000); } motors.armed(false);