Copter: Support new RC_Channels::read_input()
This commit is contained in:
parent
2deac7238c
commit
91a48a5040
@ -95,9 +95,8 @@ void Copter::read_radio()
|
|||||||
{
|
{
|
||||||
uint32_t tnow_ms = millis();
|
uint32_t tnow_ms = millis();
|
||||||
|
|
||||||
if (RC_Channels::has_new_input()) {
|
if (RC_Channels::read_input()) {
|
||||||
ap.new_radio_frame = true;
|
ap.new_radio_frame = true;
|
||||||
RC_Channels::set_pwm_all();
|
|
||||||
|
|
||||||
set_throttle_and_failsafe(channel_throttle->get_radio_in());
|
set_throttle_and_failsafe(channel_throttle->get_radio_in());
|
||||||
set_throttle_zero_flag(channel_throttle->get_control_in());
|
set_throttle_zero_flag(channel_throttle->get_control_in());
|
||||||
|
Loading…
Reference in New Issue
Block a user