51 const int ROS_RESPONSE_TIME_MS = 100;
52 const float TRY_CONNECT_EVERY_S = 1.0;
53 const float WARN_EVERY_S = 10.0;
57 if (lcm_url.empty()) {
58 lcm_url =
"udpm://225.0.0.0:7667?ttl=1";
63 lcm =
new lcm::LCM(lcm_url);
72 ROS_INFO(
"LCM connected to %s", lcm_url.c_str());
#define ROS_WARN_THROTTLE(rate,...)
ros::NodeHandle & getPrivateNodeHandle() const
PLUGINLIB_EXPORT_CLASS(dataspeed_pds_lcm::PdsNodelet, nodelet::Nodelet)
ros::NodeHandle & getNodeHandle() const
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< PdsNode > node_