Skip to content

Commit 33de704

Browse files
committed
GCS_MAVLink: handle RADIO_RC_CHANNELS
1 parent 2b52498 commit 33de704

File tree

3 files changed

+33
-0
lines changed

3 files changed

+33
-0
lines changed

libraries/GCS_MAVLink/GCS.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -683,6 +683,7 @@ class GCS_MAVLINK
683683
void handle_optical_flow(const mavlink_message_t &msg);
684684

685685
void handle_manual_control(const mavlink_message_t &msg);
686+
void handle_radio_rc_channels(const mavlink_message_t &msg);
686687

687688
// default empty handling of LANDING_TARGET
688689
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4102,6 +4102,11 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
41024102
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
41034103
handle_rc_channels_override(msg);
41044104
break;
4105+
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
4106+
case MAVLINK_MSG_ID_RADIO_RC_CHANNELS:
4107+
handle_radio_rc_channels(msg);
4108+
break;
4109+
#endif
41054110

41064111
#if AP_OPTICALFLOW_ENABLED
41074112
case MAVLINK_MSG_ID_OPTICAL_FLOW:
@@ -6407,6 +6412,14 @@ bool GCS_MAVLINK::accept_packet(const mavlink_status_t &status,
64076412
return true;
64086413
}
64096414

6415+
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
6416+
// handle messages from a mavlink receiver
6417+
if ((msg.compid == MAV_COMP_ID_TELEMETRY_RADIO) &&
6418+
(msg.msgid == MAVLINK_MSG_ID_RADIO_RC_CHANNELS)) {
6419+
return true;
6420+
}
6421+
#endif
6422+
64106423
if (!sysid_enforce()) {
64116424
return true;
64126425
}
@@ -6780,4 +6793,16 @@ MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_int_t
67806793
}
67816794
#endif // HAL_HIGH_LATENCY2_ENABLED
67826795

6796+
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
6797+
void GCS_MAVLINK::handle_radio_rc_channels(const mavlink_message_t &msg)
6798+
{
6799+
mavlink_radio_rc_channels_t packet;
6800+
mavlink_msg_radio_rc_channels_decode(&msg, &packet);
6801+
6802+
#if AP_RCPROTOCOL_ENABLED
6803+
AP::RC().handle_radio_rc_channels(&packet);
6804+
#endif
6805+
}
6806+
#endif
6807+
67836808
#endif // HAL_GCS_ENABLED

libraries/GCS_MAVLink/MAVLink_routing.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,13 @@ bool MAVLink_routing::check_and_forward(GCS_MAVLINK &in_link, const mavlink_mess
140140
int16_t target_component = -1;
141141
get_targets(msg, target_system, target_component);
142142

143+
// handle messages from a mavlink receiver as if it had target_system = our system, target_component = 0
144+
if ((msg.compid == MAV_COMP_ID_TELEMETRY_RADIO) &&
145+
(msg.msgid == MAVLINK_MSG_ID_RADIO_RC_CHANNELS)) {
146+
target_system = mavlink_system.sysid;
147+
target_component = 0;
148+
}
149+
143150
bool broadcast_system = (target_system == 0 || target_system == -1);
144151
bool broadcast_component = (target_component == 0 || target_component == -1);
145152
bool match_system = broadcast_system || (target_system == mavlink_system.sysid);

0 commit comments

Comments
 (0)