Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037
00038
00039 #include <lcm/lcm-cpp.hpp>
00040 #include <dataspeed_pds_lcm/status_t.hpp>
00041 using namespace dataspeed_pds_lcm;
00042
00043
00044 lcm::LCM * g_lcm = NULL;
00045
00046 void timerCallback(const ros::TimerEvent&, int id)
00047 {
00048 ROS_ASSERT((0 <= id) && (id <= 3));
00049 status_t msg;
00050 memset(&msg, 0x00, sizeof(msg));
00051 msg.unit_id = id;
00052 g_lcm->publish("STATUS", &msg);
00053 }
00054
00055 int main(int argc, char **argv)
00056 {
00057 ros::init(argc, argv, "sim");
00058 ros::NodeHandle nh;
00059 ros::NodeHandle nh_priv("~");
00060
00061
00062 double hz = 50;
00063 nh_priv.getParam("hz", hz);
00064
00065
00066 int unit_id = 0;
00067 nh_priv.getParam("unit_id", unit_id);
00068 if (unit_id < 0) {
00069 unit_id = 0;
00070 } else if (unit_id > 3) {
00071 unit_id = 3;
00072 }
00073
00074
00075 std::string lcm_url;
00076 nh_priv.getParam("lcm_url", lcm_url);
00077 if (lcm_url.empty()) {
00078 lcm_url = "udpm://225.0.0.0:7667?ttl=0";
00079 }
00080
00081
00082 lcm::LCM * lcm;
00083 while(ros::ok()) {
00084 lcm = new lcm::LCM(lcm_url);
00085 if(lcm->good()) {
00086 break;
00087 } else {
00088 ROS_WARN_THROTTLE(10.0,"lcm is not initialized, is the network ready?");
00089 delete lcm;
00090 }
00091 ros::Duration(1.0).sleep();
00092 }
00093 ROS_INFO("LCM connected to %s", lcm_url.c_str());
00094
00095
00096 g_lcm = lcm;
00097
00098
00099 std::vector<ros::Timer> timers;
00100 for (int i = 0; i <= unit_id; i++) {
00101 timers.push_back(nh.createTimer(ros::Duration(1.0 / hz), boost::bind(&timerCallback, _1, i)));
00102 }
00103
00104
00105 ros::spin();
00106
00107 return 0;
00108 }
00109