Skip to content

Commit

Permalink
use new SteadyTimer instead of WallTimer
Browse files Browse the repository at this point in the history
  • Loading branch information
flixr authored and mikaelarguedas committed Mar 25, 2017
1 parent 434c89a commit 0fa28b5
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions bondcpp/include/bondcpp/bond.h
Expand Up @@ -164,15 +164,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
4 changes: 2 additions & 2 deletions bondcpp/include/bondcpp/timeout.h
Expand Up @@ -51,12 +51,12 @@ class Timeout

private:
ros::NodeHandle nh_;
ros::WallTimer timer_;
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
4 changes: 2 additions & 2 deletions bondcpp/src/bond.cpp
Expand Up @@ -174,7 +174,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(ros::WallDuration(heartbeat_period_), &Bond::doPublishing, this);
publishingTimer_ = nh_.createSteadyTimer(ros::WallDuration(heartbeat_period_), &Bond::doPublishing, this);
started_ = true;
}

Expand Down Expand Up @@ -330,7 +330,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
4 changes: 2 additions & 2 deletions bondcpp/src/timeout.cpp
Expand Up @@ -62,7 +62,7 @@ void Timeout::setDuration(const ros::WallDuration &d)
void Timeout::reset()
{
timer_.stop();
timer_ = nh_.createWallTimer(duration_, &Timeout::timerCallback, this, true);
timer_ = nh_.createSteadyTimer(duration_, &Timeout::timerCallback, this, true);
deadline_ = ros::SteadyTime::now() + duration_;
}

Expand All @@ -76,7 +76,7 @@ ros::WallDuration Timeout::left()
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

0 comments on commit 0fa28b5

Please sign in to comment.