Skip to content

Commit

Permalink
Merge pull request #1362 from mavlink/pr-adjustable-timeout
Browse files Browse the repository at this point in the history
core: make timeout configurable
  • Loading branch information
julianoes committed Mar 19, 2021
2 parents d438354 + caff092 commit 75faa12
Show file tree
Hide file tree
Showing 12 changed files with 194 additions and 117 deletions.
4 changes: 2 additions & 2 deletions src/core/mavlink_commands.cpp
Expand Up @@ -74,7 +74,7 @@ void MavlinkCommandSender::queue_command_async(
// LogDebug() << "Command " << (int)(command.command) << " to send to "
// << (int)(command.target_system_id)<< ", " << (int)(command.target_component_id);

auto new_work = std::make_shared<Work>();
auto new_work = std::make_shared<Work>(_parent.timeout_s());

mavlink_msg_command_int_pack(
_parent.get_own_system_id(),
Expand Down Expand Up @@ -105,7 +105,7 @@ void MavlinkCommandSender::queue_command_async(
// LogDebug() << "Command " << (int)(command.command) << " to send to "
// << (int)(command.target_system_id)<< ", " << (int)(command.target_component_id);

auto new_work = std::make_shared<Work>();
auto new_work = std::make_shared<Work>(_parent.timeout_s());
mavlink_msg_command_long_pack(
_parent.get_own_system_id(),
_parent.get_own_component_id(),
Expand Down
2 changes: 2 additions & 0 deletions src/core/mavlink_commands.h
Expand Up @@ -116,6 +116,8 @@ class MavlinkCommandSender {
mavlink_message_t mavlink_message{};
CommandResultCallback callback{};
dl_time_t time_started{};

explicit Work(double new_timeout_s) : timeout_s(new_timeout_s) {}
};

void receive_command_ack(mavlink_message_t message);
Expand Down
52 changes: 31 additions & 21 deletions src/core/mavlink_mission_transfer.cpp
Expand Up @@ -5,10 +5,14 @@
namespace mavsdk {

MAVLinkMissionTransfer::MAVLinkMissionTransfer(
Sender& sender, MAVLinkMessageHandler& message_handler, TimeoutHandler& timeout_handler) :
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
TimeoutSCallback timeout_s_callback) :
_sender(sender),
_message_handler(message_handler),
_timeout_handler(timeout_handler)
_timeout_handler(timeout_handler),
_timeout_s_callback(timeout_s_callback)
{}

MAVLinkMissionTransfer::~MAVLinkMissionTransfer() {}
Expand All @@ -17,7 +21,7 @@ std::weak_ptr<MAVLinkMissionTransfer::WorkItem> MAVLinkMissionTransfer::upload_i
uint8_t type, const std::vector<ItemInt>& items, ResultCallback callback)
{
auto ptr = std::make_shared<UploadWorkItem>(
_sender, _message_handler, _timeout_handler, type, items, callback);
_sender, _message_handler, _timeout_handler, type, items, _timeout_s_callback(), callback);

_work_queue.push_back(ptr);

Expand All @@ -28,7 +32,7 @@ std::weak_ptr<MAVLinkMissionTransfer::WorkItem>
MAVLinkMissionTransfer::download_items_async(uint8_t type, ResultAndItemsCallback callback)
{
auto ptr = std::make_shared<DownloadWorkItem>(
_sender, _message_handler, _timeout_handler, type, callback);
_sender, _message_handler, _timeout_handler, type, _timeout_s_callback(), callback);

_work_queue.push_back(ptr);

Expand All @@ -38,15 +42,15 @@ MAVLinkMissionTransfer::download_items_async(uint8_t type, ResultAndItemsCallbac
void MAVLinkMissionTransfer::clear_items_async(uint8_t type, ResultCallback callback)
{
auto ptr = std::make_shared<ClearWorkItem>(
_sender, _message_handler, _timeout_handler, type, callback);
_sender, _message_handler, _timeout_handler, type, _timeout_s_callback(), callback);

_work_queue.push_back(ptr);
}

void MAVLinkMissionTransfer::set_current_item_async(int current, ResultCallback callback)
{
auto ptr = std::make_shared<SetCurrentWorkItem>(
_sender, _message_handler, _timeout_handler, current, callback);
_sender, _message_handler, _timeout_handler, current, _timeout_s_callback(), callback);

_work_queue.push_back(ptr);
}
Expand Down Expand Up @@ -78,11 +82,13 @@ MAVLinkMissionTransfer::WorkItem::WorkItem(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type) :
uint8_t type,
double timeout_s) :
_sender(sender),
_message_handler(message_handler),
_timeout_handler(timeout_handler),
_type(type)
_type(type),
_timeout_s(timeout_s)
{}

MAVLinkMissionTransfer::WorkItem::~WorkItem() {}
Expand All @@ -105,8 +111,9 @@ MAVLinkMissionTransfer::UploadWorkItem::UploadWorkItem(
TimeoutHandler& timeout_handler,
uint8_t type,
const std::vector<ItemInt>& items,
double timeout_s,
ResultCallback callback) :
WorkItem(sender, message_handler, timeout_handler, type),
WorkItem(sender, message_handler, timeout_handler, type, timeout_s),
_items(items),
_callback(callback)
{
Expand Down Expand Up @@ -171,7 +178,7 @@ void MAVLinkMissionTransfer::UploadWorkItem::start()

_retries_done = 0;
_step = Step::SendCount;
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);

_next_sequence = 0;

Expand Down Expand Up @@ -397,7 +404,7 @@ void MAVLinkMissionTransfer::UploadWorkItem::process_timeout()

switch (_step) {
case Step::SendCount:
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
send_count();
break;

Expand All @@ -421,8 +428,9 @@ MAVLinkMissionTransfer::DownloadWorkItem::DownloadWorkItem(
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type,
double timeout_s,
ResultAndItemsCallback callback) :
WorkItem(sender, message_handler, timeout_handler, type),
WorkItem(sender, message_handler, timeout_handler, type, timeout_s),
_callback(callback)
{
std::lock_guard<std::mutex> lock(_mutex);
Expand Down Expand Up @@ -453,7 +461,7 @@ void MAVLinkMissionTransfer::DownloadWorkItem::start()
_items.clear();
_started = true;
_retries_done = 0;
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
request_list();
}

Expand Down Expand Up @@ -617,12 +625,12 @@ void MAVLinkMissionTransfer::DownloadWorkItem::process_timeout()

switch (_step) {
case Step::RequestList:
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
request_list();
break;

case Step::RequestItem:
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
request_item();
break;
}
Expand All @@ -642,8 +650,9 @@ MAVLinkMissionTransfer::ClearWorkItem::ClearWorkItem(
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type,
double timeout_s,
ResultCallback callback) :
WorkItem(sender, message_handler, timeout_handler, type),
WorkItem(sender, message_handler, timeout_handler, type, timeout_s),
_callback(callback)
{
std::lock_guard<std::mutex> lock(_mutex);
Expand All @@ -668,7 +677,7 @@ void MAVLinkMissionTransfer::ClearWorkItem::start()

_started = true;
_retries_done = 0;
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
send_clear();
}

Expand Down Expand Up @@ -709,7 +718,7 @@ void MAVLinkMissionTransfer::ClearWorkItem::process_timeout()
return;
}

_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
send_clear();
}

Expand Down Expand Up @@ -781,8 +790,9 @@ MAVLinkMissionTransfer::SetCurrentWorkItem::SetCurrentWorkItem(
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
int current,
double timeout_s,
ResultCallback callback) :
WorkItem(sender, message_handler, timeout_handler, MAV_MISSION_TYPE_MISSION),
WorkItem(sender, message_handler, timeout_handler, MAV_MISSION_TYPE_MISSION, timeout_s),
_current(current),
_callback(callback)
{
Expand Down Expand Up @@ -814,7 +824,7 @@ void MAVLinkMissionTransfer::SetCurrentWorkItem::start()
}

_retries_done = 0;
_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
send_current_mission_item();
}

Expand Down Expand Up @@ -876,7 +886,7 @@ void MAVLinkMissionTransfer::SetCurrentWorkItem::process_timeout()
return;
}

_timeout_handler.add([this]() { process_timeout(); }, timeout_s, &_cookie);
_timeout_handler.add([this]() { process_timeout(); }, _timeout_s, &_cookie);
send_current_mission_item();
}

Expand Down
25 changes: 18 additions & 7 deletions src/core/mavlink_mission_transfer.h
Expand Up @@ -76,11 +76,12 @@ class MAVLinkMissionTransfer {

class WorkItem {
public:
WorkItem(
explicit WorkItem(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type);
uint8_t type,
double timeout_s);
virtual ~WorkItem();
virtual void start() = 0;
virtual void cancel() = 0;
Expand All @@ -97,19 +98,21 @@ class MAVLinkMissionTransfer {
MAVLinkMessageHandler& _message_handler;
TimeoutHandler& _timeout_handler;
uint8_t _type;
double _timeout_s;
bool _started{false};
bool _done{false};
std::mutex _mutex{};
};

class UploadWorkItem : public WorkItem {
public:
UploadWorkItem(
explicit UploadWorkItem(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type,
const std::vector<ItemInt>& items,
double timeout_s,
ResultCallback callback);

virtual ~UploadWorkItem();
Expand Down Expand Up @@ -146,11 +149,12 @@ class MAVLinkMissionTransfer {

class DownloadWorkItem : public WorkItem {
public:
DownloadWorkItem(
explicit DownloadWorkItem(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type,
double timeout_s,
ResultAndItemsCallback callback);

virtual ~DownloadWorkItem();
Expand Down Expand Up @@ -192,6 +196,7 @@ class MAVLinkMissionTransfer {
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
uint8_t type,
double timeout_s,
ResultCallback callback);

virtual ~ClearWorkItem();
Expand Down Expand Up @@ -221,6 +226,7 @@ class MAVLinkMissionTransfer {
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
int current,
double timeout_s,
ResultCallback callback);

virtual ~SetCurrentWorkItem();
Expand All @@ -245,11 +251,15 @@ class MAVLinkMissionTransfer {
unsigned _retries_done{0};
};

static constexpr double timeout_s = 0.5;
static constexpr unsigned retries = 4;

MAVLinkMissionTransfer(
Sender& sender, MAVLinkMessageHandler& message_handler, TimeoutHandler& timeout_handler);
using TimeoutSCallback = std::function<double()>;

explicit MAVLinkMissionTransfer(
Sender& sender,
MAVLinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
TimeoutSCallback get_timeout_s_callback);

~MAVLinkMissionTransfer();

Expand All @@ -273,6 +283,7 @@ class MAVLinkMissionTransfer {
Sender& _sender;
MAVLinkMessageHandler& _message_handler;
TimeoutHandler& _timeout_handler;
TimeoutSCallback _timeout_s_callback;

LockedQueue<WorkItem> _work_queue{};
};
Expand Down

0 comments on commit 75faa12

Please sign in to comment.