39 #include <lcm/lcm-cpp.hpp> 40 #include <dataspeed_pds_lcm/status_t.hpp> 50 memset(&msg, 0x00,
sizeof(msg));
52 g_lcm->publish(
"STATUS", &msg);
55 int main(
int argc,
char **argv)
67 nh_priv.
getParam(
"unit_id", unit_id);
70 }
else if (unit_id > 3) {
76 nh_priv.
getParam(
"lcm_url", lcm_url);
77 if (lcm_url.empty()) {
78 lcm_url =
"udpm://225.0.0.0:7667?ttl=0";
84 lcm =
new lcm::LCM(lcm_url);
93 ROS_INFO(
"LCM connected to %s", lcm_url.c_str());
99 std::vector<ros::Timer> timers;
100 for (
int i = 0; i <= unit_id; i++) {
#define ROS_WARN_THROTTLE(rate,...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
bool getParam(const std::string &key, std::string &s) const
void timerCallback(const ros::TimerEvent &, int id)