Setting Timer period for next callback
Hi, I have a ros::Timer that I want to change the period for at each callback. In the callback function, I'm calculating the time I want the next callback to occur at and calling setPeriod. However, calling setPeriod doesn't seem to affect the very NEXT callback. The next one will still occur at the "old" period. The callbacks start occurring at the new period on the second callback after I call setPeriod.
void myCallback(const ros::TimerEvent& e)
{
ROS_INFO("Time between callbacks: %f", (e.current_real - e.last_real).toSec());
// do stuff in callback
if(callbackCount == 0)
{
double t = calculateNextTimeForCallback();
myDuration = ros::Duration(t);
myTimer.setPerior(myDuration);
}
}
I end up with:
Time between callbacks: ros::Time::now (first one) Time between callbacks: old time Time between callbacks: new time Time between callbacks: new time ... Time between callbacks: new time
I'd like to have the new period to take effect on the callback immediately following the one where I call setPeriod. So then I could set a new time for each one. When I try to set the period in EACH callback (rather than just the first), the new periods never take effect.
It seems that the time a new callback occurs is based on the period and the TimerEvent's period.last_duration member. The TimerEvent is const though so I cannot change period.last_duration to hack a way for it to work. I have tried stopping and starting the timer at the end of the callback functions, but that will set the period.last_duration to 0 so the time between one ending and a new one beginning will be the new period which will always be too long.
I'm on Ubuntu 14.04 and Indigo.
If anyone can help me make this work or explain why it won't work, that would be great. If anything is unclear, please comment and I can explain further.
EDIT:
So in my example above, I was doing stuff in the callback that generally took around .3-.6 seconds. I tried to test with a callback that did almost nothing:
void myCallback(const ros::TimerEvent& e)
{
ROS_INFO("Time between callbacks: %f", (e.current_real - e.last_real).toSec());
// timer originally set to 2.0s
myDuration = ros::Duration(0.2);
myTimer.setPeriod(myDuration);
}
In that example, it actually worked just fine. So I tried another simple example that took some time for the callback to process:
void myCallback(const ros::TimerEvent& e)
{
ROS_INFO("Time between callbacks: %f", (e.current_real - e.last_real).toSec());
ROS_INFO("Last duration: %f", e.profile.last_duration.toSec());
for(int i=0;i<5000;i++)
{
ROS_INFO("Line %i", i);
}
// timer originally set to 2.0s
myDuration = ros::Duration(1.8);
myTimer.setPeriod(myDuration);
}
When I print out lots of text, the problem arises again. The time between each callback is last_duration+period. So in the last example, it generally took around .4 seconds to print the lines, and the time between callbacks was generally around 2.2 seconds.