Skip to content

Commit

Permalink
plugins: C++11 chrono want time by ref, return *_DT
Browse files Browse the repository at this point in the history
Fix #80.
  • Loading branch information
vooon committed Aug 5, 2014
1 parent 1e18425 commit 32cbe4b
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 5 deletions.
7 changes: 5 additions & 2 deletions src/plugins/command.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,8 @@ class CommandTransaction {
class CommandPlugin : public MavRosPlugin {
public:
CommandPlugin() :
uas(nullptr)
uas(nullptr),
ACK_TIMEOUT_DT(ACK_TIMEOUT_MS / 1000.0)
{ };

void initialize(UAS &uas_,
Expand Down Expand Up @@ -114,12 +115,14 @@ class CommandPlugin : public MavRosPlugin {
std::list<CommandTransaction *> ack_waiting_list;
static constexpr int ACK_TIMEOUT_MS = 5000;

const ros::Duration ACK_TIMEOUT_DT;

/* -*- mid-level functions -*- */

bool wait_ack_for(CommandTransaction *tr) {
std::unique_lock<std::mutex> lock(tr->cond_mutex);

return tr->ack.wait_for(lock, std::chrono::milliseconds(ACK_TIMEOUT_MS))
return tr->ack.wait_for(lock, std::chrono::nanoseconds(ACK_TIMEOUT_DT.toNSec()))
== std::cv_status::no_timeout;
}

Expand Down
4 changes: 3 additions & 1 deletion src/plugins/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,6 +344,7 @@ class ParamPlugin : public MavRosPlugin {
is_timedout(false),
param_rx_retries(RETRIES_COUNT),
BOOTUP_TIME_DT(BOOTUP_TIME_MS / 1000.0),
LIST_TIMEOUT_DT(LIST_TIMEOUT_MS / 1000.0),
PARAM_TIMEOUT_DT(PARAM_TIMEOUT_MS / 1000.0)
{ };

Expand Down Expand Up @@ -480,6 +481,7 @@ class ParamPlugin : public MavRosPlugin {
static constexpr int RETRIES_COUNT = 3;

const ros::Duration BOOTUP_TIME_DT;
const ros::Duration LIST_TIMEOUT_DT;
const ros::Duration PARAM_TIMEOUT_DT;

std::map<std::string, Parameter> parameters;
Expand Down Expand Up @@ -684,7 +686,7 @@ class ParamPlugin : public MavRosPlugin {
bool wait_fetch_all() {
std::unique_lock<std::mutex> lock(list_cond_mutex);

return list_receiving.wait_for(lock, std::chrono::milliseconds(LIST_TIMEOUT_MS))
return list_receiving.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
== std::cv_status::no_timeout
&& !is_timedout;
}
Expand Down
6 changes: 4 additions & 2 deletions src/plugins/waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ class WaypointPlugin : public MavRosPlugin {
do_pull_after_gcs(false),
reshedule_pull(false),
BOOTUP_TIME_DT(BOOTUP_TIME_MS / 1000.0),
LIST_TIMEOUT_DT(LIST_TIMEOUT_MS / 1000.0),
WP_TIMEOUT_DT(WP_TIMEOUT_MS/ 1000.0),
RESHEDULE_DT(RESHEDULE_MS / 1000.0)
{ };
Expand Down Expand Up @@ -287,6 +288,7 @@ class WaypointPlugin : public MavRosPlugin {
static constexpr int RETRIES_COUNT = 3;

const ros::Duration BOOTUP_TIME_DT;
const ros::Duration LIST_TIMEOUT_DT;
const ros::Duration WP_TIMEOUT_DT;
const ros::Duration RESHEDULE_DT;

Expand Down Expand Up @@ -615,15 +617,15 @@ class WaypointPlugin : public MavRosPlugin {
bool wait_fetch_all() {
std::unique_lock<std::mutex> lock(recv_cond_mutex);

return list_receiving.wait_for(lock, std::chrono::milliseconds(LIST_TIMEOUT_MS))
return list_receiving.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
== std::cv_status::no_timeout
&& !is_timedout;
}

bool wait_push_all() {
std::unique_lock<std::mutex> lock(send_cond_mutex);

return list_sending.wait_for(lock, std::chrono::milliseconds(LIST_TIMEOUT_MS))
return list_sending.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
== std::cv_status::no_timeout
&& !is_timedout;
}
Expand Down

0 comments on commit 32cbe4b

Please sign in to comment.