2011-02-17 05:36:33 -04:00
|
|
|
/// @file GCS.h
|
2012-08-16 21:50:03 -03:00
|
|
|
/// @brief Interface definition for the various Ground Control System
|
|
|
|
// protocols.
|
2016-02-17 21:25:55 -04:00
|
|
|
#pragma once
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2022-07-14 02:23:04 -03:00
|
|
|
#include "GCS_config.h"
|
2021-08-18 08:42:18 -03:00
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
|
2023-02-06 06:26:40 -04:00
|
|
|
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe_config.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include "GCS_MAVLink.h"
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2013-11-23 06:45:42 -04:00
|
|
|
#include <stdint.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include "MAVLink_routing.h"
|
2018-06-21 23:46:56 -03:00
|
|
|
#include <AP_RTC/JitterCorrection.h>
|
2018-05-20 23:18:57 -03:00
|
|
|
#include <AP_Common/Bitmask.h>
|
2019-09-05 02:01:47 -03:00
|
|
|
#include <AP_LTM_Telem/AP_LTM_Telem.h>
|
2019-02-13 19:11:52 -04:00
|
|
|
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
2022-09-14 07:06:39 -03:00
|
|
|
#include <AP_Filesystem/AP_Filesystem_config.h>
|
2022-04-16 23:54:08 -03:00
|
|
|
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
2019-11-08 02:58:57 -04:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2023-05-26 01:16:12 -03:00
|
|
|
#include <AP_Mount/AP_Mount_config.h>
|
2022-11-06 19:42:46 -04:00
|
|
|
#include <AP_SerialManager/AP_SerialManager.h>
|
2019-07-16 23:32:05 -03:00
|
|
|
|
|
|
|
#include "ap_message.h"
|
2018-05-20 23:18:57 -03:00
|
|
|
|
2018-12-06 19:14:23 -04:00
|
|
|
#define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2020-04-14 20:09:28 -03:00
|
|
|
// macros used to determine if a message will fit in the space available.
|
|
|
|
|
2022-07-08 03:27:11 -03:00
|
|
|
void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
2023-01-05 19:33:51 -04:00
|
|
|
bool check_payload_size(mavlink_channel_t chan, uint16_t max_payload_len);
|
2020-04-14 08:08:54 -03:00
|
|
|
|
2020-04-14 20:09:28 -03:00
|
|
|
// important note: despite the names, these messages do NOT check to
|
|
|
|
// see if the payload will fit in the buffer. They check to see if
|
|
|
|
// the packed message along with any channel overhead will fit.
|
|
|
|
|
|
|
|
// PAYLOAD_SIZE returns the amount of space required to send the
|
|
|
|
// mavlink message with id id on channel chan. Mavlink2 has higher
|
|
|
|
// overheads than mavlink1, for example.
|
2020-03-29 19:49:07 -03:00
|
|
|
|
|
|
|
// check if a message will fit in the payload space available
|
2019-09-12 03:14:55 -03:00
|
|
|
#define PAYLOAD_SIZE(chan, id) (unsigned(GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN))
|
2020-04-14 20:09:28 -03:00
|
|
|
|
|
|
|
// HAVE_PAYLOAD_SPACE evaluates to an expression that can be used
|
|
|
|
// anywhere in the code to determine if the mavlink message with ID id
|
2020-04-14 08:08:54 -03:00
|
|
|
// can currently fit in the output of _chan. Note the use of the ","
|
|
|
|
// operator here to increment a counter.
|
2022-07-08 03:27:11 -03:00
|
|
|
#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send(_chan), false))
|
2020-04-14 20:09:28 -03:00
|
|
|
|
|
|
|
// CHECK_PAYLOAD_SIZE - macro which may only be used within a
|
|
|
|
// GCS_MAVLink object's methods. It inserts code which will
|
|
|
|
// immediately return false from the current function if there is no
|
|
|
|
// room to fit the mavlink message with id id on the current object's
|
|
|
|
// output
|
2023-01-05 19:33:51 -04:00
|
|
|
#define CHECK_PAYLOAD_SIZE(id) if (!check_payload_size(MAVLINK_MSG_ID_ ## id ## _LEN)) return false
|
2020-04-14 20:09:28 -03:00
|
|
|
|
|
|
|
// CHECK_PAYLOAD_SIZE2 - macro which inserts code which will
|
|
|
|
// immediately return false from the current function if there is no
|
|
|
|
// room to fit the mavlink message with id id on the mavlink output
|
|
|
|
// channel "chan". It is expecting there to be a "chan" variable in
|
|
|
|
// scope.
|
2015-07-24 04:18:14 -03:00
|
|
|
#define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
|
|
|
|
|
2022-08-30 20:50:29 -03:00
|
|
|
// CHECK_PAYLOAD_SIZE2_VOID - macro which inserts code which will
|
|
|
|
// immediately return from the current (void) function if there is no
|
|
|
|
// room to fit the mavlink message with id id on the mavlink output
|
|
|
|
// channel "chan".
|
|
|
|
#define CHECK_PAYLOAD_SIZE2_VOID(chan, id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return
|
|
|
|
|
2017-08-21 00:04:47 -03:00
|
|
|
// convenience macros for defining which ap_message ids are in which streams:
|
|
|
|
#define MAV_STREAM_ENTRY(stream_name) \
|
|
|
|
{ \
|
|
|
|
GCS_MAVLINK::stream_name, \
|
|
|
|
stream_name ## _msgs, \
|
|
|
|
ARRAY_SIZE(stream_name ## _msgs) \
|
|
|
|
}
|
2018-05-21 00:49:10 -03:00
|
|
|
#define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 }
|
2017-08-21 00:04:47 -03:00
|
|
|
|
2022-12-13 21:14:18 -04:00
|
|
|
// code generation; avoid each subclass duplicating these two methods
|
|
|
|
// and just changing the name. These methods allow retrieval of
|
|
|
|
// objects specific to the vehicle's subclass, which the vehicle can
|
|
|
|
// then call its own specific methods on
|
|
|
|
#define GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(subclass_name) \
|
|
|
|
subclass_name *chan(const uint8_t ofs) override { \
|
2022-12-15 01:13:46 -04:00
|
|
|
if (ofs >= _num_gcs) { \
|
2022-12-13 21:14:18 -04:00
|
|
|
return nullptr; \
|
|
|
|
} \
|
|
|
|
return (subclass_name *)_chan[ofs]; \
|
|
|
|
} \
|
|
|
|
\
|
|
|
|
const subclass_name *chan(const uint8_t ofs) const override { \
|
2022-12-15 01:13:46 -04:00
|
|
|
if (ofs >= _num_gcs) { \
|
2022-12-13 21:14:18 -04:00
|
|
|
return nullptr; \
|
|
|
|
} \
|
|
|
|
return (subclass_name *)_chan[ofs]; \
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
#define GCS_MAVLINK_NUM_STREAM_RATES 10
|
|
|
|
class GCS_MAVLINK_Parameters
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
GCS_MAVLINK_Parameters();
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
// saveable rate of each stream
|
|
|
|
AP_Int16 streamRates[GCS_MAVLINK_NUM_STREAM_RATES];
|
|
|
|
};
|
|
|
|
|
2021-06-02 00:06:13 -03:00
|
|
|
#if HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED
|
|
|
|
class DefaultIntervalsFromFiles
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
DefaultIntervalsFromFiles(uint16_t max_num);
|
|
|
|
~DefaultIntervalsFromFiles();
|
|
|
|
|
|
|
|
void set(ap_message id, uint16_t interval);
|
|
|
|
uint16_t num_intervals() const {
|
|
|
|
return _num_intervals;
|
|
|
|
}
|
|
|
|
bool get_interval_for_ap_message_id(ap_message id, uint16_t &interval) const;
|
|
|
|
ap_message id_at(uint8_t ofs) const;
|
|
|
|
uint16_t interval_at(uint8_t ofs) const;
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
struct from_file_default_interval {
|
|
|
|
ap_message id;
|
|
|
|
uint16_t interval;
|
|
|
|
};
|
|
|
|
|
|
|
|
from_file_default_interval *_intervals;
|
|
|
|
|
|
|
|
uint16_t _num_intervals;
|
|
|
|
uint16_t _max_intervals;
|
|
|
|
};
|
|
|
|
#endif
|
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
class GCS_MAVLINK_InProgress
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
enum class Type {
|
|
|
|
NONE,
|
|
|
|
AIRSPEED_CAL,
|
2022-12-08 02:47:18 -04:00
|
|
|
SD_FORMAT,
|
2022-12-08 02:47:13 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// these can fail if there's no space on the channel to send the ack:
|
|
|
|
bool conclude(MAV_RESULT result);
|
|
|
|
bool send_in_progress();
|
2022-12-08 02:47:18 -04:00
|
|
|
// abort task without sending any further ACKs:
|
|
|
|
void abort() { task = Type::NONE; }
|
2022-12-08 02:47:13 -04:00
|
|
|
|
|
|
|
Type task;
|
|
|
|
MAV_CMD mav_cmd;
|
|
|
|
|
2023-08-11 22:14:23 -03:00
|
|
|
static class GCS_MAVLINK_InProgress *get_task(MAV_CMD cmd, Type t, uint8_t sysid, uint8_t compid, mavlink_channel_t chan);
|
2022-12-08 02:47:13 -04:00
|
|
|
|
|
|
|
static void check_tasks();
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
uint8_t requesting_sysid;
|
|
|
|
uint8_t requesting_compid;
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
|
|
|
|
bool send_ack(MAV_RESULT result);
|
|
|
|
|
|
|
|
static GCS_MAVLINK_InProgress in_progress_tasks[1];
|
|
|
|
|
|
|
|
// allocate a task-tracking ID
|
|
|
|
static uint32_t last_check_ms;
|
|
|
|
};
|
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
///
|
|
|
|
/// @class GCS_MAVLINK
|
2014-12-09 23:39:32 -04:00
|
|
|
/// @brief MAVLink transport control class
|
2011-02-17 05:36:33 -04:00
|
|
|
///
|
2014-12-09 23:39:32 -04:00
|
|
|
class GCS_MAVLINK
|
2011-02-17 05:36:33 -04:00
|
|
|
{
|
|
|
|
public:
|
2018-03-25 07:45:48 -03:00
|
|
|
friend class GCS;
|
2018-12-10 03:56:32 -04:00
|
|
|
|
|
|
|
GCS_MAVLINK(GCS_MAVLINK_Parameters ¶meters, AP_HAL::UARTDriver &uart);
|
|
|
|
virtual ~GCS_MAVLINK() {}
|
|
|
|
|
2023-02-24 00:01:58 -04:00
|
|
|
// accessors used to retrieve objects used for parsing incoming messages:
|
|
|
|
mavlink_message_t *channel_buffer() { return &_channel_buffer; }
|
|
|
|
mavlink_status_t *channel_status() { return &_channel_status; }
|
|
|
|
|
2018-05-20 23:18:57 -03:00
|
|
|
void update_receive(uint32_t max_time_us=1000);
|
|
|
|
void update_send();
|
2018-12-10 03:56:32 -04:00
|
|
|
bool init(uint8_t instance);
|
2012-08-16 21:50:03 -03:00
|
|
|
void send_message(enum ap_message id);
|
2019-07-23 05:33:56 -03:00
|
|
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...) const FMT_PRINTF(3, 4);
|
2012-08-16 21:50:03 -03:00
|
|
|
void queued_param_send();
|
2019-01-15 20:14:08 -04:00
|
|
|
void queued_mission_request_send();
|
2019-04-28 23:52:02 -03:00
|
|
|
|
2019-08-02 04:54:44 -03:00
|
|
|
bool sending_mavlink1() const;
|
|
|
|
|
2019-04-28 23:52:02 -03:00
|
|
|
// returns true if we are requesting any items from the GCS:
|
|
|
|
bool requesting_mission_items() const;
|
|
|
|
|
2019-09-12 03:14:55 -03:00
|
|
|
/// Check for available transmit space
|
|
|
|
uint16_t txspace() const {
|
|
|
|
if (_locked) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
// there were concerns over return a too-large value for
|
|
|
|
// txspace (in case we tried to do too much with the space in
|
|
|
|
// a single loop):
|
|
|
|
return MIN(_port->txspace(), 8192U);
|
|
|
|
}
|
|
|
|
|
2023-01-05 19:33:51 -04:00
|
|
|
bool check_payload_size(uint16_t max_payload_len);
|
|
|
|
|
2020-04-14 08:08:54 -03:00
|
|
|
// this is called when we discover we'd like to send something but can't:
|
|
|
|
void out_of_space_to_send() { out_of_space_to_send_count++; }
|
|
|
|
|
2019-04-28 23:52:02 -03:00
|
|
|
void send_mission_ack(const mavlink_message_t &msg,
|
|
|
|
MAV_MISSION_TYPE mission_type,
|
|
|
|
MAV_MISSION_RESULT result) const {
|
2022-08-30 20:50:29 -03:00
|
|
|
CHECK_PAYLOAD_SIZE2_VOID(chan, MISSION_ACK);
|
2019-04-28 23:52:02 -03:00
|
|
|
mavlink_msg_mission_ack_send(chan,
|
|
|
|
msg.sysid,
|
|
|
|
msg.compid,
|
|
|
|
result,
|
|
|
|
mission_type);
|
|
|
|
}
|
|
|
|
|
2016-06-14 22:04:40 -03:00
|
|
|
// packetReceived is called on any successful decode of a mavlink message
|
|
|
|
virtual void packetReceived(const mavlink_status_t &status,
|
2019-07-11 05:31:45 -03:00
|
|
|
const mavlink_message_t &msg);
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2018-11-06 22:11:08 -04:00
|
|
|
// send a mavlink_message_t out this GCS_MAVLINK connection.
|
2023-02-24 01:02:57 -04:00
|
|
|
void send_message(uint32_t msgid, const char *pkt) {
|
2018-11-06 22:11:08 -04:00
|
|
|
const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
|
|
|
|
if (entry == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
send_message(pkt, entry);
|
|
|
|
}
|
2023-02-24 01:02:57 -04:00
|
|
|
void send_message(const char *pkt, const mavlink_msg_entry_t *entry) {
|
|
|
|
if (!check_payload_size(entry->max_msg_len)) {
|
|
|
|
return;
|
|
|
|
}
|
2018-11-06 22:11:08 -04:00
|
|
|
_mav_finalize_message_chan_send(chan,
|
|
|
|
entry->msgid,
|
|
|
|
pkt,
|
|
|
|
entry->min_msg_len,
|
|
|
|
entry->max_msg_len,
|
|
|
|
entry->crc_extra);
|
|
|
|
}
|
|
|
|
|
2015-01-27 09:31:51 -04:00
|
|
|
// accessor for uart
|
|
|
|
AP_HAL::UARTDriver *get_uart() { return _port; }
|
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
virtual uint8_t sysid_my_gcs() const = 0;
|
2018-12-13 19:12:09 -04:00
|
|
|
virtual bool sysid_enforce() const { return false; }
|
2017-07-12 04:21:15 -03:00
|
|
|
|
2023-02-01 03:25:14 -04:00
|
|
|
// NOTE: param_name here must point to a 16+1 byte buffer - so do
|
|
|
|
// NOT try to pass in a static-char-* unless it does have that
|
|
|
|
// length!
|
2019-06-04 01:15:36 -03:00
|
|
|
void send_parameter_value(const char *param_name,
|
|
|
|
ap_var_type param_type,
|
|
|
|
float param_value);
|
|
|
|
|
2012-04-01 22:18:42 -03:00
|
|
|
// NOTE! The streams enum below and the
|
|
|
|
// set of AP_Int16 stream rates _must_ be
|
|
|
|
// kept in the same order
|
2018-05-21 00:49:10 -03:00
|
|
|
enum streams : uint8_t {
|
|
|
|
STREAM_RAW_SENSORS,
|
|
|
|
STREAM_EXTENDED_STATUS,
|
|
|
|
STREAM_RC_CHANNELS,
|
|
|
|
STREAM_RAW_CONTROLLER,
|
|
|
|
STREAM_POSITION,
|
|
|
|
STREAM_EXTRA1,
|
|
|
|
STREAM_EXTRA2,
|
|
|
|
STREAM_EXTRA3,
|
|
|
|
STREAM_PARAMS,
|
|
|
|
STREAM_ADSB,
|
|
|
|
NUM_STREAMS
|
|
|
|
};
|
2012-04-01 22:18:42 -03:00
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
// streams must be moved out into the top level for
|
|
|
|
// GCS_MAVLINK_Parameters to be able to use it. This is an
|
|
|
|
// extensive change, so we 'll just keep them in sync with a
|
|
|
|
// static assert for now:
|
|
|
|
static_assert(NUM_STREAMS == GCS_MAVLINK_NUM_STREAM_RATES, "num streams must equal num stream rates");
|
|
|
|
|
2017-06-15 03:09:02 -03:00
|
|
|
bool is_high_bandwidth() { return chan == MAVLINK_COMM_0; }
|
|
|
|
// return true if this channel has hardware flow control
|
|
|
|
bool have_flow_control();
|
|
|
|
|
2018-11-06 21:06:47 -04:00
|
|
|
bool is_active() const {
|
|
|
|
return GCS_MAVLINK::active_channel_mask() & (1 << (chan-MAVLINK_COMM_0));
|
|
|
|
}
|
|
|
|
bool is_streaming() const {
|
2019-06-06 20:23:06 -03:00
|
|
|
return sending_bucket_id != no_bucket_to_send;
|
2018-11-06 21:06:47 -04:00
|
|
|
}
|
|
|
|
|
2017-06-15 03:09:02 -03:00
|
|
|
mavlink_channel_t get_chan() const { return chan; }
|
|
|
|
uint32_t get_last_heartbeat_time() const { return last_heartbeat_time; };
|
|
|
|
|
2013-12-15 18:57:28 -04:00
|
|
|
uint32_t last_heartbeat_time; // milliseconds
|
|
|
|
|
2020-06-03 23:06:30 -03:00
|
|
|
static uint32_t last_radio_status_remrssi_ms() {
|
|
|
|
return last_radio_status.remrssi_ms;
|
|
|
|
}
|
2020-06-03 23:02:56 -03:00
|
|
|
static float telemetry_radio_rssi(); // 0==no signal, 1==full signal
|
2014-03-18 18:44:58 -03:00
|
|
|
|
2015-07-24 04:18:14 -03:00
|
|
|
// mission item index to be sent on queued msg, delayed or not
|
|
|
|
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
|
|
|
|
|
2023-04-19 03:13:59 -03:00
|
|
|
// generate a MISSION_STATE enumeration value for where the
|
|
|
|
// mission is up to:
|
2023-04-19 03:53:38 -03:00
|
|
|
virtual MISSION_STATE mission_state(const class AP_Mission &mission) const;
|
2023-04-19 03:13:59 -03:00
|
|
|
// send a mission_current message for the supplied waypoint
|
|
|
|
void send_mission_current(const class AP_Mission &mission, uint16_t seq);
|
|
|
|
|
2013-12-28 01:00:19 -04:00
|
|
|
// common send functions
|
2018-05-02 05:37:08 -03:00
|
|
|
void send_heartbeat(void) const;
|
2013-12-28 01:00:19 -04:00
|
|
|
void send_meminfo(void);
|
2019-01-30 22:10:35 -04:00
|
|
|
void send_fence_status() const;
|
2014-02-13 07:07:13 -04:00
|
|
|
void send_power_status(void);
|
2021-08-22 22:40:05 -03:00
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
void send_mcu_status(void);
|
|
|
|
#endif
|
2019-06-13 19:57:04 -03:00
|
|
|
void send_battery_status(const uint8_t instance) const;
|
2020-06-12 20:29:00 -03:00
|
|
|
bool send_battery_status();
|
2021-02-17 04:13:04 -04:00
|
|
|
void send_distance_sensor();
|
2018-12-18 06:47:01 -04:00
|
|
|
// send_rangefinder sends only if a downward-facing instance is
|
|
|
|
// found. Rover overrides this!
|
|
|
|
virtual void send_rangefinder() const;
|
2021-02-17 04:13:04 -04:00
|
|
|
void send_proximity();
|
2018-05-04 21:07:59 -03:00
|
|
|
virtual void send_nav_controller_output() const = 0;
|
2019-02-28 19:24:13 -04:00
|
|
|
virtual void send_pid_tuning() = 0;
|
2018-01-05 21:27:09 -04:00
|
|
|
void send_ahrs2();
|
2021-10-15 20:17:03 -03:00
|
|
|
void send_system_time() const;
|
2019-07-06 19:48:16 -03:00
|
|
|
void send_rc_channels() const;
|
|
|
|
void send_rc_channels_raw() const;
|
2018-05-02 22:31:47 -03:00
|
|
|
void send_raw_imu();
|
2018-12-07 02:30:32 -04:00
|
|
|
|
2020-07-27 13:04:00 -03:00
|
|
|
void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff));
|
2018-03-05 16:36:45 -04:00
|
|
|
void send_scaled_pressure();
|
2018-12-07 02:30:32 -04:00
|
|
|
void send_scaled_pressure2();
|
|
|
|
virtual void send_scaled_pressure3(); // allow sub to override this
|
2021-08-06 01:35:24 -03:00
|
|
|
void send_simstate() const;
|
2021-01-15 03:54:37 -04:00
|
|
|
void send_sim_state() const;
|
2018-01-05 21:27:09 -04:00
|
|
|
void send_ahrs();
|
2022-10-14 21:50:49 -03:00
|
|
|
#if AP_MAVLINK_BATTERY2_ENABLED
|
2018-05-02 05:10:18 -03:00
|
|
|
void send_battery2();
|
2022-10-14 21:50:49 -03:00
|
|
|
#endif
|
2018-09-02 03:32:50 -03:00
|
|
|
void send_opticalflow();
|
2018-05-02 03:50:28 -03:00
|
|
|
virtual void send_attitude() const;
|
2021-03-03 02:42:44 -04:00
|
|
|
virtual void send_attitude_quaternion() const;
|
2017-09-05 02:58:32 -03:00
|
|
|
void send_autopilot_version() const;
|
2018-05-23 06:07:10 -03:00
|
|
|
void send_extended_sys_state() const;
|
2018-01-05 21:27:09 -04:00
|
|
|
void send_local_position() const;
|
2018-05-09 07:55:37 -03:00
|
|
|
void send_vfr_hud();
|
2018-05-02 06:27:31 -03:00
|
|
|
void send_vibration() const;
|
2022-07-11 05:08:01 -03:00
|
|
|
void send_gimbal_device_attitude_status() const;
|
2023-04-24 01:59:55 -03:00
|
|
|
void send_gimbal_manager_information() const;
|
2023-05-09 09:25:33 -03:00
|
|
|
void send_gimbal_manager_status() const;
|
2018-05-15 02:20:30 -03:00
|
|
|
void send_named_float(const char *name, float value) const;
|
2019-02-24 21:43:47 -04:00
|
|
|
void send_home_position() const;
|
|
|
|
void send_gps_global_origin() const;
|
2022-02-03 01:33:10 -04:00
|
|
|
virtual void send_attitude_target() {};
|
2018-05-11 08:54:48 -03:00
|
|
|
virtual void send_position_target_global_int() { };
|
2019-03-28 06:38:08 -03:00
|
|
|
virtual void send_position_target_local_ned() { };
|
2018-05-10 03:56:25 -03:00
|
|
|
void send_servo_output_raw();
|
2017-05-29 18:03:10 -03:00
|
|
|
void send_accelcal_vehicle_position(uint32_t position);
|
2019-10-02 16:57:50 -03:00
|
|
|
void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature));
|
2019-01-22 21:36:45 -04:00
|
|
|
void send_sys_status();
|
2019-03-08 01:39:59 -04:00
|
|
|
void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
|
2019-03-01 18:38:12 -04:00
|
|
|
void send_rpm() const;
|
2019-11-06 20:41:16 -04:00
|
|
|
void send_generator_status() const;
|
2020-07-22 08:05:20 -03:00
|
|
|
virtual void send_winch_status() const {};
|
2021-06-15 22:35:18 -03:00
|
|
|
void send_water_depth() const;
|
2021-09-21 10:53:24 -03:00
|
|
|
int8_t battery_remaining_pct(const uint8_t instance) const;
|
|
|
|
|
2021-06-10 07:56:46 -03:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
2021-07-07 23:10:54 -03:00
|
|
|
void send_high_latency2() const;
|
2021-06-10 07:56:46 -03:00
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
2021-10-13 20:26:20 -03:00
|
|
|
void send_uavionix_adsb_out_status() const;
|
2022-06-01 08:03:09 -03:00
|
|
|
void send_autopilot_state_for_gimbal_device() const;
|
2013-12-28 01:00:19 -04:00
|
|
|
|
2019-09-12 03:14:55 -03:00
|
|
|
// lock a channel, preventing use by MAVLink
|
|
|
|
void lock(bool _lock) {
|
|
|
|
_locked = _lock;
|
|
|
|
}
|
|
|
|
// returns true if this channel isn't available for MAVLink
|
|
|
|
bool locked() const {
|
|
|
|
return _locked;
|
|
|
|
}
|
2019-07-17 02:45:07 -03:00
|
|
|
|
2014-07-17 08:03:12 -03:00
|
|
|
// return a bitmap of active channels. Used by libraries to loop
|
|
|
|
// over active channels to send to all active channels
|
|
|
|
static uint8_t active_channel_mask(void) { return mavlink_active; }
|
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
// return a bitmap of streaming channels
|
|
|
|
static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
|
|
|
|
|
2019-08-27 02:15:46 -03:00
|
|
|
// return a bitmap of private channels
|
|
|
|
static uint8_t private_channel_mask(void) { return mavlink_private; }
|
|
|
|
|
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
|
|
|
|
static void set_channel_private(mavlink_channel_t chan);
|
|
|
|
|
|
|
|
// return true if channel is private
|
|
|
|
static bool is_private(mavlink_channel_t _chan) {
|
|
|
|
return (mavlink_private & (1U<<(unsigned)_chan)) != 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return true if channel is private
|
|
|
|
bool is_private(void) const { return is_private(chan); }
|
|
|
|
|
2022-01-25 22:51:54 -04:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
2022-12-20 20:34:27 -04:00
|
|
|
// true if this is a high latency link
|
|
|
|
bool is_high_latency_link;
|
2022-01-25 22:51:54 -04:00
|
|
|
#endif
|
|
|
|
|
2015-03-28 22:36:06 -03:00
|
|
|
/*
|
|
|
|
send a MAVLink message to all components with this vehicle's system id
|
|
|
|
This is a no-op if no routes to components have been learned
|
|
|
|
*/
|
2019-10-17 04:07:23 -03:00
|
|
|
static void send_to_components(uint32_t msgid, const char *pkt, uint8_t pkt_len) { routing.send_to_components(msgid, pkt, pkt_len); }
|
|
|
|
|
2016-05-11 06:24:59 -03:00
|
|
|
/*
|
|
|
|
allow forwarding of packets / heartbeats to be blocked as required by some components to reduce traffic
|
|
|
|
*/
|
|
|
|
static void disable_channel_routing(mavlink_channel_t chan) { routing.no_route_mask |= (1U<<(chan-MAVLINK_COMM_0)); }
|
|
|
|
|
2015-07-24 08:52:56 -03:00
|
|
|
/*
|
|
|
|
search for a component in the routing table with given mav_type and retrieve it's sysid, compid and channel
|
|
|
|
returns if a matching component is found
|
|
|
|
*/
|
|
|
|
static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) { return routing.find_by_mavtype(mav_type, sysid, compid, channel); }
|
|
|
|
|
2022-09-07 05:18:53 -03:00
|
|
|
/*
|
|
|
|
search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel
|
|
|
|
returns true if a match is found
|
|
|
|
*/
|
|
|
|
static bool find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) { return routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel); }
|
2023-02-23 01:06:48 -04:00
|
|
|
// same as above, but returns a pointer to the GCS_MAVLINK object
|
|
|
|
// corresponding to the channel
|
|
|
|
static GCS_MAVLINK *find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid);
|
2022-09-07 05:18:53 -03:00
|
|
|
|
2016-01-21 02:55:50 -04:00
|
|
|
// update signing timestamp on GPS lock
|
|
|
|
static void update_signing_timestamp(uint64_t timestamp_usec);
|
2016-04-05 01:09:47 -03:00
|
|
|
|
|
|
|
// return current packet overhead for a channel
|
|
|
|
static uint8_t packet_overhead_chan(mavlink_channel_t chan);
|
|
|
|
|
2018-03-25 07:45:48 -03:00
|
|
|
// alternative protocol function handler
|
|
|
|
FUNCTOR_TYPEDEF(protocol_handler_fn_t, bool, uint8_t, AP_HAL::UARTDriver *);
|
2017-08-21 00:04:47 -03:00
|
|
|
|
|
|
|
struct stream_entries {
|
2018-05-21 00:49:10 -03:00
|
|
|
const streams stream_id;
|
|
|
|
const ap_message *ap_message_ids;
|
2017-08-21 00:04:47 -03:00
|
|
|
const uint8_t num_ap_message_ids;
|
|
|
|
};
|
|
|
|
// vehicle subclass cpp files should define this:
|
|
|
|
static const struct stream_entries all_stream_entries[];
|
|
|
|
|
2018-03-28 21:49:34 -03:00
|
|
|
virtual uint64_t capabilities() const;
|
2020-03-23 22:36:25 -03:00
|
|
|
uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; }
|
2020-12-14 20:26:03 -04:00
|
|
|
uint8_t get_last_txbuf() const { return last_txbuf; }
|
2018-03-28 21:49:34 -03:00
|
|
|
|
2019-09-10 22:26:15 -03:00
|
|
|
MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us);
|
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
protected:
|
|
|
|
|
2019-07-31 22:02:31 -03:00
|
|
|
bool mavlink_coordinate_frame_to_location_alt_frame(MAV_FRAME coordinate_frame,
|
2019-03-14 22:46:05 -03:00
|
|
|
Location::AltFrame &frame);
|
2019-02-05 17:46:28 -04:00
|
|
|
|
2016-08-13 18:42:40 -03:00
|
|
|
// overridable method to check for packet acceptance. Allows for
|
|
|
|
// enforcement of GCS sysid
|
2021-02-01 12:16:38 -04:00
|
|
|
bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg) const;
|
2018-05-16 00:38:15 -03:00
|
|
|
void set_ekf_origin(const Location& loc);
|
2017-07-07 23:51:37 -03:00
|
|
|
|
2018-03-22 05:49:33 -03:00
|
|
|
virtual MAV_MODE base_mode() const = 0;
|
2019-11-24 17:24:44 -04:00
|
|
|
MAV_STATE system_status() const;
|
|
|
|
virtual MAV_STATE vehicle_system_status() const = 0;
|
2018-03-22 05:49:33 -03:00
|
|
|
|
2018-05-23 06:07:10 -03:00
|
|
|
virtual MAV_VTOL_STATE vtol_state() const { return MAV_VTOL_STATE_UNDEFINED; }
|
|
|
|
virtual MAV_LANDED_STATE landed_state() const { return MAV_LANDED_STATE_UNDEFINED; }
|
|
|
|
|
2019-07-17 01:50:12 -03:00
|
|
|
// return a MAVLink parameter type given a AP_Param type
|
|
|
|
static MAV_PARAM_TYPE mav_param_type(enum ap_var_type t);
|
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
AP_Param * _queued_parameter; ///< next parameter to
|
|
|
|
// be sent in queue
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
|
|
|
|
|
|
|
|
// saveable rate of each stream
|
2018-12-10 03:56:32 -04:00
|
|
|
AP_Int16 *streamRates;
|
2016-05-27 09:52:24 -03:00
|
|
|
|
2021-02-04 22:28:08 -04:00
|
|
|
void handle_heartbeat(const mavlink_message_t &msg) const;
|
|
|
|
|
2018-05-21 09:34:22 -03:00
|
|
|
virtual bool persist_streamrates() const { return false; }
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_request_data_stream(const mavlink_message_t &msg);
|
2016-05-27 09:52:24 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
virtual void handle_command_ack(const mavlink_message_t &msg);
|
|
|
|
void handle_set_mode(const mavlink_message_t &msg);
|
|
|
|
void handle_command_int(const mavlink_message_t &msg);
|
2018-07-05 21:56:06 -03:00
|
|
|
|
2023-07-15 03:17:32 -03:00
|
|
|
MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet);
|
2023-08-17 04:53:02 -03:00
|
|
|
virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
2023-05-27 06:46:06 -03:00
|
|
|
MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet);
|
2018-07-03 22:43:27 -03:00
|
|
|
|
2018-07-05 21:56:06 -03:00
|
|
|
virtual bool set_home_to_current_location(bool lock) = 0;
|
|
|
|
virtual bool set_home(const Location& loc, bool lock) = 0;
|
|
|
|
|
2023-05-02 04:10:07 -03:00
|
|
|
virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet);
|
2020-07-02 01:29:38 -03:00
|
|
|
MAV_RESULT handle_command_do_aux_function(const mavlink_command_long_t &packet);
|
2022-12-08 02:47:18 -04:00
|
|
|
MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_mission_request_list(const mavlink_message_t &msg);
|
2023-02-24 01:02:57 -04:00
|
|
|
void handle_mission_request(const mavlink_message_t &msg);
|
|
|
|
void handle_mission_request_int(const mavlink_message_t &msg);
|
|
|
|
void handle_mission_clear_all(const mavlink_message_t &msg);
|
2021-02-18 06:32:08 -04:00
|
|
|
|
2023-03-16 03:14:28 -03:00
|
|
|
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
|
2021-02-18 06:32:08 -04:00
|
|
|
// Note that there exists a relatively new mavlink DO command,
|
|
|
|
// MAV_CMD_DO_SET_MISSION_CURRENT which provides an acknowledgement
|
|
|
|
// that the command has been received, rather than the GCS having to
|
|
|
|
// rely on getting back an identical sequence number as some currently
|
|
|
|
// do.
|
2019-07-11 05:31:45 -03:00
|
|
|
virtual void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg);
|
2023-03-16 03:14:28 -03:00
|
|
|
#endif
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_mission_count(const mavlink_message_t &msg);
|
|
|
|
void handle_mission_write_partial_list(const mavlink_message_t &msg);
|
|
|
|
void handle_mission_item(const mavlink_message_t &msg);
|
|
|
|
|
2019-12-09 22:45:26 -04:00
|
|
|
void handle_distance_sensor(const mavlink_message_t &msg);
|
|
|
|
void handle_obstacle_distance(const mavlink_message_t &msg);
|
2020-12-06 08:17:48 -04:00
|
|
|
void handle_obstacle_distance_3d(const mavlink_message_t &msg);
|
2019-12-09 22:45:26 -04:00
|
|
|
|
2021-10-12 20:25:23 -03:00
|
|
|
void handle_adsb_message(const mavlink_message_t &msg);
|
|
|
|
|
2021-02-01 12:16:38 -04:00
|
|
|
void handle_osd_param_config(const mavlink_message_t &msg) const;
|
2020-08-09 13:31:59 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_common_param_message(const mavlink_message_t &msg);
|
|
|
|
void handle_param_set(const mavlink_message_t &msg);
|
|
|
|
void handle_param_request_list(const mavlink_message_t &msg);
|
|
|
|
void handle_param_request_read(const mavlink_message_t &msg);
|
2017-08-19 08:23:19 -03:00
|
|
|
virtual bool params_ready() const { return true; }
|
2021-02-04 22:28:08 -04:00
|
|
|
void handle_rc_channels_override(const mavlink_message_t &msg);
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_system_time_message(const mavlink_message_t &msg);
|
|
|
|
void handle_common_rally_message(const mavlink_message_t &msg);
|
|
|
|
void handle_rally_fetch_point(const mavlink_message_t &msg);
|
2021-02-01 12:16:38 -04:00
|
|
|
void handle_rally_point(const mavlink_message_t &msg) const;
|
2022-07-15 19:16:27 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2019-07-11 05:31:45 -03:00
|
|
|
virtual void handle_mount_message(const mavlink_message_t &msg);
|
2022-07-15 19:16:27 -03:00
|
|
|
#endif
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_fence_message(const mavlink_message_t &msg);
|
|
|
|
void handle_param_value(const mavlink_message_t &msg);
|
|
|
|
void handle_radio_status(const mavlink_message_t &msg, bool log_radio);
|
|
|
|
void handle_serial_control(const mavlink_message_t &msg);
|
|
|
|
void handle_vision_position_delta(const mavlink_message_t &msg);
|
|
|
|
|
|
|
|
void handle_common_message(const mavlink_message_t &msg);
|
|
|
|
void handle_set_gps_global_origin(const mavlink_message_t &msg);
|
2021-02-01 12:16:38 -04:00
|
|
|
void handle_setup_signing(const mavlink_message_t &msg) const;
|
2022-09-13 21:46:55 -03:00
|
|
|
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
2023-06-15 20:54:41 -03:00
|
|
|
struct {
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
bool taken;
|
|
|
|
} _deadlock_sem;
|
|
|
|
void deadlock_sem(void);
|
2018-05-20 23:18:57 -03:00
|
|
|
|
|
|
|
// reset a message interval via mavlink:
|
|
|
|
MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);
|
2018-12-24 01:22:00 -04:00
|
|
|
MAV_RESULT handle_command_get_message_interval(const mavlink_command_long_t &packet);
|
|
|
|
bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const;
|
2019-02-07 22:05:54 -04:00
|
|
|
MAV_RESULT handle_command_request_message(const mavlink_command_long_t &packet);
|
2018-05-20 23:18:57 -03:00
|
|
|
|
2017-07-16 20:49:21 -03:00
|
|
|
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
2023-02-06 06:26:40 -04:00
|
|
|
|
2017-07-25 03:36:53 -03:00
|
|
|
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
|
2016-11-06 21:42:47 -04:00
|
|
|
|
2022-10-26 23:46:13 -03:00
|
|
|
#if AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_send_autopilot_version(const mavlink_message_t &msg);
|
2022-10-26 23:46:13 -03:00
|
|
|
#endif
|
2022-10-26 23:52:41 -03:00
|
|
|
#if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED
|
2017-08-18 20:07:42 -03:00
|
|
|
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
|
2022-10-26 23:52:41 -03:00
|
|
|
#endif
|
2017-08-18 20:07:42 -03:00
|
|
|
|
2017-08-19 08:23:19 -03:00
|
|
|
virtual void send_banner();
|
|
|
|
|
2022-02-07 22:57:18 -04:00
|
|
|
// send a (textual) message to the GCS that a received message has
|
|
|
|
// been deprecated
|
|
|
|
void send_received_message_deprecation_warning(const char *message);
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_device_op_read(const mavlink_message_t &msg);
|
|
|
|
void handle_device_op_write(const mavlink_message_t &msg);
|
2017-03-29 03:47:32 -03:00
|
|
|
|
2018-05-16 04:17:25 -03:00
|
|
|
void send_timesync();
|
|
|
|
// returns the time a timesync message was most likely received:
|
|
|
|
uint64_t timesync_receive_timestamp_ns() const;
|
|
|
|
// returns a timestamp suitable for packing into the ts1 field of TIMESYNC:
|
|
|
|
uint64_t timesync_timestamp_ns() const;
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_timesync(const mavlink_message_t &msg);
|
2018-05-16 04:17:25 -03:00
|
|
|
struct {
|
|
|
|
int64_t sent_ts1;
|
|
|
|
uint32_t last_sent_ms;
|
|
|
|
const uint16_t interval_ms = 10000;
|
|
|
|
} _timesync_request;
|
|
|
|
|
2021-02-01 12:16:38 -04:00
|
|
|
void handle_statustext(const mavlink_message_t &msg) const;
|
2021-08-29 21:18:26 -03:00
|
|
|
void handle_named_value(const mavlink_message_t &msg) const;
|
2017-07-12 04:21:15 -03:00
|
|
|
|
2017-07-12 05:11:41 -03:00
|
|
|
bool telemetry_delayed() const;
|
|
|
|
virtual uint32_t telem_delay() const = 0;
|
|
|
|
|
2021-06-01 05:48:15 -03:00
|
|
|
MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_long_t &packet);
|
2017-07-16 22:04:32 -03:00
|
|
|
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
|
2018-06-27 03:00:43 -03:00
|
|
|
MAV_RESULT handle_command_flash_bootloader(const mavlink_command_long_t &packet);
|
2018-03-17 06:25:52 -03:00
|
|
|
|
|
|
|
// generally this should not be overridden; Plane overrides it to ensure
|
2019-03-27 04:19:38 -03:00
|
|
|
// failsafe isn't triggered during calibration
|
2022-12-08 02:47:13 -04:00
|
|
|
virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
2018-03-17 06:25:52 -03:00
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
|
|
|
virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg);
|
2018-03-17 05:19:14 -03:00
|
|
|
|
2021-02-18 06:32:08 -04:00
|
|
|
virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet);
|
|
|
|
|
2019-06-18 06:30:35 -03:00
|
|
|
MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet);
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_command_long(const mavlink_message_t &msg);
|
2018-07-04 00:43:07 -03:00
|
|
|
MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet);
|
2019-03-16 04:07:36 -03:00
|
|
|
MAV_RESULT handle_command_do_set_roi_sysid(const uint8_t sysid);
|
|
|
|
MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet);
|
|
|
|
MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_long_t &packet);
|
2023-03-02 17:41:51 -04:00
|
|
|
MAV_RESULT handle_command_do_set_roi_none();
|
|
|
|
|
2023-08-17 04:53:02 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2023-05-09 09:25:33 -03:00
|
|
|
virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
2023-08-17 04:53:02 -03:00
|
|
|
#endif
|
2023-08-01 23:38:10 -03:00
|
|
|
|
|
|
|
MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet);
|
|
|
|
MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet);
|
|
|
|
|
2023-08-17 04:53:02 -03:00
|
|
|
MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
|
|
|
virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
2017-07-26 02:48:01 -03:00
|
|
|
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
2017-08-19 11:29:01 -03:00
|
|
|
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
|
2018-10-13 19:24:24 -03:00
|
|
|
MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
|
|
|
|
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
|
2018-07-03 23:16:16 -03:00
|
|
|
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
2020-07-03 19:46:43 -03:00
|
|
|
MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet);
|
2017-09-16 08:50:59 -03:00
|
|
|
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
2018-03-16 00:57:18 -03:00
|
|
|
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
2019-02-03 20:07:23 -04:00
|
|
|
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
2019-02-08 04:41:28 -04:00
|
|
|
MAV_RESULT handle_command_debug_trap(const mavlink_command_long_t &packet);
|
2021-08-14 03:43:44 -03:00
|
|
|
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_long_t &packet);
|
2023-06-18 18:00:03 -03:00
|
|
|
MAV_RESULT handle_command_airframe_configuration(const mavlink_command_long_t &packet);
|
2017-07-13 22:43:30 -03:00
|
|
|
|
2022-02-06 17:22:26 -04:00
|
|
|
/*
|
|
|
|
handle MAV_CMD_CAN_FORWARD and CAN_FRAME messages for CAN over MAVLink
|
|
|
|
*/
|
|
|
|
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &);
|
|
|
|
MAV_RESULT handle_can_forward(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
|
|
|
void handle_can_frame(const mavlink_message_t &msg) const;
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_optical_flow(const mavlink_message_t &msg);
|
2019-03-27 04:19:13 -03:00
|
|
|
|
2022-11-21 23:33:22 -04:00
|
|
|
void handle_manual_control(const mavlink_message_t &msg);
|
|
|
|
|
2019-05-31 07:58:27 -03:00
|
|
|
// default empty handling of LANDING_TARGET
|
|
|
|
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }
|
2017-07-17 20:53:41 -03:00
|
|
|
// vehicle-overridable message send function
|
|
|
|
virtual bool try_send_message(enum ap_message id);
|
2019-02-28 17:38:55 -04:00
|
|
|
virtual void send_global_position_int();
|
2017-07-17 20:53:41 -03:00
|
|
|
|
|
|
|
// message sending functions:
|
2017-07-18 05:55:06 -03:00
|
|
|
bool try_send_mission_message(enum ap_message id);
|
2017-07-18 08:50:23 -03:00
|
|
|
void send_hwstatus();
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_data_packet(const mavlink_message_t &msg);
|
2018-03-25 07:45:48 -03:00
|
|
|
|
2018-05-01 09:04:00 -03:00
|
|
|
// these two methods are called after current_loc is updated:
|
|
|
|
virtual int32_t global_position_int_alt() const;
|
|
|
|
virtual int32_t global_position_int_relative_alt() const;
|
|
|
|
|
2018-05-09 07:55:37 -03:00
|
|
|
virtual float vfr_hud_climbrate() const;
|
|
|
|
virtual float vfr_hud_airspeed() const;
|
|
|
|
virtual int16_t vfr_hud_throttle() const { return 0; }
|
2018-11-05 21:03:34 -04:00
|
|
|
virtual float vfr_hud_alt() const;
|
2018-05-09 07:55:37 -03:00
|
|
|
|
2021-06-10 07:56:46 -03:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
virtual int16_t high_latency_target_altitude() const { return 0; }
|
|
|
|
virtual uint8_t high_latency_tgt_heading() const { return 0; }
|
|
|
|
virtual uint16_t high_latency_tgt_dist() const { return 0; }
|
|
|
|
virtual uint8_t high_latency_tgt_airspeed() const { return 0; }
|
|
|
|
virtual uint8_t high_latency_wind_speed() const { return 0; }
|
|
|
|
virtual uint8_t high_latency_wind_direction() const { return 0; }
|
2021-09-30 04:23:31 -03:00
|
|
|
int8_t high_latency_air_temperature() const;
|
2021-06-10 07:56:46 -03:00
|
|
|
|
2022-01-25 22:51:54 -04:00
|
|
|
MAV_RESULT handle_control_high_latency(const mavlink_command_long_t &packet);
|
|
|
|
|
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
|
2017-06-06 22:38:05 -03:00
|
|
|
static constexpr const float magic_force_arm_value = 2989.0f;
|
|
|
|
static constexpr const float magic_force_disarm_value = 21196.0f;
|
|
|
|
|
2022-02-25 01:06:31 -04:00
|
|
|
void manual_override(class RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
2018-05-06 02:24:30 -03:00
|
|
|
|
2021-08-24 11:17:24 -03:00
|
|
|
uint8_t receiver_rssi() const;
|
|
|
|
|
2020-07-02 08:02:34 -03:00
|
|
|
/*
|
|
|
|
correct an offboard timestamp in microseconds to a local time
|
|
|
|
since boot in milliseconds
|
|
|
|
*/
|
|
|
|
uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size);
|
|
|
|
|
2022-02-02 22:52:28 -04:00
|
|
|
// converts a COMMAND_LONG packet to a COMMAND_INT packet, where
|
|
|
|
// the command-long packet is assumed to be in the supplied frame.
|
|
|
|
// If location is not present in the command then just omit frame.
|
2023-07-10 23:57:14 -03:00
|
|
|
// this method ensures the passed-in structure is entirely
|
|
|
|
// initialised.
|
2022-02-02 22:52:28 -04:00
|
|
|
static void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT);
|
|
|
|
|
|
|
|
// methods to extract a Location object from a command_long or command_int
|
|
|
|
bool location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out);
|
|
|
|
bool location_from_command_t(const mavlink_command_int_t &in, Location &out);
|
2021-11-24 06:46:40 -04:00
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
private:
|
2016-05-29 07:47:57 -03:00
|
|
|
|
2023-02-24 00:01:58 -04:00
|
|
|
// define the two objects used for parsing incoming messages:
|
|
|
|
mavlink_message_t _channel_buffer;
|
|
|
|
mavlink_status_t _channel_status;
|
|
|
|
|
2022-07-11 04:57:40 -03:00
|
|
|
const AP_SerialManager::UARTState *uartstate;
|
|
|
|
|
2020-06-03 23:02:56 -03:00
|
|
|
// last time we got a non-zero RSSI from RADIO_STATUS
|
|
|
|
static struct LastRadioStatus {
|
|
|
|
uint32_t remrssi_ms;
|
|
|
|
uint8_t rssi;
|
|
|
|
uint32_t received_ms; // time RADIO_STATUS received
|
|
|
|
} last_radio_status;
|
|
|
|
|
2020-04-05 22:09:24 -03:00
|
|
|
enum class Flags {
|
|
|
|
USING_SIGNING = (1<<0),
|
|
|
|
ACTIVE = (1<<1),
|
|
|
|
STREAMING = (1<<2),
|
|
|
|
PRIVATE = (1<<3),
|
|
|
|
LOCKED = (1<<4),
|
|
|
|
};
|
2019-02-06 22:29:55 -04:00
|
|
|
void log_mavlink_stats();
|
|
|
|
|
2017-09-15 23:29:54 -03:00
|
|
|
MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode);
|
|
|
|
|
2022-02-07 22:57:18 -04:00
|
|
|
// send a (textual) message to the GCS that a received message has
|
|
|
|
// been deprecated
|
|
|
|
uint32_t last_deprecation_warning_send_time_ms;
|
|
|
|
const char *last_deprecation_message;
|
|
|
|
|
2020-05-03 01:06:23 -03:00
|
|
|
void service_statustext(void);
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
virtual void handleMessage(const mavlink_message_t &msg) = 0;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2018-07-03 23:16:16 -03:00
|
|
|
MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
|
2023-08-03 00:31:40 -03:00
|
|
|
bool send_relay_status() const;
|
2017-07-13 23:44:21 -03:00
|
|
|
|
2019-08-22 22:23:57 -03:00
|
|
|
static bool command_long_stores_location(const MAV_CMD command);
|
|
|
|
|
2018-03-17 08:55:57 -03:00
|
|
|
bool calibrate_gyros();
|
|
|
|
|
2014-12-09 23:39:32 -04:00
|
|
|
/// The stream we are communicating over
|
|
|
|
AP_HAL::UARTDriver *_port;
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
/// Perform queued sending operations
|
|
|
|
///
|
|
|
|
enum ap_var_type _queued_parameter_type; ///< type of the next
|
|
|
|
// parameter
|
|
|
|
AP_Param::ParamToken _queued_parameter_token; ///AP_Param token for
|
|
|
|
// next() call
|
|
|
|
uint16_t _queued_parameter_index; ///< next queued
|
|
|
|
// parameter's index
|
|
|
|
uint16_t _queued_parameter_count; ///< saved count of
|
|
|
|
// parameters for
|
|
|
|
// queued send
|
2013-11-23 06:45:42 -04:00
|
|
|
uint32_t _queued_parameter_send_time_ms;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2019-02-15 20:56:22 -04:00
|
|
|
// number of extra ms to add to slow things down for the radio
|
|
|
|
uint16_t stream_slowdown_ms;
|
2020-12-14 20:26:03 -04:00
|
|
|
// last reported radio buffer percent available
|
|
|
|
uint8_t last_txbuf = 100;
|
2013-03-20 23:54:04 -03:00
|
|
|
|
2018-05-20 23:18:57 -03:00
|
|
|
// outbound ("deferred message") queue.
|
|
|
|
|
2018-12-06 19:14:38 -04:00
|
|
|
// "special" messages such as heartbeat, next_param etc are stored
|
|
|
|
// separately to stream-rated messages like AHRS2 etc. If these
|
|
|
|
// were to be stored in buckets then they would be slowed down
|
|
|
|
// based on stream_slowdown, which we have not traditionally done.
|
2018-05-20 23:18:57 -03:00
|
|
|
struct deferred_message_t {
|
|
|
|
const ap_message id;
|
|
|
|
uint16_t interval_ms;
|
|
|
|
uint16_t last_sent_ms; // from AP_HAL::millis16()
|
2022-01-25 22:51:54 -04:00
|
|
|
} deferred_message[3] = {
|
2018-05-20 23:18:57 -03:00
|
|
|
{ MSG_HEARTBEAT, },
|
|
|
|
{ MSG_NEXT_PARAM, },
|
2022-01-25 22:51:54 -04:00
|
|
|
{ MSG_HIGH_LATENCY2, },
|
2018-05-20 23:18:57 -03:00
|
|
|
};
|
|
|
|
// returns index of id in deferred_message[] or -1 if not present
|
|
|
|
int8_t get_deferred_message_index(const ap_message id) const;
|
|
|
|
// returns index of a message in deferred_message[] which should
|
|
|
|
// be sent (or -1 if none to send at the moment)
|
2020-09-15 08:18:08 -03:00
|
|
|
int8_t deferred_message_to_send_index(uint16_t now16_ms);
|
2018-05-20 23:18:57 -03:00
|
|
|
// cache of which deferred message should be sent next:
|
|
|
|
int8_t next_deferred_message_to_send_cache = -1;
|
|
|
|
|
|
|
|
struct deferred_message_bucket_t {
|
2019-04-11 09:13:14 -03:00
|
|
|
Bitmask<MSG_LAST> ap_message_ids;
|
2018-05-20 23:18:57 -03:00
|
|
|
uint16_t interval_ms;
|
|
|
|
uint16_t last_sent_ms; // from AP_HAL::millis16()
|
|
|
|
};
|
2018-12-06 20:11:02 -04:00
|
|
|
deferred_message_bucket_t deferred_message_bucket[10];
|
2018-05-20 23:18:57 -03:00
|
|
|
static const uint8_t no_bucket_to_send = -1;
|
|
|
|
static const ap_message no_message_to_send = (ap_message)-1;
|
|
|
|
uint8_t sending_bucket_id = no_bucket_to_send;
|
2019-04-11 09:13:14 -03:00
|
|
|
Bitmask<MSG_LAST> bucket_message_ids_to_send;
|
2018-05-20 23:18:57 -03:00
|
|
|
|
2020-09-15 08:18:08 -03:00
|
|
|
ap_message next_deferred_bucket_message_to_send(uint16_t now16_ms);
|
|
|
|
void find_next_bucket_to_send(uint16_t now16_ms);
|
2018-05-20 23:18:57 -03:00
|
|
|
void remove_message_from_bucket(int8_t bucket, ap_message id);
|
|
|
|
|
|
|
|
// bitmask of IDs the code has spontaneously decided it wants to
|
|
|
|
// send out. Examples include HEARTBEAT (gcs_send_heartbeat)
|
2019-04-11 09:13:14 -03:00
|
|
|
Bitmask<MSG_LAST> pushed_ap_message_ids;
|
2018-05-20 23:18:57 -03:00
|
|
|
|
|
|
|
// returns true if it is OK to send a message while we are in
|
|
|
|
// delay callback. In particular, when we are doing sensor init
|
|
|
|
// we still send heartbeats.
|
|
|
|
bool should_send_message_in_delay_callback(const ap_message id) const;
|
|
|
|
|
|
|
|
// if true is returned, interval will contain the default interval for id
|
|
|
|
bool get_default_interval_for_ap_message(const ap_message id, uint16_t &interval) const;
|
|
|
|
// if true is returned, interval will contain the default interval for id
|
|
|
|
// returns an interval in milliseconds for any ap_message in stream id
|
|
|
|
uint16_t get_interval_for_stream(GCS_MAVLINK::streams id) const;
|
|
|
|
// set an inverval for a specific mavlink message. Returns false
|
|
|
|
// on failure (typically because there is no mapping from that
|
|
|
|
// mavlink ID to an ap_message)
|
|
|
|
bool set_mavlink_message_id_interval(const uint32_t mavlink_id,
|
|
|
|
const uint16_t interval_ms);
|
|
|
|
// map a mavlink ID to an ap_message which, if passed to
|
|
|
|
// try_send_message, will cause a mavlink message with that id to
|
|
|
|
// be emitted. Returns MSG_LAST if no such mapping exists.
|
|
|
|
ap_message mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const;
|
|
|
|
// set the interval at which an ap_message should be emitted (in ms)
|
|
|
|
bool set_ap_message_interval(enum ap_message id, uint16_t interval_ms);
|
|
|
|
// call set_ap_message_interval for each entry in a stream,
|
|
|
|
// the interval being based on the stream's rate
|
|
|
|
void initialise_message_intervals_for_stream(GCS_MAVLINK::streams id);
|
|
|
|
// call initialise_message_intervals_for_stream on every stream:
|
|
|
|
void initialise_message_intervals_from_streamrates();
|
|
|
|
// boolean that indicated that message intervals have been set
|
|
|
|
// from streamrates:
|
|
|
|
bool deferred_messages_initialised;
|
2021-06-02 00:06:13 -03:00
|
|
|
#if HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED
|
|
|
|
// read configuration files from (e.g.) SD and ROMFS, set
|
|
|
|
// intervals from same
|
|
|
|
void initialise_message_intervals_from_config_files();
|
|
|
|
// read file, set message intervals from it:
|
|
|
|
void get_intervals_from_filepath(const char *path, DefaultIntervalsFromFiles &);
|
|
|
|
#endif
|
2018-05-20 23:18:57 -03:00
|
|
|
// return interval deferred message bucket should be sent after.
|
|
|
|
// When sending parameters and waypoints this may be longer than
|
|
|
|
// the interval specified in "deferred"
|
|
|
|
uint16_t get_reschedule_interval_ms(const deferred_message_bucket_t &deferred) const;
|
|
|
|
|
|
|
|
bool do_try_send_message(const ap_message id);
|
2014-03-18 20:56:09 -03:00
|
|
|
|
2016-05-27 21:41:52 -03:00
|
|
|
// time when we missed sending a parameter for GCS
|
|
|
|
static uint32_t reserve_param_space_start_ms;
|
|
|
|
|
2014-07-17 08:03:12 -03:00
|
|
|
// bitmask of what mavlink channels are active
|
|
|
|
static uint8_t mavlink_active;
|
2014-05-20 23:38:07 -03:00
|
|
|
|
2018-11-21 19:17:59 -04:00
|
|
|
// bitmask of what mavlink channels are private
|
|
|
|
static uint8_t mavlink_private;
|
|
|
|
|
2016-06-13 17:36:34 -03:00
|
|
|
// bitmask of what mavlink channels are streaming
|
|
|
|
static uint8_t chan_is_streaming;
|
|
|
|
|
2014-12-09 23:31:31 -04:00
|
|
|
// mavlink routing object
|
|
|
|
static MAVLink_routing routing;
|
|
|
|
|
2017-04-29 02:30:57 -03:00
|
|
|
struct pending_param_request {
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
int16_t param_index;
|
|
|
|
char param_name[AP_MAX_NAME_SIZE+1];
|
|
|
|
};
|
|
|
|
|
|
|
|
struct pending_param_reply {
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
float value;
|
|
|
|
enum ap_var_type p_type;
|
|
|
|
int16_t param_index;
|
|
|
|
uint16_t count;
|
|
|
|
char param_name[AP_MAX_NAME_SIZE+1];
|
|
|
|
};
|
|
|
|
|
|
|
|
// queue of pending parameter requests and replies
|
|
|
|
static ObjectBuffer<pending_param_request> param_requests;
|
|
|
|
static ObjectBuffer<pending_param_reply> param_replies;
|
|
|
|
|
|
|
|
// have we registered the IO timer callback?
|
|
|
|
static bool param_timer_registered;
|
|
|
|
|
|
|
|
// IO timer callback for parameters
|
|
|
|
void param_io_timer(void);
|
2019-03-13 22:22:04 -03:00
|
|
|
|
|
|
|
uint8_t send_parameter_async_replies();
|
2014-12-09 23:31:31 -04:00
|
|
|
|
2019-09-26 00:42:14 -03:00
|
|
|
enum class FTP_OP : uint8_t {
|
|
|
|
None = 0,
|
|
|
|
TerminateSession = 1,
|
|
|
|
ResetSessions = 2,
|
|
|
|
ListDirectory = 3,
|
|
|
|
OpenFileRO = 4,
|
|
|
|
ReadFile = 5,
|
|
|
|
CreateFile = 6,
|
|
|
|
WriteFile = 7,
|
|
|
|
RemoveFile = 8,
|
|
|
|
CreateDirectory = 9,
|
|
|
|
RemoveDirectory = 10,
|
|
|
|
OpenFileWO = 11,
|
|
|
|
TruncateFile = 12,
|
|
|
|
Rename = 13,
|
|
|
|
CalcFileCRC32 = 14,
|
|
|
|
BurstReadFile = 15,
|
|
|
|
Ack = 128,
|
|
|
|
Nack = 129,
|
|
|
|
};
|
|
|
|
|
|
|
|
enum class FTP_ERROR : uint8_t {
|
|
|
|
None = 0,
|
|
|
|
Fail = 1,
|
|
|
|
FailErrno = 2,
|
|
|
|
InvalidDataSize = 3,
|
|
|
|
InvalidSession = 4,
|
|
|
|
NoSessionsAvailable = 5,
|
|
|
|
EndOfFile = 6,
|
|
|
|
UnknownCommand = 7,
|
|
|
|
FileExists = 8,
|
|
|
|
FileProtected = 9,
|
|
|
|
FileNotFound = 10,
|
|
|
|
};
|
|
|
|
|
|
|
|
struct pending_ftp {
|
|
|
|
uint32_t offset;
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
uint16_t seq_number;
|
|
|
|
FTP_OP opcode;
|
|
|
|
FTP_OP req_opcode;
|
|
|
|
bool burst_complete;
|
|
|
|
uint8_t size;
|
|
|
|
uint8_t session;
|
|
|
|
uint8_t sysid;
|
|
|
|
uint8_t compid;
|
|
|
|
uint8_t data[239];
|
|
|
|
};
|
|
|
|
|
|
|
|
enum class FTP_FILE_MODE {
|
|
|
|
Read,
|
|
|
|
Write,
|
|
|
|
};
|
|
|
|
|
|
|
|
struct ftp_state {
|
|
|
|
ObjectBuffer<pending_ftp> *requests;
|
|
|
|
|
|
|
|
// session specific info, currently only support a single session over all links
|
|
|
|
int fd = -1;
|
|
|
|
FTP_FILE_MODE mode; // work around AP_Filesystem not supporting file modes
|
|
|
|
int16_t current_session;
|
2020-03-25 01:09:57 -03:00
|
|
|
uint32_t last_send_ms;
|
2020-05-02 21:55:56 -03:00
|
|
|
uint8_t need_banner_send_mask;
|
2019-09-26 00:42:14 -03:00
|
|
|
};
|
|
|
|
static struct ftp_state ftp;
|
|
|
|
|
|
|
|
static void ftp_error(struct pending_ftp &response, FTP_ERROR error); // FTP helper method for packing a NAK
|
2019-11-02 06:49:52 -03:00
|
|
|
static int gen_dir_entry(char *dest, size_t space, const char * path, const struct dirent * entry); // FTP helper for emitting a dir response
|
2019-09-26 00:42:14 -03:00
|
|
|
static void ftp_list_dir(struct pending_ftp &request, struct pending_ftp &response);
|
|
|
|
|
|
|
|
bool ftp_init(void);
|
|
|
|
void handle_file_transfer_protocol(const mavlink_message_t &msg);
|
2023-01-01 16:49:26 -04:00
|
|
|
bool send_ftp_reply(const pending_ftp &reply);
|
2019-09-26 00:42:14 -03:00
|
|
|
void ftp_worker(void);
|
2019-11-02 07:15:51 -03:00
|
|
|
void ftp_push_replies(pending_ftp &reply);
|
2019-09-26 00:42:14 -03:00
|
|
|
|
2019-07-11 03:03:14 -03:00
|
|
|
void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;
|
2018-05-09 04:46:20 -03:00
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
2022-01-29 07:19:13 -04:00
|
|
|
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_common_mission_message(const mavlink_message_t &msg);
|
2014-03-18 19:59:40 -03:00
|
|
|
|
2022-11-21 23:33:22 -04:00
|
|
|
virtual void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) {};
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void handle_vicon_position_estimate(const mavlink_message_t &msg);
|
|
|
|
void handle_vision_position_estimate(const mavlink_message_t &msg);
|
|
|
|
void handle_global_vision_position_estimate(const mavlink_message_t &msg);
|
|
|
|
void handle_att_pos_mocap(const mavlink_message_t &msg);
|
2021-12-17 21:36:12 -04:00
|
|
|
void handle_odometry(const mavlink_message_t &msg);
|
2018-04-19 01:22:21 -03:00
|
|
|
void handle_common_vision_position_estimate_data(const uint64_t usec,
|
|
|
|
const float x,
|
|
|
|
const float y,
|
|
|
|
const float z,
|
|
|
|
const float roll,
|
|
|
|
const float pitch,
|
2018-05-15 21:43:09 -03:00
|
|
|
const float yaw,
|
2020-06-03 23:55:08 -03:00
|
|
|
const float covariance[21],
|
2020-04-10 01:38:59 -03:00
|
|
|
const uint8_t reset_counter,
|
2018-05-15 21:43:09 -03:00
|
|
|
const uint16_t payload_size);
|
2020-05-13 05:29:55 -03:00
|
|
|
void handle_vision_speed_estimate(const mavlink_message_t &msg);
|
2019-05-31 07:58:27 -03:00
|
|
|
void handle_landing_target(const mavlink_message_t &msg);
|
2017-07-18 22:36:49 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void lock_channel(const mavlink_channel_t chan, bool lock);
|
2015-04-22 20:11:43 -03:00
|
|
|
|
2016-01-21 02:55:50 -04:00
|
|
|
mavlink_signing_t signing;
|
|
|
|
static mavlink_signing_streams_t signing_streams;
|
2016-04-05 20:38:21 -03:00
|
|
|
static uint32_t last_signing_save_ms;
|
2020-03-26 01:32:27 -03:00
|
|
|
|
2016-01-21 02:55:50 -04:00
|
|
|
static StorageAccess _signing_storage;
|
2016-04-05 20:38:21 -03:00
|
|
|
static bool signing_key_save(const struct SigningKey &key);
|
|
|
|
static bool signing_key_load(struct SigningKey &key);
|
2016-01-20 22:49:06 -04:00
|
|
|
void load_signing_key(void);
|
2016-04-05 01:09:47 -03:00
|
|
|
bool signing_enabled(void) const;
|
2016-04-05 20:38:21 -03:00
|
|
|
static void save_signing_timestamp(bool force_save_now);
|
2018-03-25 07:45:48 -03:00
|
|
|
|
2021-06-02 00:06:13 -03:00
|
|
|
#if HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED
|
|
|
|
// structure containing default intervals read from files for this
|
|
|
|
// link:
|
|
|
|
DefaultIntervalsFromFiles *default_intervals_from_files;
|
|
|
|
#endif
|
|
|
|
|
2018-03-25 07:45:48 -03:00
|
|
|
// alternative protocol handler support
|
|
|
|
struct {
|
|
|
|
GCS_MAVLINK::protocol_handler_fn_t handler;
|
|
|
|
uint32_t last_mavlink_ms;
|
|
|
|
uint32_t last_alternate_ms;
|
|
|
|
bool active;
|
|
|
|
} alternative;
|
2018-05-14 00:09:12 -03:00
|
|
|
|
2018-06-21 23:46:56 -03:00
|
|
|
JitterCorrection lag_correction;
|
|
|
|
|
2018-05-01 09:04:00 -03:00
|
|
|
// we cache the current location and send it even if the AHRS has
|
|
|
|
// no idea where we are:
|
2023-02-02 18:58:39 -04:00
|
|
|
Location global_position_current_loc;
|
2018-05-01 09:04:00 -03:00
|
|
|
|
2019-02-06 22:29:55 -04:00
|
|
|
uint8_t last_tx_seq;
|
|
|
|
uint16_t send_packet_count;
|
2020-04-14 08:08:54 -03:00
|
|
|
uint16_t out_of_space_to_send_count; // number of times HAVE_PAYLOAD_SPACE and friends have returned false
|
2019-02-06 22:29:55 -04:00
|
|
|
|
2018-12-06 19:14:23 -04:00
|
|
|
#if GCS_DEBUG_SEND_MESSAGE_TIMINGS
|
2018-05-20 23:18:57 -03:00
|
|
|
struct {
|
|
|
|
uint32_t longest_time_us;
|
|
|
|
ap_message longest_id;
|
|
|
|
uint32_t no_space_for_message;
|
|
|
|
uint16_t statustext_last_sent_ms;
|
|
|
|
uint32_t behind;
|
2019-08-20 19:19:23 -03:00
|
|
|
uint32_t out_of_time;
|
2018-05-20 23:18:57 -03:00
|
|
|
uint16_t fnbts_maxtime;
|
|
|
|
uint32_t max_retry_deferred_body_us;
|
|
|
|
uint8_t max_retry_deferred_body_type;
|
|
|
|
} try_send_message_stats;
|
2019-02-15 20:56:22 -04:00
|
|
|
uint16_t max_slowdown_ms;
|
2018-05-20 23:18:57 -03:00
|
|
|
#endif
|
|
|
|
|
2019-02-06 22:29:55 -04:00
|
|
|
uint32_t last_mavlink_stats_logged;
|
2019-09-12 03:14:55 -03:00
|
|
|
|
2020-06-12 20:29:00 -03:00
|
|
|
uint8_t last_battery_status_idx;
|
|
|
|
|
2021-02-17 04:13:04 -04:00
|
|
|
// if we've ever sent a DISTANCE_SENSOR message out of an
|
|
|
|
// orientation we continue to send it out, even if it is not
|
|
|
|
// longer valid.
|
|
|
|
uint8_t proximity_ever_valid_bitmask;
|
|
|
|
|
2019-09-12 03:14:55 -03:00
|
|
|
// true if we should NOT do MAVLink on this port (usually because
|
|
|
|
// someone's doing SERIAL_CONTROL over mavlink)
|
|
|
|
bool _locked;
|
2011-02-17 05:36:33 -04:00
|
|
|
};
|
2016-05-30 07:05:00 -03:00
|
|
|
|
|
|
|
/// @class GCS
|
|
|
|
/// @brief global GCS object
|
|
|
|
class GCS
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
GCS() {
|
|
|
|
if (_singleton == nullptr) {
|
|
|
|
_singleton = this;
|
|
|
|
} else {
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
// this is a serious problem, but we don't need to kill a
|
|
|
|
// real vehicle
|
|
|
|
AP_HAL::panic("GCS must be singleton");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
2019-02-10 01:02:09 -04:00
|
|
|
static class GCS *get_singleton() {
|
2016-05-30 07:05:00 -03:00
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
2019-02-12 07:54:24 -04:00
|
|
|
virtual uint32_t custom_mode() const = 0;
|
|
|
|
virtual MAV_TYPE frame_type() const = 0;
|
2019-03-01 02:07:45 -04:00
|
|
|
virtual const char* frame_string() const { return nullptr; }
|
2019-02-12 07:54:24 -04:00
|
|
|
|
2020-05-03 01:06:23 -03:00
|
|
|
struct statustext_t {
|
|
|
|
mavlink_statustext_t msg;
|
2020-05-12 01:08:10 -03:00
|
|
|
uint16_t entry_created_ms;
|
2020-05-03 01:06:23 -03:00
|
|
|
uint8_t bitmask;
|
|
|
|
};
|
|
|
|
class StatusTextQueue : public ObjectArray<statustext_t> {
|
|
|
|
public:
|
|
|
|
using ObjectArray::ObjectArray;
|
|
|
|
HAL_Semaphore &semaphore() { return _sem; }
|
2020-05-12 01:08:10 -03:00
|
|
|
void prune();
|
2020-05-03 01:06:23 -03:00
|
|
|
private:
|
|
|
|
// a lock for the statustext queue, to make it safe to use send_text()
|
|
|
|
// from multiple threads
|
|
|
|
HAL_Semaphore _sem;
|
2020-05-12 01:08:10 -03:00
|
|
|
|
|
|
|
uint32_t last_prune_ms;
|
2020-05-03 01:06:23 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
StatusTextQueue &statustext_queue() {
|
|
|
|
return _statustext_queue;
|
|
|
|
}
|
|
|
|
|
2021-02-04 22:28:08 -04:00
|
|
|
// last time traffic was seen from my designated GCS. traffic
|
|
|
|
// includes heartbeats and some manual control messages.
|
|
|
|
uint32_t sysid_myggcs_last_seen_time_ms() const {
|
|
|
|
return _sysid_mygcs_last_seen_time_ms;
|
|
|
|
}
|
|
|
|
// called when valid traffic has been seen from our GCS
|
|
|
|
void sysid_myggcs_seen(uint32_t seen_time_ms) {
|
|
|
|
_sysid_mygcs_last_seen_time_ms = seen_time_ms;
|
|
|
|
}
|
|
|
|
|
2018-11-06 22:11:08 -04:00
|
|
|
void send_to_active_channels(uint32_t msgid, const char *pkt);
|
|
|
|
|
2019-07-23 05:33:56 -03:00
|
|
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(3, 4);
|
2017-08-01 02:13:34 -03:00
|
|
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
2020-01-12 22:08:14 -04:00
|
|
|
virtual void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t mask);
|
2019-08-27 02:15:46 -03:00
|
|
|
uint8_t statustext_send_channel_mask() const;
|
2020-01-12 22:08:14 -04:00
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
|
|
|
|
virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;
|
|
|
|
// return the number of valid GCS objects
|
|
|
|
uint8_t num_gcs() const { return _num_gcs; };
|
2017-02-13 06:57:50 -04:00
|
|
|
void send_message(enum ap_message id);
|
|
|
|
void send_mission_item_reached_message(uint16_t mission_index);
|
2018-05-15 02:20:30 -03:00
|
|
|
void send_named_float(const char *name, float value) const;
|
2018-03-11 19:50:51 -03:00
|
|
|
|
|
|
|
void send_parameter_value(const char *param_name,
|
|
|
|
ap_var_type param_type,
|
|
|
|
float param_value);
|
|
|
|
|
2022-09-27 20:46:38 -03:00
|
|
|
// an array of objects used to handle each of the different
|
|
|
|
// protocol types we support. This is indexed by the enumeration
|
|
|
|
// MAV_MISSION_TYPE, taking advantage of the fact that fence,
|
|
|
|
// mission and rally have values 0, 1 and 2. Indexing should be via
|
|
|
|
// get_prot_for_mission_type to do bounds checking.
|
|
|
|
static class MissionItemProtocol *missionitemprotocols[3];
|
2022-02-25 01:06:31 -04:00
|
|
|
class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
|
2021-02-01 12:16:38 -04:00
|
|
|
void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const;
|
2019-04-28 23:52:02 -03:00
|
|
|
|
2018-05-20 23:18:57 -03:00
|
|
|
void update_send();
|
|
|
|
void update_receive();
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2019-04-26 01:44:34 -03:00
|
|
|
// minimum amount of time (in microseconds) that must remain in
|
|
|
|
// the main scheduler loop before we are allowed to send any
|
|
|
|
// mavlink messages. We want to prioritise the main flight
|
|
|
|
// control loop over communications
|
|
|
|
virtual uint16_t min_loop_time_remaining_for_message_send_us() const {
|
|
|
|
return 200;
|
2017-08-20 23:32:25 -03:00
|
|
|
}
|
2018-12-10 03:56:32 -04:00
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
void init();
|
2018-12-10 03:56:32 -04:00
|
|
|
void setup_console();
|
|
|
|
void setup_uarts();
|
|
|
|
|
2019-04-26 01:44:34 -03:00
|
|
|
bool out_of_time() const;
|
2017-08-20 23:32:25 -03:00
|
|
|
|
2022-04-16 23:54:08 -03:00
|
|
|
#if AP_FRSKY_TELEM_ENABLED
|
2019-02-12 07:54:24 -04:00
|
|
|
// frsky backend
|
2022-02-25 01:06:31 -04:00
|
|
|
class AP_Frsky_Telem *frsky;
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2022-06-27 03:39:33 -03:00
|
|
|
#if AP_LTM_TELEM_ENABLED
|
2019-09-05 02:01:47 -03:00
|
|
|
// LTM backend
|
|
|
|
AP_LTM_Telem ltm_telemetry;
|
2021-11-18 23:34:22 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AP_DEVO_TELEM_ENABLED
|
2019-02-13 19:11:52 -04:00
|
|
|
// Devo backend
|
|
|
|
AP_DEVO_Telem devo_telemetry;
|
2019-09-03 21:37:06 -03:00
|
|
|
#endif
|
2019-02-13 19:11:52 -04:00
|
|
|
|
2018-03-25 07:45:48 -03:00
|
|
|
// install an alternative protocol handler
|
|
|
|
bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler);
|
2018-07-01 07:49:30 -03:00
|
|
|
|
|
|
|
// get the VFR_HUD throttle
|
2022-12-22 02:33:16 -04:00
|
|
|
int16_t get_hud_throttle(void) const {
|
|
|
|
const GCS_MAVLINK *link = chan(0);
|
|
|
|
if (link == nullptr) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return link->vfr_hud_throttle();
|
|
|
|
}
|
2018-08-06 02:51:38 -03:00
|
|
|
|
2018-12-19 07:25:20 -04:00
|
|
|
// update uart pass-thru
|
|
|
|
void update_passthru();
|
|
|
|
|
2019-02-13 21:59:00 -04:00
|
|
|
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
|
2019-03-01 07:50:05 -04:00
|
|
|
virtual bool vehicle_initialised() const { return true; }
|
2019-02-13 21:59:00 -04:00
|
|
|
|
2019-03-01 19:27:52 -04:00
|
|
|
virtual bool simple_input_active() const { return false; }
|
|
|
|
virtual bool supersimple_input_active() const { return false; }
|
|
|
|
|
2019-10-02 04:17:09 -03:00
|
|
|
// set message interval for a given serial port and message id
|
|
|
|
// this function is for use by lua scripts, most consumers should use the channel level function
|
2019-09-10 22:26:15 -03:00
|
|
|
MAV_RESULT set_message_interval(uint8_t port_num, uint32_t msg_id, int32_t interval_us);
|
2019-10-02 04:17:09 -03:00
|
|
|
|
2019-09-10 22:26:15 -03:00
|
|
|
uint8_t get_channel_from_port_number(uint8_t port_num);
|
|
|
|
|
2022-01-25 22:51:54 -04:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
2022-12-20 20:34:27 -04:00
|
|
|
bool high_latency_link_enabled;
|
2022-01-25 22:51:54 -04:00
|
|
|
void enable_high_latency_connections(bool enabled);
|
2022-12-20 20:34:27 -04:00
|
|
|
bool get_high_latency_status();
|
2022-01-25 22:51:54 -04:00
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
virtual uint8_t sysid_this_mav() const = 0;
|
|
|
|
|
2022-11-21 23:33:22 -04:00
|
|
|
protected:
|
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart) = 0;
|
|
|
|
|
2019-02-13 21:59:00 -04:00
|
|
|
uint32_t control_sensors_present;
|
|
|
|
uint32_t control_sensors_enabled;
|
|
|
|
uint32_t control_sensors_health;
|
2019-02-19 19:01:16 -04:00
|
|
|
virtual void update_vehicle_sensor_status_flags() {}
|
2019-02-13 20:39:32 -04:00
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
GCS_MAVLINK_Parameters chan_parameters[MAVLINK_COMM_NUM_BUFFERS];
|
|
|
|
uint8_t _num_gcs;
|
|
|
|
GCS_MAVLINK *_chan[MAVLINK_COMM_NUM_BUFFERS];
|
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
private:
|
|
|
|
|
|
|
|
static GCS *_singleton;
|
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
void create_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart);
|
|
|
|
|
2019-12-08 06:37:10 -04:00
|
|
|
char statustext_printf_buffer[256+1];
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2019-11-08 02:58:57 -04:00
|
|
|
virtual AP_GPS::GPS_Status min_status_for_gps_healthy() const {
|
|
|
|
// NO_FIX simply excludes NO_GPS
|
|
|
|
return AP_GPS::GPS_Status::NO_FIX;
|
|
|
|
}
|
|
|
|
|
2019-08-16 01:22:15 -03:00
|
|
|
void update_sensor_status_flags();
|
|
|
|
|
2021-02-04 22:28:08 -04:00
|
|
|
// time we last saw traffic from our GCS
|
|
|
|
uint32_t _sysid_mygcs_last_seen_time_ms;
|
|
|
|
|
2020-01-12 22:08:14 -04:00
|
|
|
void service_statustext(void);
|
2019-09-29 20:08:44 -03:00
|
|
|
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2021-05-25 03:54:21 -03:00
|
|
|
static const uint8_t _status_capacity = 7;
|
2016-05-30 07:05:00 -03:00
|
|
|
#else
|
|
|
|
static const uint8_t _status_capacity = 30;
|
|
|
|
#endif
|
|
|
|
|
2021-05-25 03:54:21 -03:00
|
|
|
// queue of outgoing statustext messages. Each entry consumes 58
|
|
|
|
// bytes of RAM on stm32
|
2020-05-03 01:06:23 -03:00
|
|
|
StatusTextQueue _statustext_queue{_status_capacity};
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2019-04-28 23:52:02 -03:00
|
|
|
// true if we have already allocated protocol objects:
|
|
|
|
bool initialised_missionitemprotocol_objects;
|
|
|
|
|
2019-12-17 21:00:33 -04:00
|
|
|
// true if update_send has ever been called:
|
|
|
|
bool update_send_has_been_called;
|
|
|
|
|
2018-12-19 07:25:20 -04:00
|
|
|
// handle passthru between two UARTs
|
|
|
|
struct {
|
|
|
|
bool enabled;
|
|
|
|
bool timer_installed;
|
|
|
|
AP_HAL::UARTDriver *port1;
|
|
|
|
AP_HAL::UARTDriver *port2;
|
|
|
|
uint32_t start_ms;
|
|
|
|
uint32_t last_ms;
|
|
|
|
uint32_t last_port1_data_ms;
|
2020-11-14 22:15:44 -04:00
|
|
|
uint32_t baud1;
|
|
|
|
uint32_t baud2;
|
2018-12-19 07:25:20 -04:00
|
|
|
uint8_t timeout_s;
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
} _passthru;
|
|
|
|
|
|
|
|
// timer called to implement pass-thru
|
|
|
|
void passthru_timer();
|
2020-02-25 00:23:52 -04:00
|
|
|
|
|
|
|
// this contains the index of the GCS_MAVLINK backend we will
|
|
|
|
// first call update_send on. It is incremented each time
|
|
|
|
// GCS::update_send is called so we don't starve later links of
|
|
|
|
// time in which they are permitted to send messages.
|
|
|
|
uint8_t first_backend_to_send;
|
2016-05-30 07:05:00 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
GCS &gcs();
|
2020-03-29 19:49:07 -03:00
|
|
|
|
|
|
|
// send text when we do have a GCS
|
2021-07-11 03:40:22 -03:00
|
|
|
#if !defined(HAL_BUILD_AP_PERIPH)
|
2020-03-29 19:49:07 -03:00
|
|
|
#define GCS_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
|
2021-07-11 03:40:22 -03:00
|
|
|
#else
|
|
|
|
extern "C" {
|
|
|
|
void can_printf(const char *fmt, ...);
|
|
|
|
}
|
|
|
|
#define GCS_SEND_TEXT(severity, format, args...) (void)severity; can_printf(format, ##args)
|
|
|
|
#endif
|
2020-03-29 19:49:07 -03:00
|
|
|
|
2020-12-03 01:41:07 -04:00
|
|
|
#elif defined(HAL_BUILD_AP_PERIPH) && !defined(STM32F1)
|
|
|
|
|
|
|
|
// map send text to can_printf() on larger AP_Periph boards
|
|
|
|
extern "C" {
|
|
|
|
void can_printf(const char *fmt, ...);
|
|
|
|
}
|
|
|
|
#define GCS_SEND_TEXT(severity, format, args...) can_printf(format, ##args)
|
|
|
|
|
2021-08-18 08:42:18 -03:00
|
|
|
#else // HAL_GCS_ENABLED
|
2020-03-29 19:49:07 -03:00
|
|
|
// empty send text when we have no GCS
|
|
|
|
#define GCS_SEND_TEXT(severity, format, args...)
|
|
|
|
|
2021-08-18 08:42:18 -03:00
|
|
|
#endif // HAL_GCS_ENABLED
|
2020-03-29 19:49:07 -03:00
|
|
|
|