GCS_Mavlink: refactor zero_rc_outputs() out of GCS_Mavlink

This commit is contained in:
yaapu 2020-09-10 14:53:40 +02:00 committed by Peter Barker
parent bc7c5a0c8e
commit e7a49dd624
2 changed files with 1 additions and 14 deletions

View File

@ -825,8 +825,6 @@ private:
// no idea where we are:
struct Location global_position_current_loc;
void zero_rc_outputs();
uint8_t last_tx_seq;
uint16_t send_packet_count;
uint16_t out_of_space_to_send_count; // number of times HAVE_PAYLOAD_SPACE and friends have returned false

View File

@ -2610,17 +2610,6 @@ void GCS_MAVLINK::send_vfr_hud()
vfr_hud_climbrate());
}
void GCS_MAVLINK::zero_rc_outputs()
{
// Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short
// For that matter, send an invalid signal to all channels to prevent undesired/unexpected behavior
SRV_Channels::cork();
for (int i=0; i<NUM_RC_CHANNELS; i++) {
hal.rcout->write(i, 0);
}
SRV_Channels::push();
}
/*
handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command
@ -2668,7 +2657,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
}
if (should_zero_rc_outputs_on_reboot()) {
zero_rc_outputs();
SRV_Channels::zero_rc_outputs();
}
// send ack before we reboot