00001 /* 00002 * Copyright (c) 2016, Ivor Wanders 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions are met: 00006 * * Redistributions of source code must retain the above copyright notice, 00007 * this list of conditions and the following disclaimer. 00008 * * Redistributions in binary form must reproduce the above copyright 00009 * notice, this list of conditions and the following disclaimer in the 00010 * documentation and/or other materials provided with the distribution. 00011 * * Neither the name of the copyright holder nor the names of its 00012 * contributors may be used to endorse or promote products derived from 00013 * this software without specific prior written permission. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #include <ros/ros.h> 00029 #include <socketcan_bridge/topic_to_socketcan.h> 00030 #include <socketcan_interface/threading.h> 00031 #include <socketcan_interface/string.h> 00032 #include <string> 00033 00034 00035 00036 int main(int argc, char *argv[]) 00037 { 00038 ros::init(argc, argv, "topic_to_socketcan_node"); 00039 00040 ros::NodeHandle nh(""), nh_param("~"); 00041 00042 std::string can_device; 00043 nh_param.param<std::string>("can_device", can_device, "can0"); 00044 00045 boost::shared_ptr<can::ThreadedSocketCANInterface> driver = boost::make_shared<can::ThreadedSocketCANInterface> (); 00046 00047 if (!driver->init(can_device, 0)) // initialize device at can_device, 0 for no loopback. 00048 { 00049 ROS_FATAL("Failed to initialize can_device at %s", can_device.c_str()); 00050 return 1; 00051 } 00052 else 00053 { 00054 ROS_INFO("Successfully connected to %s.", can_device.c_str()); 00055 } 00056 00057 socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver); 00058 to_socketcan_bridge.setup(); 00059 00060 ros::spin(); 00061 00062 driver->shutdown(); 00063 driver.reset(); 00064 00065 ros::waitForShutdown(); 00066 }