2014-04-03 23:55:18 -03:00
|
|
|
/*
|
|
|
|
MAVLink SERIAL_CONTROL handling
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2023-09-01 10:13:34 -03:00
|
|
|
#include "GCS_config.h"
|
|
|
|
|
|
|
|
#if AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED
|
2014-04-03 23:55:18 -03:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "GCS.h"
|
2019-06-13 23:43:24 -03:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2014-04-03 23:55:18 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
/**
|
|
|
|
handle a SERIAL_CONTROL message
|
|
|
|
*/
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg)
|
2014-04-03 23:55:18 -03:00
|
|
|
{
|
|
|
|
mavlink_serial_control_t packet;
|
2019-07-11 05:31:45 -03:00
|
|
|
mavlink_msg_serial_control_decode(&msg, &packet);
|
2014-04-03 23:55:18 -03:00
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
AP_HAL::UARTDriver *port = nullptr;
|
2018-03-21 23:41:29 -03:00
|
|
|
AP_HAL::BetterStream *stream = nullptr;
|
2014-04-03 23:55:18 -03:00
|
|
|
|
|
|
|
if (packet.flags & SERIAL_CONTROL_FLAG_REPLY) {
|
|
|
|
// how did this packet get to us?
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
|
|
|
|
|
|
|
|
switch (packet.device) {
|
2019-09-12 03:14:55 -03:00
|
|
|
case SERIAL_CONTROL_DEV_TELEM1: {
|
|
|
|
GCS_MAVLINK *link = gcs().chan(1);
|
|
|
|
if (link == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
stream = port = link->get_uart();
|
|
|
|
link->lock(exclusive);
|
2014-04-03 23:55:18 -03:00
|
|
|
break;
|
2019-09-12 03:14:55 -03:00
|
|
|
}
|
|
|
|
case SERIAL_CONTROL_DEV_TELEM2: {
|
|
|
|
GCS_MAVLINK *link = gcs().chan(2);
|
|
|
|
if (link == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
stream = port = link->get_uart();
|
|
|
|
link->lock(exclusive);
|
2014-04-03 23:55:18 -03:00
|
|
|
break;
|
2019-09-12 03:14:55 -03:00
|
|
|
}
|
2024-02-14 04:26:12 -04:00
|
|
|
#if AP_GPS_ENABLED
|
2014-04-03 23:55:18 -03:00
|
|
|
case SERIAL_CONTROL_DEV_GPS1:
|
2020-12-10 20:18:38 -04:00
|
|
|
stream = port = hal.serial(3);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().lock_port(0, exclusive);
|
2014-04-03 23:55:18 -03:00
|
|
|
break;
|
|
|
|
case SERIAL_CONTROL_DEV_GPS2:
|
2020-12-10 20:18:38 -04:00
|
|
|
stream = port = hal.serial(4);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().lock_port(1, exclusive);
|
2014-04-03 23:55:18 -03:00
|
|
|
break;
|
2024-02-14 04:26:12 -04:00
|
|
|
#endif // AP_GPS_ENABLED
|
2015-06-17 04:05:48 -03:00
|
|
|
case SERIAL_CONTROL_DEV_SHELL:
|
|
|
|
stream = hal.util->get_shell_stream();
|
2018-03-31 02:26:05 -03:00
|
|
|
if (stream == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2015-06-17 04:05:48 -03:00
|
|
|
break;
|
2020-09-02 21:21:47 -03:00
|
|
|
case SERIAL_CONTROL_SERIAL0 ... SERIAL_CONTROL_SERIAL9: {
|
2019-11-30 20:59:22 -04:00
|
|
|
// direct access to a SERIALn port
|
|
|
|
stream = port = AP::serialmanager().get_serial_by_id(packet.device - SERIAL_CONTROL_SERIAL0);
|
2020-09-02 21:21:47 -03:00
|
|
|
|
|
|
|
// see if we need to lock mavlink
|
2022-12-13 20:34:19 -04:00
|
|
|
for (uint8_t i=0; i<gcs().num_gcs(); i++) {
|
2020-09-02 21:21:47 -03:00
|
|
|
GCS_MAVLINK *link = gcs().chan(i);
|
|
|
|
if (link == nullptr || link->get_uart() != port) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
link->lock(exclusive);
|
|
|
|
break;
|
|
|
|
}
|
2019-11-30 20:59:22 -04:00
|
|
|
break;
|
2020-09-02 21:21:47 -03:00
|
|
|
}
|
2019-11-30 20:59:22 -04:00
|
|
|
|
2014-04-03 23:55:18 -03:00
|
|
|
default:
|
|
|
|
// not supported yet
|
|
|
|
return;
|
|
|
|
}
|
2018-03-31 02:26:05 -03:00
|
|
|
if (stream == nullptr) {
|
|
|
|
// this is probably very bad
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
AP_HAL::panic("stream is nullptr");
|
|
|
|
#endif
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
if (exclusive && port != nullptr) {
|
2014-04-03 23:55:18 -03:00
|
|
|
// force flow control off for exclusive access. This protocol
|
|
|
|
// is used to talk to bootloaders which may not have flow
|
|
|
|
// control support
|
|
|
|
port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
|
|
|
}
|
|
|
|
|
|
|
|
// optionally change the baudrate
|
2016-10-30 02:24:21 -03:00
|
|
|
if (packet.baudrate != 0 && port != nullptr) {
|
2014-04-03 23:55:18 -03:00
|
|
|
port->begin(packet.baudrate);
|
|
|
|
}
|
|
|
|
|
|
|
|
// write the data
|
|
|
|
if (packet.count != 0) {
|
|
|
|
if ((packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
|
2015-06-17 04:05:48 -03:00
|
|
|
stream->write(packet.data, packet.count);
|
2014-04-03 23:55:18 -03:00
|
|
|
} else {
|
|
|
|
const uint8_t *data = &packet.data[0];
|
|
|
|
uint8_t count = packet.count;
|
|
|
|
while (count > 0) {
|
2015-06-17 04:05:48 -03:00
|
|
|
while (stream->txspace() <= 0) {
|
2014-04-03 23:55:18 -03:00
|
|
|
hal.scheduler->delay(5);
|
|
|
|
}
|
2015-06-17 04:05:48 -03:00
|
|
|
uint16_t n = stream->txspace();
|
2014-04-03 23:55:18 -03:00
|
|
|
if (n > packet.count) {
|
|
|
|
n = packet.count;
|
|
|
|
}
|
2015-06-17 04:05:48 -03:00
|
|
|
stream->write(data, n);
|
2014-04-03 23:55:18 -03:00
|
|
|
data += n;
|
|
|
|
count -= n;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if ((packet.flags & SERIAL_CONTROL_FLAG_RESPOND) == 0) {
|
|
|
|
// no response expected
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t flags = packet.flags;
|
|
|
|
|
|
|
|
more_data:
|
|
|
|
// sleep for the timeout
|
|
|
|
while (packet.timeout != 0 &&
|
2015-06-17 04:05:48 -03:00
|
|
|
stream->available() < (int16_t)sizeof(packet.data)) {
|
2014-04-03 23:55:18 -03:00
|
|
|
hal.scheduler->delay(1);
|
|
|
|
packet.timeout--;
|
|
|
|
}
|
|
|
|
|
|
|
|
packet.flags = SERIAL_CONTROL_FLAG_REPLY;
|
|
|
|
|
|
|
|
// work out how many bytes are available
|
2015-06-17 04:05:48 -03:00
|
|
|
int16_t available = stream->available();
|
2014-04-03 23:55:18 -03:00
|
|
|
if (available < 0) {
|
|
|
|
available = 0;
|
|
|
|
}
|
|
|
|
if (available > (int16_t)sizeof(packet.data)) {
|
|
|
|
available = sizeof(packet.data);
|
|
|
|
}
|
2015-06-17 04:05:48 -03:00
|
|
|
if (available == 0 && (flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) {
|
2016-04-05 01:09:47 -03:00
|
|
|
while (!HAVE_PAYLOAD_SPACE(chan, SERIAL_CONTROL)) {
|
2015-06-17 04:05:48 -03:00
|
|
|
hal.scheduler->delay(1);
|
|
|
|
}
|
|
|
|
} else {
|
2016-04-05 01:09:47 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, SERIAL_CONTROL)) {
|
2015-06-17 04:05:48 -03:00
|
|
|
// no space for reply
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2014-04-03 23:55:18 -03:00
|
|
|
|
|
|
|
// read any reply data
|
|
|
|
packet.count = 0;
|
2015-03-06 22:54:58 -04:00
|
|
|
memset(packet.data, 0, sizeof(packet.data));
|
2014-04-03 23:55:18 -03:00
|
|
|
while (available > 0) {
|
2015-06-17 04:05:48 -03:00
|
|
|
packet.data[packet.count++] = (uint8_t)stream->read();
|
2014-04-03 23:55:18 -03:00
|
|
|
available--;
|
|
|
|
}
|
|
|
|
|
|
|
|
// and send the reply
|
|
|
|
_mav_finalize_message_chan_send(chan,
|
2016-04-04 00:07:27 -03:00
|
|
|
MAVLINK_MSG_ID_SERIAL_CONTROL,
|
2014-04-03 23:55:18 -03:00
|
|
|
(const char *)&packet,
|
2016-04-06 06:30:03 -03:00
|
|
|
MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN,
|
2014-04-03 23:55:18 -03:00
|
|
|
MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
|
|
|
|
MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
|
|
|
|
if ((flags & SERIAL_CONTROL_FLAG_MULTI) && packet.count != 0) {
|
2015-06-17 04:05:48 -03:00
|
|
|
if (flags & SERIAL_CONTROL_FLAG_BLOCKING) {
|
|
|
|
hal.scheduler->delay(1);
|
|
|
|
}
|
2014-04-03 23:55:18 -03:00
|
|
|
goto more_data;
|
|
|
|
}
|
|
|
|
}
|
2023-09-01 10:13:34 -03:00
|
|
|
|
|
|
|
#endif // AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED
|