mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
GCS_MAVLink: added private channel mask
this allows a channel to be marked "private". A private channel gets heartbeats, but doesn't get forwarded packets or broadcast messages This is used by solo gimbal driver
This commit is contained in:
parent
635540b4d6
commit
1e354d53c9
@ -207,6 +207,18 @@ public:
|
||||
// return a bitmap of streaming channels
|
||||
static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
|
||||
|
||||
// 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); }
|
||||
|
||||
// send queued parameters if needed
|
||||
void send_queued_parameters(void);
|
||||
|
||||
@ -463,6 +475,9 @@ private:
|
||||
// bitmask of what mavlink channels are active
|
||||
static uint8_t mavlink_active;
|
||||
|
||||
// bitmask of what mavlink channels are private
|
||||
static uint8_t mavlink_private;
|
||||
|
||||
// bitmask of what mavlink channels are streaming
|
||||
static uint8_t chan_is_streaming;
|
||||
|
||||
|
@ -50,6 +50,10 @@ uint8_t GCS_MAVLINK::mavlink_active = 0;
|
||||
uint8_t GCS_MAVLINK::chan_is_streaming = 0;
|
||||
uint32_t GCS_MAVLINK::reserve_param_space_start_ms;
|
||||
|
||||
// private channels are ones used for point-to-point protocols, and
|
||||
// don't get broadcasts or fwded packets
|
||||
uint8_t GCS_MAVLINK::mavlink_private = 0;
|
||||
|
||||
GCS *GCS::_singleton = nullptr;
|
||||
|
||||
GCS_MAVLINK::GCS_MAVLINK()
|
||||
@ -900,7 +904,10 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
|
||||
// we exclude radio packets because we historically used this to
|
||||
// make it possible to use the CLI over the radio
|
||||
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
|
||||
mavlink_active |= (1U<<(chan-MAVLINK_COMM_0));
|
||||
const uint8_t mask = (1U<<(chan-MAVLINK_COMM_0));
|
||||
if (!(mask & mavlink_private)) {
|
||||
mavlink_active |= mask;
|
||||
}
|
||||
}
|
||||
if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
|
||||
(status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) &&
|
||||
@ -985,7 +992,7 @@ GCS_MAVLINK::update(uint32_t max_time_us)
|
||||
|
||||
// send a timesync message every 10 seconds; this is for data
|
||||
// collection purposes
|
||||
if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms) {
|
||||
if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms && !is_private()) {
|
||||
if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
|
||||
send_timesync();
|
||||
_timesync_request.last_sent_ms = tnow;
|
||||
|
@ -69,6 +69,15 @@ void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
|
||||
}
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
|
||||
// return a MAVLink variable type given a AP_Param type
|
||||
uint8_t mav_var_type(enum ap_var_type t)
|
||||
{
|
||||
|
@ -143,7 +143,9 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
||||
(broadcast_component ||
|
||||
target_component == routes[i].compid ||
|
||||
!match_system))) {
|
||||
if (in_channel != routes[i].channel && !sent_to_chan[routes[i].channel]) {
|
||||
if (in_channel != routes[i].channel &&
|
||||
!sent_to_chan[routes[i].channel] &&
|
||||
!GCS_MAVLINK::is_private(routes[i].channel)) {
|
||||
if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) +
|
||||
GCS_MAVLINK::packet_overhead_chan(routes[i].channel)) {
|
||||
#if ROUTING_DEBUG
|
||||
|
Loading…
Reference in New Issue
Block a user