node.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 #include <ros/ros.h>
36 #include "PdsNode.h"
37 
38 int main(int argc, char **argv)
39 {
40  ros::init(argc, argv, "pds");
41  ros::NodeHandle node;
42  ros::NodeHandle priv_nh("~");
43 
44  const int ROS_RESPONSE_TIME_MS = 100;
45  const float TRY_CONNECT_EVERY_S = 1.0;
46  const float WARN_EVERY_S = 10.0;
47 
48  std::string lcm_url;
49  priv_nh.getParam("lcm_url", lcm_url);
50  if (lcm_url.empty()) {
51  lcm_url = "udpm://225.0.0.0:7667?ttl=1";
52  }
53 
54  // Initialize LCM
55  lcm::LCM * lcm;
56  while(ros::ok()) {
57  lcm = new lcm::LCM(lcm_url);
58  if(lcm->good()) {
59  break;
60  } else {
61  ROS_WARN_THROTTLE(WARN_EVERY_S,"lcm is not initialized, is the network ready?");
62  delete lcm;
63  }
64  ros::Duration(TRY_CONNECT_EVERY_S).sleep();
65  }
66  ROS_INFO("LCM connected to %s", lcm_url.c_str());
67 
68  // Create PdsNode class
69  dataspeed_pds_lcm::PdsNode n(node, priv_nh, lcm);
70 
71  // Handle ros callbacks asynchronous to lcm
72  ros::AsyncSpinner spinner(1);
73  spinner.start();
74 
75  // TODO: This is a little jenky, lcm handling could get its own thread
76  while(ros::ok()) {
77  lcm->handleTimeout(ROS_RESPONSE_TIME_MS);
78  }
79 
80  return 0;
81 }
82 
#define ROS_WARN_THROTTLE(rate,...)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
Definition: node.cpp:38


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