mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: move serial_control case to base class
This commit is contained in:
parent
c7c9cb9b0f
commit
154b212545
@ -267,7 +267,7 @@ protected:
|
||||
void handle_common_camera_message(const mavlink_message_t *msg);
|
||||
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const;
|
||||
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
|
||||
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
|
||||
void handle_serial_control(const mavlink_message_t *msg);
|
||||
|
||||
void handle_common_message(mavlink_message_t *msg);
|
||||
void handle_setup_signing(const mavlink_message_t *msg);
|
||||
|
@ -1832,6 +1832,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
||||
handle_common_mission_message(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||
handle_serial_control(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
||||
/* fall through */
|
||||
case MAVLINK_MSG_ID_GPS_INPUT:
|
||||
|
@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal;
|
||||
/**
|
||||
handle a SERIAL_CONTROL message
|
||||
*/
|
||||
void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps)
|
||||
void GCS_MAVLINK::handle_serial_control(const mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_serial_control_t packet;
|
||||
mavlink_msg_serial_control_decode(msg, &packet);
|
||||
@ -40,6 +40,8 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps)
|
||||
return;
|
||||
}
|
||||
|
||||
AP_GPS *gps = get_gps();
|
||||
|
||||
bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
|
||||
|
||||
switch (packet.device) {
|
||||
@ -53,11 +55,17 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps)
|
||||
break;
|
||||
case SERIAL_CONTROL_DEV_GPS1:
|
||||
stream = port = hal.uartB;
|
||||
gps.lock_port(0, exclusive);
|
||||
if (gps == nullptr) {
|
||||
return;
|
||||
}
|
||||
gps->lock_port(0, exclusive);
|
||||
break;
|
||||
case SERIAL_CONTROL_DEV_GPS2:
|
||||
stream = port = hal.uartE;
|
||||
gps.lock_port(1, exclusive);
|
||||
if (gps == nullptr) {
|
||||
return;
|
||||
}
|
||||
gps->lock_port(1, exclusive);
|
||||
break;
|
||||
case SERIAL_CONTROL_DEV_SHELL:
|
||||
stream = hal.util->get_shell_stream();
|
||||
|
Loading…
Reference in New Issue
Block a user