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

Merge Viktor's update #51

Merged
merged 4 commits into from
Apr 11, 2024
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions include/mrs_lib/impl/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ class ThreadTimer::Impl {
void start();
void stop();
void setPeriod(const ros::Duration& duration, const bool reset = true);
void setCallback(const std::function<void(const ros::TimerEvent&)>& callback);

friend class ThreadTimer;

Expand Down
18 changes: 18 additions & 0 deletions include/mrs_lib/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,15 @@ namespace mrs_lib
*/
virtual void setPeriod(const ros::Duration& duration, const bool reset = true) = 0;

/**
* @brief change the callback method
*
* Usable e.g. for running thread with a specific parameter if you bind it using std::bind
*
* @param callback callback method to be called.
*/
virtual void setCallback(const std::function<void(const ros::TimerEvent&)>& callback) = 0;

/**
* @brief returns true if callbacks should be called
*
Expand Down Expand Up @@ -208,6 +217,15 @@ namespace mrs_lib
* @param reset ignored in this implementation.
*/
virtual void setPeriod(const ros::Duration& duration, const bool reset = true) override;

/**
* @brief change the callback method
*
* Usable e.g. for running thread with a specific parameter if you bind it using std::bind
*
* @param callback callback method to be called.
*/
virtual void setCallback(const std::function<void(const ros::TimerEvent&)>& callback) override;

/**
* @brief returns true if callbacks should be called
Expand Down
16 changes: 16 additions & 0 deletions src/timer/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,16 @@ void ThreadTimer::setPeriod(const ros::Duration& duration, [[maybe_unused]] cons

//}

/* ThreadTimer::setCallback() //{ */

void ThreadTimer::setCallback(const std::function<void(const ros::TimerEvent&)>& callback) {
if (impl_) {
impl_->setCallback(callback);
}
}

//}

/* ThreadTimer::running() //{ */

bool ThreadTimer::running()
Expand Down Expand Up @@ -159,6 +169,12 @@ void ThreadTimer::Impl::setPeriod(const ros::Duration& duration, [[maybe_unused]
this->oneshot_ = true;
}

void ThreadTimer::Impl::setCallback(const std::function<void(const ros::TimerEvent&)>& callback){
std::scoped_lock lock(mutex_state_);

callback_ = callback;
}

//}

/* ThreadTimer::breakableSleep() method //{ */
Expand Down
Loading