Browse Source
This adds a class to allow for retransmission of outgoing commands. The sent commands are kept in a timestamped list to check if they are acked as required by the mavlink protocol. If they are not acked within a timeout, they can be retransmitted.sbg
7 changed files with 527 additions and 18 deletions
@ -0,0 +1,230 @@
@@ -0,0 +1,230 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file mavlink_command_sender.cpp |
||||
* Mavlink commands sender with support for retransmission. |
||||
* |
||||
* @author Julian Oes <julian@oes.ch> |
||||
*/ |
||||
|
||||
#include "mavlink_command_sender.h" |
||||
#include <px4_log.h> |
||||
#include <cassert> |
||||
|
||||
bool MavlinkCommandSender::_init = false; |
||||
MavlinkCommandSender *MavlinkCommandSender::_instance = nullptr; |
||||
px4_sem_t MavlinkCommandSender::_lock; |
||||
|
||||
void MavlinkCommandSender::initialize() |
||||
{ |
||||
if (_init) { |
||||
return; |
||||
} |
||||
|
||||
px4_sem_init(&_lock, 1, 1); |
||||
_init = true; |
||||
} |
||||
|
||||
MavlinkCommandSender &MavlinkCommandSender::instance() |
||||
{ |
||||
if (_instance == nullptr) { |
||||
_instance = new MavlinkCommandSender(); |
||||
} |
||||
|
||||
return *_instance; |
||||
} |
||||
|
||||
MavlinkCommandSender::MavlinkCommandSender() : |
||||
_commands(5) |
||||
{ |
||||
} |
||||
|
||||
MavlinkCommandSender::~MavlinkCommandSender() |
||||
{ |
||||
px4_sem_destroy(&_lock); |
||||
} |
||||
|
||||
int MavlinkCommandSender::handle_vehicle_command(struct vehicle_command_s &command, mavlink_channel_t channel) |
||||
{ |
||||
assert(0 <= channel); |
||||
assert(channel < MAX_MAVLINK_CHANNEL); |
||||
|
||||
lock(); |
||||
PX4_INFO("getting vehicle command with timestamp %" PRIu64 ", channel: %d", command.timestamp, channel); |
||||
|
||||
mavlink_command_long_t msg = {}; |
||||
msg.target_system = command.target_system; |
||||
msg.target_component = command.target_component; |
||||
msg.command = command.command; |
||||
msg.confirmation = command.confirmation; |
||||
msg.param1 = command.param1; |
||||
msg.param2 = command.param2; |
||||
msg.param3 = command.param3; |
||||
msg.param4 = command.param4; |
||||
msg.param5 = command.param5; |
||||
msg.param6 = command.param6; |
||||
msg.param7 = command.param7; |
||||
mavlink_msg_command_long_send_struct(channel, &msg); |
||||
|
||||
bool already_existing = false; |
||||
_commands.reset_to_start(); |
||||
|
||||
while (command_item_t *item = _commands.get_next()) { |
||||
if (item->timestamp_us == command.timestamp) { |
||||
|
||||
// We should activate the channel by setting num_sent_per_channel from -1 to 0.
|
||||
item->num_sent_per_channel[channel] = 0; |
||||
|
||||
PX4_INFO("already existing"); |
||||
already_existing = true; |
||||
|
||||
break; |
||||
} |
||||
} |
||||
|
||||
if (!already_existing) { |
||||
|
||||
command_item_t new_item; |
||||
new_item.command = msg; |
||||
new_item.timestamp_us = command.timestamp; |
||||
new_item.num_sent_per_channel[channel] = 0; |
||||
new_item.last_time_sent_us = hrt_absolute_time(); |
||||
_commands.put(new_item); |
||||
} |
||||
|
||||
unlock(); |
||||
return 0; |
||||
} |
||||
|
||||
void MavlinkCommandSender::handle_mavlink_command_ack(const mavlink_command_ack_t &ack, |
||||
uint8_t from_sysid, uint8_t from_compid) |
||||
{ |
||||
PX4_INFO("handling result %d for command %d: %d from %d, %d", |
||||
ack.result, ack.command, from_sysid, from_compid); |
||||
lock(); |
||||
|
||||
_commands.reset_to_start(); |
||||
|
||||
while (command_item_t *item = _commands.get_next()) { |
||||
// Check if the incoming ack matches any of the commands that we have sent.
|
||||
if (item->command.command == ack.command && |
||||
from_sysid == item->command.target_system && |
||||
from_compid == item->command.target_component) { |
||||
PX4_INFO("handling result %d for command %d: %d", ack.result, ack.command); |
||||
// Drop it anyway because the command seems to have arrived at the destination, even if we
|
||||
// receive IN_PROGRESS because we trust that it will be handled after that.
|
||||
_commands.drop_current(); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
unlock(); |
||||
} |
||||
|
||||
void MavlinkCommandSender::check_timeout(mavlink_channel_t channel) |
||||
{ |
||||
assert(0 <= channel); |
||||
assert(channel < MAX_MAVLINK_CHANNEL); |
||||
|
||||
lock(); |
||||
|
||||
_commands.reset_to_start(); |
||||
|
||||
while (command_item_t *item = _commands.get_next()) { |
||||
if (hrt_elapsed_time(&item->last_time_sent_us) <= TIMEOUT_US) { |
||||
// We keep waiting for the timeout.
|
||||
continue; |
||||
} |
||||
|
||||
// The goal of this is to retry from all channels. Therefore, we keep
|
||||
// track of the retry count for each channel.
|
||||
//
|
||||
// When the first channel does a retry, the timeout is reset.
|
||||
// (e.g. all channel have done 2 retries, then channel 0 is called
|
||||
// and does retry number 3, and also resets the timeout timestamp).
|
||||
|
||||
// First, we need to determine what the current max and min retry level
|
||||
// are because we can only level up, if all have caught up.
|
||||
// If num_sent_per_channel is at -1, the channel is inactive.
|
||||
int8_t max_sent = 0; |
||||
int8_t min_sent = INT8_MAX; |
||||
|
||||
for (unsigned i = 0; i < MAX_MAVLINK_CHANNEL; ++i) { |
||||
if (item->num_sent_per_channel[i] > max_sent) { |
||||
max_sent = item->num_sent_per_channel[i]; |
||||
} |
||||
|
||||
if ((item->num_sent_per_channel[i] != -1) && |
||||
(item->num_sent_per_channel[i] < min_sent)) { |
||||
min_sent = item->num_sent_per_channel[i]; |
||||
} |
||||
} |
||||
|
||||
if (item->num_sent_per_channel[channel] < max_sent) { |
||||
// We are behind and need to do a retransmission.
|
||||
mavlink_msg_command_long_send_struct(channel, &item->command); |
||||
item->num_sent_per_channel[channel]++; |
||||
|
||||
PX4_INFO("%x timeout (behind), retries: %d/%d, channel: %d", |
||||
item, item->num_sent_per_channel[channel], max_sent, channel); |
||||
|
||||
} else if (item->num_sent_per_channel[channel] == max_sent && |
||||
min_sent == max_sent) { |
||||
|
||||
// If the next retry would be above the needed retries anyway, we can
|
||||
// drop the item, and continue with other items.
|
||||
if (item->num_sent_per_channel[channel] + 1 > RETRIES) { |
||||
_commands.drop_current(); |
||||
PX4_INFO("%x, timeout dropped", item); |
||||
continue; |
||||
} |
||||
|
||||
// We are the first of a new retransmission series.
|
||||
mavlink_msg_command_long_send_struct(channel, &item->command); |
||||
item->num_sent_per_channel[channel]++; |
||||
// Therefore, we are the ones setting the timestamp of this retry round.
|
||||
item->last_time_sent_us = hrt_absolute_time(); |
||||
|
||||
PX4_INFO("%x timeout (first), retries: %d/%d, channel: %d", |
||||
item, item->num_sent_per_channel[channel], max_sent, channel); |
||||
|
||||
} else { |
||||
// We are already ahead, so this should not happen.
|
||||
// If it ever does, just ignore it. It will timeout eventually.
|
||||
continue; |
||||
} |
||||
} |
||||
|
||||
unlock(); |
||||
} |
@ -0,0 +1,125 @@
@@ -0,0 +1,125 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file mavlink_command_sender.h |
||||
* Mavlink commands sender with support for retransmission. |
||||
* |
||||
* @author Julian Oes <julian@oes.ch> |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <px4_tasks.h> |
||||
#include <px4_sem.h> |
||||
#include <drivers/drv_hrt.h> |
||||
|
||||
#include <uORB/topics/vehicle_command.h> |
||||
#include <uORB/topics/vehicle_command_ack.h> |
||||
|
||||
#include "timestamped_list.h" |
||||
#include "mavlink_bridge_header.h" |
||||
#include <v2.0/mavlink_types.h> |
||||
|
||||
/**
|
||||
* @class MavlinkCommandSender |
||||
*/ |
||||
class MavlinkCommandSender |
||||
{ |
||||
public: |
||||
/**
|
||||
* initialize: call this once on startup (this function is not thread-safe!) |
||||
*/ |
||||
static void initialize(); |
||||
|
||||
static MavlinkCommandSender &instance(); |
||||
|
||||
/**
|
||||
* Send a command on a channel and keep it in a queue for retransmission. |
||||
* thread-safe |
||||
* @return 0 on success, <0 otherwise |
||||
*/ |
||||
int handle_vehicle_command(struct vehicle_command_s &command, mavlink_channel_t channel); |
||||
|
||||
/**
|
||||
* Check timeouts to verify if an commands need retransmission. |
||||
* thread-safe |
||||
*/ |
||||
void check_timeout(mavlink_channel_t channel); |
||||
|
||||
/**
|
||||
* Handle mavlink command_ack. |
||||
* thread-safe |
||||
*/ |
||||
void handle_mavlink_command_ack(const mavlink_command_ack_t &ack, uint8_t from_sysid, uint8_t from_compid); |
||||
|
||||
private: |
||||
MavlinkCommandSender(); |
||||
|
||||
~MavlinkCommandSender(); |
||||
|
||||
static void lock() |
||||
{ |
||||
do {} while (px4_sem_wait(&_lock) != 0); |
||||
} |
||||
|
||||
static void unlock() |
||||
{ |
||||
px4_sem_post(&_lock); |
||||
} |
||||
|
||||
|
||||
static bool _init; |
||||
static MavlinkCommandSender *_instance; |
||||
|
||||
static px4_sem_t _lock; |
||||
|
||||
// There are MAVLINK_COMM_0 to MAVLINK_COMM_3, so it should be 4.
|
||||
static const unsigned MAX_MAVLINK_CHANNEL = 4; |
||||
|
||||
typedef struct { |
||||
mavlink_command_long_t command = {}; |
||||
hrt_abstime timestamp_us = 0; |
||||
hrt_abstime last_time_sent_us = 0; |
||||
int8_t num_sent_per_channel[MAX_MAVLINK_CHANNEL] = {-1, -1, -1, -1}; |
||||
} command_item_t; |
||||
|
||||
TimestampedList<command_item_t> _commands; |
||||
|
||||
static const uint8_t RETRIES = 3; |
||||
static const uint64_t TIMEOUT_US = 500000; |
||||
|
||||
/* do not allow copying or assigning this class */ |
||||
MavlinkCommandSender(const MavlinkCommandSender &) = delete; |
||||
MavlinkCommandSender operator=(const MavlinkCommandSender &) = delete; |
||||
}; |
@ -0,0 +1,158 @@
@@ -0,0 +1,158 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file timestamped list.h |
||||
* Fixed size list with timestamps. |
||||
* |
||||
* The list has a fixed size that is set at instantiation and is based |
||||
* on timestamps. If a new value is put into a full list, the oldest value |
||||
* is overwritten. |
||||
* |
||||
* @author Julian Oes <julian@oes.ch> |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <drivers/drv_hrt.h> |
||||
|
||||
/**
|
||||
* @class TimestampedList |
||||
*/ |
||||
template <class T> |
||||
class TimestampedList |
||||
{ |
||||
public: |
||||
TimestampedList(int num_items) |
||||
{ |
||||
_list = new item_t[num_items]; |
||||
_list_len = num_items; |
||||
} |
||||
~TimestampedList() |
||||
{ |
||||
delete[] _list; |
||||
} |
||||
|
||||
/*
|
||||
* Insert a value into the list, overwrite the oldest entry if full. |
||||
*/ |
||||
void put(T new_value) |
||||
{ |
||||
hrt_abstime now = hrt_absolute_time(); |
||||
|
||||
// Insert it wherever there is a free space.
|
||||
for (int i = 0; i < _list_len; ++i) { |
||||
if (_list[i].timestamp_us == 0) { |
||||
_list[i].timestamp_us = now; |
||||
_list[i].value = new_value; |
||||
return; |
||||
} |
||||
} |
||||
|
||||
// Find oldest entry.
|
||||
int oldest_i = 0; |
||||
|
||||
for (int i = 1; i < _list_len; ++i) { |
||||
if (_list[i].timestamp_us < _list[oldest_i].timestamp_us) { |
||||
oldest_i = i; |
||||
} |
||||
} |
||||
|
||||
// And overwrite oldest.
|
||||
_list[oldest_i].timestamp_us = now; |
||||
_list[oldest_i].value = new_value; |
||||
} |
||||
|
||||
/*
|
||||
* Before iterating using get_next(), reset to start. |
||||
*/ |
||||
void reset_to_start() |
||||
{ |
||||
_current_i = -1; |
||||
} |
||||
|
||||
/*
|
||||
* Iterate through all active values (not sorted). |
||||
* Return nullptr if at end of list. |
||||
* |
||||
* This is basically a poor man's iterator. |
||||
*/ |
||||
T *get_next() |
||||
{ |
||||
// Increment first, then leave it until called again.
|
||||
++_current_i; |
||||
|
||||
for (int i = _current_i; i < _list_len; ++i) { |
||||
if (_list[i].timestamp_us != 0) { |
||||
_current_i = i; |
||||
return &_list[i].value; |
||||
} |
||||
} |
||||
|
||||
return nullptr; |
||||
} |
||||
|
||||
/*
|
||||
* Disable the last item that we have gotten. |
||||
*/ |
||||
void drop_current() |
||||
{ |
||||
if (_current_i < _list_len) { |
||||
_list[_current_i].timestamp_us = 0; |
||||
} |
||||
} |
||||
|
||||
/*
|
||||
* Update the timestamp of the item we have gotten. |
||||
*/ |
||||
void update_current() |
||||
{ |
||||
if (_current_i < _list_len) { |
||||
_list[_current_i].timestamp = hrt_absolute_time(); |
||||
} |
||||
} |
||||
|
||||
/* do not allow copying or assigning this class */ |
||||
TimestampedList(const TimestampedList &) = delete; |
||||
TimestampedList operator=(const TimestampedList &) = delete; |
||||
|
||||
private: |
||||
typedef struct { |
||||
hrt_abstime timestamp_us = 0; // 0 signals inactive.
|
||||
T value; |
||||
} item_t; |
||||
|
||||
item_t *_list = nullptr; |
||||
int _list_len = 0; |
||||
int _current_i = -1; |
||||
}; |
Loading…
Reference in new issue