Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use SteadyTime and SteadyTimer for bond timeouts #18

Merged
merged 3 commits into from Jul 20, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 2 additions & 2 deletions bondcpp/include/bondcpp/bond.h
Expand Up @@ -167,15 +167,15 @@ class Bond

ros::Subscriber sub_;
ros::Publisher pub_;
ros::WallTimer publishingTimer_;
ros::SteadyTimer publishingTimer_;

void onConnectTimeout();
void onHeartbeatTimeout();
void onDisconnectTimeout();

void bondStatusCB(const bond::Status::ConstPtr &msg);

void doPublishing(const ros::WallTimerEvent &e);
void doPublishing(const ros::SteadyTimerEvent &e);
void publishStatus(bool active);

std::vector<boost::function<void(void)> > pending_callbacks_;
Expand Down
6 changes: 3 additions & 3 deletions bondcpp/include/bondcpp/timeout.h
Expand Up @@ -55,12 +55,12 @@ class Timeout

private:
ros::NodeHandle nh_;
ros::WallTimer timer_;
ros::WallTime deadline_;
ros::SteadyTimer timer_;
ros::SteadyTime deadline_;
ros::WallDuration duration_;
boost::function<void(void)> on_timeout_;

void timerCallback(const ros::WallTimerEvent &e);
void timerCallback(const ros::SteadyTimerEvent &e);
};


Expand Down
12 changes: 6 additions & 6 deletions bondcpp/src/bond.cpp
Expand Up @@ -178,7 +178,7 @@ void Bond::start()
pub_ = nh_.advertise<bond::Status>(topic_, 5);
sub_ = nh_.subscribe<bond::Status>(topic_, 30, boost::bind(&Bond::bondStatusCB, this, _1));

publishingTimer_ = nh_.createWallTimer(
publishingTimer_ = nh_.createSteadyTimer(
ros::WallDuration(heartbeat_period_), &Bond::doPublishing, this);
started_ = true;
}
Expand All @@ -202,7 +202,7 @@ bool Bond::waitUntilFormed(ros::Duration timeout)
bool Bond::waitUntilFormed(ros::WallDuration timeout)
{
boost::mutex::scoped_lock lock(mutex_);
ros::WallTime deadline(ros::WallTime::now() + timeout);
ros::SteadyTime deadline(ros::SteadyTime::now() + timeout);

while (sm_.getState().getId() == SM::WaitingForSister.getId()) {
if (!ros::ok()) {
Expand All @@ -211,7 +211,7 @@ bool Bond::waitUntilFormed(ros::WallDuration timeout)

ros::WallDuration wait_time = ros::WallDuration(0.1);
if (timeout >= ros::WallDuration(0.0)) {
wait_time = std::min(wait_time, deadline - ros::WallTime::now());
wait_time = std::min(wait_time, deadline - ros::SteadyTime::now());
}

if (wait_time <= ros::WallDuration(0.0)) {
Expand All @@ -230,7 +230,7 @@ bool Bond::waitUntilBroken(ros::Duration timeout)
bool Bond::waitUntilBroken(ros::WallDuration timeout)
{
boost::mutex::scoped_lock lock(mutex_);
ros::WallTime deadline(ros::WallTime::now() + timeout);
ros::SteadyTime deadline(ros::SteadyTime::now() + timeout);

while (sm_.getState().getId() != SM::Dead.getId()) {
if (!ros::ok()) {
Expand All @@ -239,7 +239,7 @@ bool Bond::waitUntilBroken(ros::WallDuration timeout)

ros::WallDuration wait_time = ros::WallDuration(0.1);
if (timeout >= ros::WallDuration(0.0)) {
wait_time = std::min(wait_time, deadline - ros::WallTime::now());
wait_time = std::min(wait_time, deadline - ros::SteadyTime::now());
}

if (wait_time <= ros::WallDuration(0.0)) {
Expand Down Expand Up @@ -337,7 +337,7 @@ void Bond::bondStatusCB(const bond::Status::ConstPtr &msg)
}
}

void Bond::doPublishing(const ros::WallTimerEvent &)
void Bond::doPublishing(const ros::SteadyTimerEvent &)
{
boost::mutex::scoped_lock lock(mutex_);
if (sm_.getState().getId() == SM::WaitingForSister.getId() ||
Expand Down
8 changes: 4 additions & 4 deletions bondcpp/src/timeout.cpp
Expand Up @@ -64,8 +64,8 @@ void Timeout::setDuration(const ros::WallDuration &d)
void Timeout::reset()
{
timer_.stop();
timer_ = nh_.createWallTimer(duration_, &Timeout::timerCallback, this, true);
deadline_ = ros::WallTime::now() + duration_;
timer_ = nh_.createSteadyTimer(duration_, &Timeout::timerCallback, this, true);
deadline_ = ros::SteadyTime::now() + duration_;
}

void Timeout::cancel()
Expand All @@ -75,10 +75,10 @@ void Timeout::cancel()

ros::WallDuration Timeout::left()
{
return std::max(ros::WallDuration(0.0), deadline_ - ros::WallTime::now());
return std::max(ros::WallDuration(0.0), deadline_ - ros::SteadyTime::now());
}

void Timeout::timerCallback(const ros::WallTimerEvent &)
void Timeout::timerCallback(const ros::SteadyTimerEvent &)
{
if (on_timeout_) {
on_timeout_();
Expand Down