ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
9

ros::Timer won't start if initialized before dynamic reconfigure server

asked 2020-10-26 03:05:19 -0500

klaxalk gravatar image

Hey, I am not sure where to post the issue, so I am showing it here first. Maybe I am doing something wrong.

My ros::Timer won't start if I initialize it before the initialization of a dynamic reconfigure server. Here is the summary:

Environment

  • Ubuntu 20.04 + ROS Noetic
  • empty workspace with no specific flags
  • tested on amd64 or arm64

Observations

  • when ros::Timer is initialized before a dynamic reconfigure server (DRS), the timer won't start
  • it affects fast timers (100 Hz and more) rather than slow timers
  • it is non-deterministic, sometimes it starts correctly
  • the higher the number of DRS parameters, the higher the chance of replicating the issue (10+ parameters = near 100% chance)
  • seems not to be influenced by the computational resources, happens on i9-9900K as well as on Rpi4
  • does not happen at all on 18.04 + ROS Melodic

Minimal non-working example

Solution

  • I don't know, the DRS seems to be devoid of ros::Timers.
  • Can't say for sure, but swapping the order is not a viable workaround for ros::Pluginlib plugins. So far it looks like some plugins' timers are blocked by other plugins' DRSs.
  • the only workaround I found is to use a slow timer (or a thread) to check the activity and restart any broken fast timers... but... duh...

Sources

Full sources here: https://github.com/klaxalk/ros_timer_...

The main cpp file:

#include <ros/ros.h>
#include <nodelet/nodelet.h>

#include <dynamic_reconfigure/server.h>
#include <timer_tester/timer_testerConfig.h>

#define TIMERS_BEFORE 1

namespace timer_tester
{

class TimerTester : public nodelet::Nodelet {

public:
  virtual void onInit();

private:
  ros::NodeHandle nh_;

  // | --------------- dynamic reconfigure server --------------- |

  boost::recursive_mutex                           mutex_drs_;
  typedef timer_tester::timer_testerConfig         DrsConfig_t;
  typedef dynamic_reconfigure::Server<DrsConfig_t> Drs_t;
  boost::shared_ptr<Drs_t>                         drs_;
  void                                             callbackDrs(timer_tester::timer_testerConfig& config, uint32_t level);

  // | ------------------------- timers ------------------------- |

  ros::Timer timer_fast_;
  void       timerFast(const ros::TimerEvent& te);

  ros::Timer timer_slow_;
  void       timerSlow(const ros::TimerEvent& te);
};

void TimerTester::onInit() {

  ros::NodeHandle nh_ = nodelet::Nodelet::getMTPrivateNodeHandle();

  ros::Time::waitForValid();

  ROS_INFO("[TimerTester]: initializing");

#if TIMERS_BEFORE == 1
  ROS_INFO("[TimerTester]: creating timers before DRS");
  timer_fast_ = nh_.createTimer(ros::Rate(100.0), &TimerTester::timerFast, this);
  timer_slow_ = nh_.createTimer(ros::Rate(1.0), &TimerTester::timerSlow, this);
#endif

  // | --------------- dynamic reconfigure server --------------- |

  drs_.reset(new Drs_t(mutex_drs_, nh_));
  Drs_t::CallbackType f = boost::bind(&TimerTester::callbackDrs, this, _1, _2);
  drs_->setCallback(f);

#if TIMERS_BEFORE == 0
  ROS_INFO("[TimerTester]: creating timers after DRS");
  timer_fast_ = nh_.createTimer(ros::Rate(100.0), &TimerTester::timerFast, this);
  timer_slow_ = nh_.createTimer(ros::Rate(1.0), &TimerTester::timerSlow, this);
#endif

  ROS_INFO_ONCE("[TimerTester]: initialized");
}

// | --------------------- timer callbacks -------------------- |

void TimerTester::timerFast([[maybe_unused]] const ros::TimerEvent& te) {

  ROS_INFO_THROTTLE(0.1, "[TimerTester]: 100 Hz timer spinning");
}

void TimerTester::timerSlow([[maybe_unused]] const ros::TimerEvent& te) {

  ROS_INFO_THROTTLE(0.1, "[TimerTester]: 1 Hz timer spinning");
}

void TimerTester::callbackDrs([[maybe_unused]] timer_tester::timer_testerConfig& config, [[maybe_unused]] uint32_t level) {

  ROS_INFO("[TimerTester]: callbackDrs() called");
}

}  // namespace timer_tester

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(timer_tester::TimerTester, nodelet::Nodelet);

The ... (more)

edit retag flag offensive close merge delete

Comments

klaxalk gravatar image klaxalk  ( 2020-10-28 06:57:02 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-11-30 07:48:17 -0500

klaxalk gravatar image

I finally got it. The problem is not with DRS in particular but with anything that takes a non-zero amount of time to execute. It can be broken with sleep() or just with some traditional operations. The problem is in fact caused by the nodelet, specifically by the first commit that got to Noetic: https://github.com/ros/nodelet_core/5272c34. The commit was intended to fix this particular issue, but it, in fact, causes it. They disable callback queues before calling onInit() and re-enable them after. But it seems that this is not a good solution. I have submitted an issue there: https://github.com/ros/nodelet_core/i.... In the meantime, a temporary workaround is to compile the nodelet_core without that commit.

edit flag offensive delete link more

Question Tools

6 followers

Stats

Asked: 2020-10-25 11:07:02 -0500

Seen: 309 times

Last updated: Nov 30 '20