Skip to content

Commit 65e6da7

Browse files
committed
GCS_MAVLink: handle RADIO_RC_CHANNELS
1 parent 6eb6306 commit 65e6da7

File tree

3 files changed

+29
-0
lines changed

3 files changed

+29
-0
lines changed

libraries/GCS_MAVLink/GCS.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -674,6 +674,7 @@ class GCS_MAVLINK
674674
void handle_optical_flow(const mavlink_message_t &msg);
675675

676676
void handle_manual_control(const mavlink_message_t &msg);
677+
void handle_radio_rc_channels(const mavlink_message_t &msg);
677678

678679
// default empty handling of LANDING_TARGET
679680
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }
@@ -738,6 +739,9 @@ class GCS_MAVLINK
738739
mavlink_message_t _channel_buffer;
739740
mavlink_status_t _channel_status;
740741

742+
// for mavlink radio
743+
mavlink_radio_t _mavlink_radio_packet;
744+
741745
const AP_SerialManager::UARTState *uartstate;
742746

743747
// last time we got a non-zero RSSI from RADIO_STATUS

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4037,6 +4037,9 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
40374037
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
40384038
handle_rc_channels_override(msg);
40394039
break;
4040+
case MAVLINK_MSG_ID_RADIO_RC_CHANNELS:
4041+
handle_radio_rc_channels(msg);
4042+
break;
40404043

40414044
#if AP_OPTICALFLOW_ENABLED
40424045
case MAVLINK_MSG_ID_OPTICAL_FLOW:
@@ -6344,6 +6347,12 @@ bool GCS_MAVLINK::accept_packet(const mavlink_status_t &status,
63446347
return true;
63456348
}
63466349

6350+
// handle messages from a mavlink receiver
6351+
if ((msg.compid == MAV_COMP_ID_TELEMETRY_RADIO) &&
6352+
(msg.msgid == MAVLINK_MSG_ID_RADIO_RC_CHANNELS)) {
6353+
return true;
6354+
}
6355+
63476356
if (!sysid_enforce()) {
63486357
return true;
63496358
}
@@ -6716,3 +6725,12 @@ MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_long_t
67166725
return MAV_RESULT_ACCEPTED;
67176726
}
67186727
#endif // HAL_HIGH_LATENCY2_ENABLED
6728+
6729+
void GCS_MAVLINK::handle_radio_rc_channels(const mavlink_message_t &msg)
6730+
{
6731+
mavlink_radio_rc_channels_t packet;
6732+
mavlink_msg_radio_rc_channels_decode(&msg, &packet);
6733+
6734+
AP::RC().handle_radio_rc_channels(&packet);
6735+
}
6736+

libraries/GCS_MAVLink/MAVLink_routing.cpp

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

130+
// handle messages from a mavlink receiver as if it had target_system = our system, target_component = 0
131+
if ((msg.compid == MAV_COMP_ID_TELEMETRY_RADIO) &&
132+
(msg.msgid == MAVLINK_MSG_ID_RADIO_RC_CHANNELS)) {
133+
target_system = mavlink_system.sysid;
134+
target_component = 0;
135+
}
136+
130137
bool broadcast_system = (target_system == 0 || target_system == -1);
131138
bool broadcast_component = (target_component == 0 || target_component == -1);
132139
bool match_system = broadcast_system || (target_system == mavlink_system.sysid);

0 commit comments

Comments
 (0)