socketcan_bridge_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>
33 #include <memory>
34 #include <string>
35 
36 
37 int main(int argc, char *argv[])
38 {
39  ros::init(argc, argv, "socketcan_bridge_node");
40 
41  ros::NodeHandle nh(""), nh_param("~");
42 
43  std::string can_device;
44  nh_param.param<std::string>("can_device", can_device, "can0");
45 
46  can::ThreadedSocketCANInterfaceSharedPtr driver = std::make_shared<can::ThreadedSocketCANInterface> ();
47 
48  // initialize device at can_device, 0 for no loopback.
49  if (!driver->init(can_device, 0, XmlRpcSettings::create(nh_param)))
50  {
51  ROS_FATAL("Failed to initialize can_device at %s", can_device.c_str());
52  return 1;
53  }
54  else
55  {
56  ROS_INFO("Successfully connected to %s.", can_device.c_str());
57  }
58 
59  // initialize the bridge both ways.
60  socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver);
61  to_socketcan_bridge.setup();
62 
63  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver);
64  to_topic_bridge.setup(nh_param);
65 
66  ros::spin();
67 
68  driver->shutdown();
69  driver.reset();
70 
72 }
#define ROS_FATAL(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/")
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_INFO(...)
std::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
ROSCPP_DECL void spin()
int main(int argc, char *argv[])
ROSCPP_DECL void waitForShutdown()


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Mon Feb 28 2022 23:28:13