mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Rover: use cork/push wrapper
This commit is contained in:
parent
a6c7890c74
commit
d57f307032
@ -200,9 +200,9 @@ void AP_MotorsUGV::output(bool armed, float dt)
|
||||
|
||||
// send values to the PWM timers for output
|
||||
SRV_Channels::calc_pwm();
|
||||
hal.rcout->cork();
|
||||
SRV_Channels::cork();
|
||||
SRV_Channels::output_ch_all();
|
||||
hal.rcout->push();
|
||||
SRV_Channels::push();
|
||||
_last_throttle = _throttle;
|
||||
}
|
||||
|
||||
@ -442,9 +442,9 @@ bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct)
|
||||
return false;
|
||||
}
|
||||
SRV_Channels::calc_pwm();
|
||||
hal.rcout->cork();
|
||||
SRV_Channels::cork();
|
||||
SRV_Channels::output_ch_all();
|
||||
hal.rcout->push();
|
||||
SRV_Channels::push();
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -488,8 +488,8 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm)
|
||||
return false;
|
||||
}
|
||||
SRV_Channels::calc_pwm();
|
||||
hal.rcout->cork();
|
||||
SRV_Channels::cork();
|
||||
SRV_Channels::output_ch_all();
|
||||
hal.rcout->push();
|
||||
SRV_Channels::push();
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user