2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
2012-08-08 23:06:21 -03:00
|
|
|
|
|
|
|
/// @file GCS_MAVLink.cpp
|
|
|
|
|
|
|
|
/*
|
|
|
|
This provides some support code and variables for MAVLink enabled sketches
|
|
|
|
|
|
|
|
*/
|
2023-09-02 02:21:36 -03:00
|
|
|
|
|
|
|
#include "GCS_config.h"
|
|
|
|
|
2023-09-27 20:33:30 -03:00
|
|
|
#if HAL_MAVLINK_BINDINGS_ENABLED
|
2023-09-02 02:21:36 -03:00
|
|
|
|
2015-12-23 12:34:55 -04:00
|
|
|
#include "GCS.h"
|
|
|
|
#include "GCS_MAVLink.h"
|
2012-08-08 23:06:21 -03:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-12-23 12:34:55 -04:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-10-26 09:01:52 -03:00
|
|
|
|
2018-08-06 02:51:38 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2012-08-08 23:06:21 -03:00
|
|
|
|
2012-08-30 23:09:52 -03:00
|
|
|
#ifdef MAVLINK_SEPARATE_HELPERS
|
2017-01-31 14:03:45 -04:00
|
|
|
// Shut up warnings about missing declarations; TODO: should be fixed on
|
|
|
|
// mavlink/pymavlink project for when MAVLINK_SEPARATE_HELPERS is defined
|
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wmissing-declarations"
|
2016-01-11 18:22:05 -04:00
|
|
|
#include "include/mavlink/v2.0/mavlink_helpers.h"
|
2017-01-31 14:03:45 -04:00
|
|
|
#pragma GCC diagnostic pop
|
2016-01-11 18:22:05 -04:00
|
|
|
#endif
|
2012-08-30 23:09:52 -03:00
|
|
|
|
2023-09-27 20:33:30 -03:00
|
|
|
#endif // HAL_MAVLINK_BINDINGS_ENABLED
|
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
|
2015-05-15 02:40:23 -03:00
|
|
|
AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
|
2018-03-25 07:45:48 -03:00
|
|
|
bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS];
|
2012-08-08 23:06:21 -03:00
|
|
|
|
2018-08-06 02:51:38 -03:00
|
|
|
// per-channel lock
|
|
|
|
static HAL_Semaphore chan_locks[MAVLINK_COMM_NUM_BUFFERS];
|
2022-02-14 02:28:16 -04:00
|
|
|
static bool chan_discard[MAVLINK_COMM_NUM_BUFFERS];
|
2018-08-06 02:51:38 -03:00
|
|
|
|
2014-11-17 20:20:28 -04:00
|
|
|
mavlink_system_t mavlink_system = {7,1};
|
2012-08-08 23:06:21 -03:00
|
|
|
|
2014-12-09 23:02:08 -04:00
|
|
|
// routing table
|
|
|
|
MAVLink_routing GCS_MAVLINK::routing;
|
|
|
|
|
2023-02-23 01:06:48 -04:00
|
|
|
GCS_MAVLINK *GCS_MAVLINK::find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid) {
|
|
|
|
mavlink_channel_t channel;
|
|
|
|
if (!routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel)) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return gcs().chan(channel);
|
|
|
|
}
|
|
|
|
|
2023-02-24 00:01:58 -04:00
|
|
|
mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) {
|
|
|
|
GCS_MAVLINK *link = gcs().chan(chan);
|
|
|
|
if (link == nullptr) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return link->channel_buffer();
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_status_t* mavlink_get_channel_status(uint8_t chan) {
|
|
|
|
GCS_MAVLINK *link = gcs().chan(chan);
|
|
|
|
if (link == nullptr) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return link->channel_status();
|
|
|
|
}
|
|
|
|
|
2018-11-21 19:17:59 -04:00
|
|
|
// set a channel as private. Private channels get sent heartbeats, but
|
|
|
|
// don't get broadcast packets or forwarded packets
|
|
|
|
void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
|
|
|
|
{
|
|
|
|
const uint8_t mask = (1U<<(unsigned)_chan);
|
|
|
|
mavlink_private |= mask;
|
|
|
|
}
|
|
|
|
|
2019-02-06 22:55:46 -04:00
|
|
|
// return a MAVLink parameter type given a AP_Param type
|
2019-07-17 01:50:12 -03:00
|
|
|
MAV_PARAM_TYPE GCS_MAVLINK::mav_param_type(enum ap_var_type t)
|
2012-08-08 23:22:46 -03:00
|
|
|
{
|
|
|
|
if (t == AP_PARAM_INT8) {
|
2019-02-06 22:55:46 -04:00
|
|
|
return MAV_PARAM_TYPE_INT8;
|
2012-08-08 23:22:46 -03:00
|
|
|
}
|
|
|
|
if (t == AP_PARAM_INT16) {
|
2019-02-06 22:55:46 -04:00
|
|
|
return MAV_PARAM_TYPE_INT16;
|
2012-08-08 23:22:46 -03:00
|
|
|
}
|
|
|
|
if (t == AP_PARAM_INT32) {
|
2019-02-06 22:55:46 -04:00
|
|
|
return MAV_PARAM_TYPE_INT32;
|
2012-08-08 23:22:46 -03:00
|
|
|
}
|
|
|
|
// treat any others as float
|
2019-02-06 22:55:46 -04:00
|
|
|
return MAV_PARAM_TYPE_REAL32;
|
2012-08-08 23:22:46 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2014-04-03 23:19:15 -03:00
|
|
|
/// Check for available transmit space on the nominated MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to check
|
|
|
|
/// @returns Number of bytes available
|
|
|
|
uint16_t comm_get_txspace(mavlink_channel_t chan)
|
|
|
|
{
|
2019-09-12 03:14:55 -03:00
|
|
|
GCS_MAVLINK *link = gcs().chan(chan);
|
|
|
|
if (link == nullptr) {
|
2014-04-03 23:55:18 -03:00
|
|
|
return 0;
|
|
|
|
}
|
2019-09-12 03:14:55 -03:00
|
|
|
return link->txspace();
|
2014-04-03 23:19:15 -03:00
|
|
|
}
|
|
|
|
|
2013-01-08 00:31:01 -04:00
|
|
|
/*
|
|
|
|
send a buffer out a MAVLink channel
|
|
|
|
*/
|
|
|
|
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
|
|
|
{
|
2022-02-14 02:28:16 -04:00
|
|
|
if (!valid_channel(chan) || mavlink_comm_port[chan] == nullptr || chan_discard[chan]) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return;
|
|
|
|
}
|
2022-01-25 22:51:54 -04:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
// if it's a disabled high latency channel, don't send
|
|
|
|
GCS_MAVLINK *link = gcs().chan(chan);
|
2022-12-20 20:34:27 -04:00
|
|
|
if (link->is_high_latency_link && !gcs().get_high_latency_status()) {
|
2022-01-25 22:51:54 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2018-03-25 07:45:48 -03:00
|
|
|
if (gcs_alternative_active[chan]) {
|
|
|
|
// an alternative protocol is active
|
|
|
|
return;
|
|
|
|
}
|
2019-02-15 22:04:09 -04:00
|
|
|
const size_t written = mavlink_comm_port[chan]->write(buf, len);
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
if (written < len) {
|
2019-10-28 02:53:35 -03:00
|
|
|
AP_HAL::panic("Short write on UART: %lu < %u", (unsigned long)written, len);
|
2019-02-15 22:04:09 -04:00
|
|
|
}
|
|
|
|
#else
|
|
|
|
(void)written;
|
|
|
|
#endif
|
2013-01-08 00:31:01 -04:00
|
|
|
}
|
2018-08-06 02:51:38 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
lock a channel for send
|
2022-02-14 02:28:16 -04:00
|
|
|
if there is insufficient space to send size bytes then all bytes
|
|
|
|
written to the channel by the mavlink library will be discarded
|
|
|
|
while the lock is held.
|
2018-08-06 02:51:38 -03:00
|
|
|
*/
|
2022-02-14 02:28:16 -04:00
|
|
|
void comm_send_lock(mavlink_channel_t chan_m, uint16_t size)
|
2018-08-06 02:51:38 -03:00
|
|
|
{
|
2022-02-14 02:28:16 -04:00
|
|
|
const uint8_t chan = uint8_t(chan_m);
|
|
|
|
chan_locks[chan].take_blocking();
|
|
|
|
if (mavlink_comm_port[chan]->txspace() < size) {
|
|
|
|
chan_discard[chan] = true;
|
2022-07-08 03:27:11 -03:00
|
|
|
gcs_out_of_space_to_send(chan_m);
|
2022-02-14 02:28:16 -04:00
|
|
|
}
|
2018-08-06 02:51:38 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
unlock a channel
|
|
|
|
*/
|
2022-02-14 02:28:16 -04:00
|
|
|
void comm_send_unlock(mavlink_channel_t chan_m)
|
|
|
|
{
|
|
|
|
const uint8_t chan = uint8_t(chan_m);
|
|
|
|
chan_discard[chan] = false;
|
|
|
|
chan_locks[chan].give();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return reference to GCS channel lock, allowing for
|
|
|
|
HAVE_PAYLOAD_SPACE() to be run with a locked channel
|
|
|
|
*/
|
|
|
|
HAL_Semaphore &comm_chan_lock(mavlink_channel_t chan)
|
2018-08-06 02:51:38 -03:00
|
|
|
{
|
2022-02-14 02:28:16 -04:00
|
|
|
return chan_locks[uint8_t(chan)];
|
2018-08-06 02:51:38 -03:00
|
|
|
}
|
2023-09-02 02:21:36 -03:00
|
|
|
|
|
|
|
#endif // HAL_GCS_ENABLED
|