mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
AP_HAL_SITL: suppress output until initialization is finished
This commit is contained in:
parent
07fa65a88c
commit
4413ebab7b
@ -45,6 +45,7 @@ void RCOutput::disable_ch(uint8_t ch)
|
||||
|
||||
void RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
_sitlState->output_ready = true;
|
||||
if (ch < SITL_NUM_CHANNELS && (_enable_mask & (1U<<ch))) {
|
||||
if (_corked) {
|
||||
_pending[ch] = period_us;
|
||||
|
@ -323,7 +323,7 @@ void SITL_State::_simulator_servos(SITL::Aircraft::sitl_input &input)
|
||||
* to change */
|
||||
uint8_t i;
|
||||
|
||||
if (last_update_usec == 0) {
|
||||
if (last_update_usec == 0 || !output_ready) {
|
||||
for (i=0; i<SITL_NUM_CHANNELS; i++) {
|
||||
pwm_output[i] = 1000;
|
||||
}
|
||||
|
@ -45,6 +45,7 @@ public:
|
||||
ssize_t gps_read(int fd, void *buf, size_t count);
|
||||
uint16_t pwm_output[SITL_NUM_CHANNELS];
|
||||
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS];
|
||||
bool output_ready = false;
|
||||
bool new_rc_input;
|
||||
void loop_hook(void);
|
||||
uint16_t base_port(void) const {
|
||||
|
Loading…
Reference in New Issue
Block a user