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
|
|
|
|
|
|
|
|
*/
|
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>
|
|
|
|
#include <AP_GPS/AP_GPS.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
|
|
|
|
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];
|
|
|
|
|
2014-11-17 20:20:28 -04:00
|
|
|
mavlink_system_t mavlink_system = {7,1};
|
2012-08-08 23:06:21 -03:00
|
|
|
|
2014-04-03 23:55:18 -03:00
|
|
|
// mask of serial ports disabled to allow for SERIAL_CONTROL
|
|
|
|
static uint8_t mavlink_locked_mask;
|
|
|
|
|
2014-12-09 23:02:08 -04:00
|
|
|
// routing table
|
|
|
|
MAVLink_routing GCS_MAVLINK::routing;
|
|
|
|
|
2014-04-03 23:55:18 -03:00
|
|
|
/*
|
|
|
|
lock a channel, preventing use by MAVLink
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
|
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(chan)) {
|
2014-04-03 23:55:18 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (lock) {
|
|
|
|
mavlink_locked_mask |= (1U<<(unsigned)_chan);
|
|
|
|
} else {
|
|
|
|
mavlink_locked_mask &= ~(1U<<(unsigned)_chan);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
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;
|
|
|
|
mavlink_active &= ~mask;
|
|
|
|
}
|
|
|
|
|
2019-02-06 22:55:46 -04:00
|
|
|
// return a MAVLink parameter type given a AP_Param type
|
|
|
|
MAV_PARAM_TYPE 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)
|
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(chan)) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return 0;
|
|
|
|
}
|
2014-04-03 23:55:18 -03:00
|
|
|
if ((1U<<chan) & mavlink_locked_mask) {
|
|
|
|
return 0;
|
|
|
|
}
|
2015-05-15 02:40:23 -03:00
|
|
|
int16_t ret = mavlink_comm_port[chan]->txspace();
|
2014-04-03 23:19:15 -03:00
|
|
|
if (ret < 0) {
|
|
|
|
ret = 0;
|
|
|
|
}
|
|
|
|
return (uint16_t)ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
/// Check for available data on the nominated MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to check
|
|
|
|
/// @returns Number of bytes available
|
|
|
|
uint16_t comm_get_available(mavlink_channel_t chan)
|
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(chan)) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return 0;
|
|
|
|
}
|
2014-04-03 23:55:18 -03:00
|
|
|
if ((1U<<chan) & mavlink_locked_mask) {
|
|
|
|
return 0;
|
|
|
|
}
|
2015-05-15 02:40:23 -03:00
|
|
|
int16_t bytes = mavlink_comm_port[chan]->available();
|
2014-04-03 23:19:15 -03:00
|
|
|
if (bytes == -1) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return (uint16_t)bytes;
|
|
|
|
}
|
|
|
|
|
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)
|
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(chan)) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return;
|
|
|
|
}
|
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-06-10 13:41:43 -03:00
|
|
|
AP_HAL::panic("Short write on UART: %lu < %u", 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
|
|
|
|
*/
|
|
|
|
void comm_send_lock(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
chan_locks[(uint8_t)chan].take_blocking();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
unlock a channel
|
|
|
|
*/
|
|
|
|
void comm_send_unlock(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
chan_locks[(uint8_t)chan].give();
|
|
|
|
}
|