mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
ACMotors: ESC Calibration only for enabled motors
This commit is contained in:
parent
33d1129904
commit
5bb0582854
@ -73,13 +73,15 @@ void AP_Motors::Init()
|
||||
setup_throttle_curve();
|
||||
};
|
||||
|
||||
// throttle_pass_through - passes throttle through to motors - dangerous but used for initialising ESCs
|
||||
// throttle_pass_through - passes pilot's throttle input directly to all motors - dangerous but used for initialising ESCs
|
||||
void AP_Motors::throttle_pass_through()
|
||||
{
|
||||
if( armed() ) {
|
||||
// XXX
|
||||
for( int16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
hal.rcout->write(_motor_to_channel_map[i], _rc_throttle->radio_in);
|
||||
if (armed()) {
|
||||
// send the pilot's input directly to each enabled motor
|
||||
for (int16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i]) {
|
||||
hal.rcout->write(_motor_to_channel_map[i], _rc_throttle->radio_in);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -126,7 +126,7 @@ public:
|
||||
virtual void output_test() {
|
||||
};
|
||||
|
||||
// throttle_pass_through - passes throttle through to motors - dangerous but required for initialising ESCs
|
||||
// throttle_pass_through - passes pilot's throttle input directly to all motors - dangerous but used for initialising ESCs
|
||||
virtual void throttle_pass_through();
|
||||
|
||||
// setup_throttle_curve - used to linearlise thrust output by motors
|
||||
|
Loading…
Reference in New Issue
Block a user