diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index f9a93d4ecc..b4bc88c747 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -329,7 +329,7 @@ void AP_MotorsMatrix::output_disarmed() output_min(); } -// output_disarmed - sends commands to the motors +// output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction void AP_MotorsMatrix::output_test() { uint8_t min_order, max_order; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index ef7e0953bb..2400c4e4ed 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -39,7 +39,7 @@ public: // enable - starts allowing signals to be sent to motors virtual void enable(); - // motor test + // output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction virtual void output_test(); // output_min - sends minimum values out to the motors