hz.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017-2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // ROS and messages
36 #include <ros/ros.h>
37 
38 // LCM and messages
39 #include <lcm/lcm-cpp.hpp>
40 #include <dataspeed_pds_lcm/status_t.hpp>
41 using namespace dataspeed_pds_lcm;
42 
43 // LCM handle
44 lcm::LCM * g_lcm = NULL;
45 
46 void timerCallback(const ros::TimerEvent&, int id)
47 {
48  ROS_ASSERT((0 <= id) && (id <= 3));
49  status_t msg;
50  memset(&msg, 0x00, sizeof(msg));
51  msg.unit_id = id;
52  g_lcm->publish("STATUS", &msg);
53 }
54 
55 int main(int argc, char **argv)
56 {
57  ros::init(argc, argv, "sim");
58  ros::NodeHandle nh;
59  ros::NodeHandle nh_priv("~");
60 
61  // Configurable period
62  double hz = 50; // 50 Hz
63  nh_priv.getParam("hz", hz);
64 
65  // Multiple units (optional)
66  int unit_id = 0;
67  nh_priv.getParam("unit_id", unit_id);
68  if (unit_id < 0) {
69  unit_id = 0;
70  } else if (unit_id > 3) {
71  unit_id = 3;
72  }
73 
74  // LCM URL
75  std::string lcm_url;
76  nh_priv.getParam("lcm_url", lcm_url);
77  if (lcm_url.empty()) {
78  lcm_url = "udpm://225.0.0.0:7667?ttl=0";
79  }
80 
81  // Initialize LCM
82  lcm::LCM * lcm;
83  while(ros::ok()) {
84  lcm = new lcm::LCM(lcm_url);
85  if(lcm->good()) {
86  break;
87  } else {
88  ROS_WARN_THROTTLE(10.0,"lcm is not initialized, is the network ready?");
89  delete lcm;
90  }
91  ros::Duration(1.0).sleep();
92  }
93  ROS_INFO("LCM connected to %s", lcm_url.c_str());
94 
95  // Hold onto the LCM handle
96  g_lcm = lcm;
97 
98  // Setup Timers
99  std::vector<ros::Timer> timers;
100  for (int i = 0; i <= unit_id; i++) {
101  timers.push_back(nh.createTimer(ros::Duration(1.0 / hz), boost::bind(&timerCallback, _1, i)));
102  }
103 
104  // Handle callbacks until shutdown
105  ros::spin();
106 
107  return 0;
108 }
109 
#define ROS_WARN_THROTTLE(rate,...)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: hz.cpp:55
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
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
lcm::LCM * g_lcm
Definition: hz.cpp:44
#define ROS_ASSERT(cond)
void timerCallback(const ros::TimerEvent &, int id)
Definition: hz.cpp:46


dataspeed_pds_lcm
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Sat Jul 11 2020 03:09:53