00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2017-2018, Dataspeed Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Dataspeed Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include <ros/ros.h> 00036 #include "PdsNode.h" 00037 00038 int main(int argc, char **argv) 00039 { 00040 ros::init(argc, argv, "pds"); 00041 ros::NodeHandle node; 00042 ros::NodeHandle priv_nh("~"); 00043 00044 const int ROS_RESPONSE_TIME_MS = 100; 00045 const float TRY_CONNECT_EVERY_S = 1.0; 00046 const float WARN_EVERY_S = 10.0; 00047 00048 std::string lcm_url; 00049 priv_nh.getParam("lcm_url", lcm_url); 00050 if (lcm_url.empty()) { 00051 lcm_url = "udpm://225.0.0.0:7667?ttl=1"; 00052 } 00053 00054 // Initialize LCM 00055 lcm::LCM * lcm; 00056 while(ros::ok()) { 00057 lcm = new lcm::LCM(lcm_url); 00058 if(lcm->good()) { 00059 break; 00060 } else { 00061 ROS_WARN_THROTTLE(WARN_EVERY_S,"lcm is not initialized, is the network ready?"); 00062 delete lcm; 00063 } 00064 ros::Duration(TRY_CONNECT_EVERY_S).sleep(); 00065 } 00066 ROS_INFO("LCM connected to %s", lcm_url.c_str()); 00067 00068 // Create PdsNode class 00069 dataspeed_pds_lcm::PdsNode n(node, priv_nh, lcm); 00070 00071 // Handle ros callbacks asynchronous to lcm 00072 ros::AsyncSpinner spinner(1); 00073 spinner.start(); 00074 00075 // TODO: This is a little jenky, lcm handling could get its own thread 00076 while(ros::ok()) { 00077 lcm->handleTimeout(ROS_RESPONSE_TIME_MS); 00078 } 00079 00080 return 0; 00081 } 00082