Skip to content
Snippets Groups Projects
Commit 7cc4da0d authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Made loop_rate_ attribute private; Added setRate and getRate protected functions

parent ea264ee4
No related branches found
No related tags found
No related merge requests found
......@@ -110,16 +110,6 @@ class IriBaseAlgorithm
*/
ros::NodeHandle private_node_handle_;
/**
* \brief main thread loop rate
*
* This value determines the loop frequency of the node main thread function
* mainThread() in HZ. It is initialized at construction time. This variable
* may be modified in the node implementation constructor if a desired
* frequency is required.
*/
ros::Rate loop_rate_;
/**
* \brief default main thread frequency
*
......@@ -179,7 +169,31 @@ class IriBaseAlgorithm
*/
dynamic_reconfigure::Server<Config> dsrv_;
/**
* \brief main thread loop rate
*
* This value determines the loop frequency of the node main thread function
* mainThread() in HZ. It is initialized at construction time. This variable
* may be modified in the node implementation constructor if a desired
* frequency is required.
*/
ros::Rate loop_rate_;
protected:
/**
* \brief
*
*/
void setRate(double rate_hz);
/**
* \brief
*
*/
double getRate(void);
/**
* \brief dynamic reconfigure server callback
*
......@@ -273,6 +287,19 @@ IriBaseAlgorithm<Algorithm>::~IriBaseAlgorithm()
pthread_join(this->thread,NULL);
}
template <class Algorithm>
void IriBaseAlgorithm<Algorithm>::setRate(double rate_hz)
{
this->loop_rate_=rate_hz;
}
template <class Algorithm>
double IriBaseAlgorithm<Algorithm>::getRate(void)
{
return this->loop_rate_;
}
template <class Algorithm>
void IriBaseAlgorithm<Algorithm>::reconfigureCallback(Config &config, uint32_t level)
{
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment