Copter: move handling of RC_CHANNELS_OVERRIDE up

This commit is contained in:
Peter Barker 2019-02-04 08:42:04 +11:00 committed by Peter Barker
parent 76fe58a3bd
commit 609b4f87c5
2 changed files with 7 additions and 28 deletions

View File

@ -526,6 +526,12 @@ void GCS_MAVLINK_Copter::send_banner()
send_text(MAV_SEVERITY_INFO, "Frame: %s", copter.get_frame_string());
}
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
void GCS_MAVLINK_Copter::handle_rc_channels_override(const mavlink_message_t *msg)
{
copter.failsafe.last_heartbeat_ms = AP_HAL::millis();
GCS_MAVLINK::handle_rc_channels_override(msg);
}
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t* msg)
{
@ -971,34 +977,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: // MAV ID: 70
{
// allow override of RC channel values for HIL
// or for complete GCS control of switch position
// and RC PWM values.
if(msg->sysid != copter.g.sysid_my_gcs) {
break; // Only accept control from our gcs
}
uint32_t tnow = AP_HAL::millis();
mavlink_rc_channels_override_t packet;
mavlink_msg_rc_channels_override_decode(msg, &packet);
RC_Channels::set_override(0, packet.chan1_raw, tnow);
RC_Channels::set_override(1, packet.chan2_raw, tnow);
RC_Channels::set_override(2, packet.chan3_raw, tnow);
RC_Channels::set_override(3, packet.chan4_raw, tnow);
RC_Channels::set_override(4, packet.chan5_raw, tnow);
RC_Channels::set_override(5, packet.chan6_raw, tnow);
RC_Channels::set_override(6, packet.chan7_raw, tnow);
RC_Channels::set_override(7, packet.chan8_raw, tnow);
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
copter.failsafe.last_heartbeat_ms = tnow;
break;
}
case MAVLINK_MSG_ID_MANUAL_CONTROL:
{
if (msg->sysid != copter.g.sysid_my_gcs) {

View File

@ -44,6 +44,7 @@ private:
void handle_command_ack(const mavlink_message_t* msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
void handle_rc_channels_override(const mavlink_message_t *msg) override;
bool try_send_message(enum ap_message id) override;
bool vehicle_initialised() const override;