Copter: passthrough pilot input to motors to allow wiggling servos

This commit is contained in:
Randy Mackay 2016-02-06 10:43:16 +09:00
parent 4f1e62d551
commit ce1fb7fb06
2 changed files with 10 additions and 0 deletions

View File

@ -923,6 +923,7 @@ private:
void read_radio();
void set_throttle_and_failsafe(uint16_t throttle_pwm);
void set_throttle_zero_flag(int16_t throttle_control);
void radio_passthrough_to_motors();
void init_barometer(bool full_calibration);
void read_barometer(void);
void init_sonar(void);

View File

@ -115,6 +115,9 @@ void Copter::read_radio()
// update output on any aux channels, for manual passthru
RC_Channel_aux::output_ch_all();
// pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters)
radio_passthrough_to_motors();
float dt = (tnow_ms - last_update_ms)*1.0e-3f;
rc_throttle_control_in_filter.apply(g.rc_3.control_in, dt);
last_update_ms = tnow_ms;
@ -191,3 +194,9 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control)
ap.throttle_zero = true;
}
}
// pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
void Copter::radio_passthrough_to_motors()
{
motors.set_radio_passthrough(channel_roll->control_in/1000.0f, channel_pitch->control_in/1000.0f, channel_throttle->control_in/1000.0f, channel_yaw->control_in/1000.0f);
}