mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: handle RADIO_RC_CHANNELS
This commit is contained in:
parent
31e2353c11
commit
0bb98c3db5
@ -690,6 +690,7 @@ protected:
|
||||
void handle_optical_flow(const mavlink_message_t &msg);
|
||||
|
||||
void handle_manual_control(const mavlink_message_t &msg);
|
||||
void handle_radio_rc_channels(const mavlink_message_t &msg);
|
||||
|
||||
// default empty handling of LANDING_TARGET
|
||||
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }
|
||||
|
@ -4193,6 +4193,11 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg)
|
||||
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
||||
handle_rc_channels_override(msg);
|
||||
break;
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
case MAVLINK_MSG_ID_RADIO_RC_CHANNELS:
|
||||
handle_radio_rc_channels(msg);
|
||||
break;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if AP_OPTICALFLOW_ENABLED
|
||||
@ -6976,4 +6981,14 @@ MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_int_t
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
void GCS_MAVLINK::handle_radio_rc_channels(const mavlink_message_t &msg)
|
||||
{
|
||||
mavlink_radio_rc_channels_t packet;
|
||||
mavlink_msg_radio_rc_channels_decode(&msg, &packet);
|
||||
|
||||
AP::RC().handle_radio_rc_channels(&packet);
|
||||
}
|
||||
#endif // AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user