mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_Motors: refactor output_test -> output_test_seq
This commit is contained in:
parent
9ce9f95692
commit
abcb845af5
@ -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()) {
|
||||
|
@ -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();
|
||||
|
@ -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
|
||||
|
@ -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()) {
|
||||
|
@ -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;
|
||||
|
@ -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()) {
|
||||
|
@ -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;
|
||||
|
@ -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()) {
|
||||
|
@ -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;
|
||||
|
@ -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()) {
|
||||
|
@ -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();
|
||||
|
@ -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()) {
|
||||
|
@ -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();
|
||||
|
@ -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();
|
||||
|
@ -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()) {
|
||||
|
@ -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();
|
||||
|
@ -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
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user