File tree 3 files changed +18
-1
lines changed
3 files changed +18
-1
lines changed Original file line number Diff line number Diff line change @@ -78,6 +78,13 @@ void AP_ODIDScanner::handle_msg(mavlink_message_t msg) {
78
78
last_dev_hb_ms = now_ms;
79
79
break ;
80
80
}
81
+ case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION:
82
+ {
83
+ mavlink_open_drone_id_location_t loc;
84
+ mavlink_msg_open_drone_id_location_decode (&msg, &loc);
85
+ // Handle the location message.
86
+ break ;
87
+ }
81
88
}
82
89
}
83
90
void AP_ODIDScanner::update () {
@@ -100,3 +107,6 @@ void AP_ODIDScanner::update() {
100
107
}
101
108
}
102
109
110
+ bool AP_ODIDScanner::message_from_rx (mavlink_channel_t & chan) {
111
+ return chan == _chan;
112
+ }
Original file line number Diff line number Diff line change @@ -25,6 +25,8 @@ class AP_ODIDScanner
25
25
void handle_msg (mavlink_message_t );
26
26
// mavlink_channel_t _chan; // mavlink channel that communicates with the remote id transceiver
27
27
uint8_t _mav_port;
28
+ bool message_from_rx (mavlink_channel_t & chan);
29
+
28
30
mavlink_uav_found_t found_msg;
29
31
mavlink_channel_t _chan;
30
32
AP_HAL::UARTDriver* _port;
Original file line number Diff line number Diff line change @@ -4168,7 +4168,12 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
4168
4168
case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID:
4169
4169
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM:
4170
4170
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE:
4171
- AP::opendroneid ().handle_msg (chan, msg);
4171
+ if (AP::vehicle ()->odidscanner .message_from_rx (chan)) {
4172
+ GCS_SEND_TEXT (MAV_SEVERITY_INFO, " Detected msg from odid-rx" );
4173
+ AP::vehicle ()->odidscanner .handle_msg (msg);
4174
+ } else {
4175
+ AP::opendroneid ().handle_msg (chan, msg);
4176
+ }
4172
4177
break ;
4173
4178
#endif
4174
4179
case MAVLINK_MSG_ID_UAV_FOUND:
You can’t perform that action at this time.
0 commit comments