topic_to_socketcan_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016, Ivor Wanders
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the name of the copyright holder nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include <ros/ros.h>
32 #include <string>
33 
34 
35 
36 int main(int argc, char *argv[])
37 {
38  ros::init(argc, argv, "topic_to_socketcan_node");
39 
40  ros::NodeHandle nh(""), nh_param("~");
41 
42  std::string can_device;
43  nh_param.param<std::string>("can_device", can_device, "can0");
44 
45  can::ThreadedSocketCANInterfaceSharedPtr driver = boost::make_shared<can::ThreadedSocketCANInterface> ();
46 
47  if (!driver->init(can_device, 0)) // initialize device at can_device, 0 for no loopback.
48  {
49  ROS_FATAL("Failed to initialize can_device at %s", can_device.c_str());
50  return 1;
51  }
52  else
53  {
54  ROS_INFO("Successfully connected to %s.", can_device.c_str());
55  }
56 
57  socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver);
58  to_socketcan_bridge.setup();
59 
60  ros::spin();
61 
62  driver->shutdown();
63  driver.reset();
64 
66 }
#define ROS_FATAL(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL void spin()
int main(int argc, char *argv[])
ROSCPP_DECL void waitForShutdown()


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Sat May 4 2019 02:40:49