src
socketcan_to_topic_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
>
29
#include <
socketcan_bridge/socketcan_to_topic.h
>
30
#include <
socketcan_interface/threading.h
>
31
#include <
socketcan_interface/string.h
>
32
#include <
socketcan_interface/xmlrpc_settings.h
>
33
#include <memory>
34
#include <string>
35
36
37
38
int
main
(
int
argc,
char
*argv[])
39
{
40
ros::init
(argc, argv,
"socketcan_to_topic_node"
);
41
42
ros::NodeHandle
nh(
""
), nh_param(
"~"
);
43
44
std::string can_device;
45
nh_param.
param
<std::string>(
"can_device"
, can_device,
"can0"
);
46
47
can::ThreadedSocketCANInterfaceSharedPtr
driver = std::make_shared<can::ThreadedSocketCANInterface> ();
48
49
// initialize device at can_device, 0 for no loopback.
50
if
(!driver->init(can_device, 0,
XmlRpcSettings::create
(nh_param)))
51
{
52
ROS_FATAL
(
"Failed to initialize can_device at %s"
, can_device.c_str());
53
return
1;
54
}
55
else
56
{
57
ROS_INFO
(
"Successfully connected to %s."
, can_device.c_str());
58
}
59
60
socketcan_bridge::SocketCANToTopic
to_topic_bridge(&nh, &nh_param, driver);
61
to_topic_bridge.
setup
(nh_param);
62
63
ros::spin
();
64
65
driver->shutdown();
66
driver.reset();
67
68
ros::waitForShutdown
();
69
}
socketcan_to_topic.h
threading.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
can::ThreadedSocketCANInterfaceSharedPtr
std::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
XmlRpcSettings::create
static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/")
ROS_FATAL
#define ROS_FATAL(...)
string.h
socketcan_bridge::SocketCANToTopic::setup
void setup()
Definition:
socketcan_to_topic.cpp:60
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
ros::NodeHandle::param
T param(const std::string ¶m_name, const T &default_val) const
xmlrpc_settings.h
ros::spin
ROSCPP_DECL void spin()
main
int main(int argc, char *argv[])
Definition:
socketcan_to_topic_node.cpp:38
socketcan_bridge::SocketCANToTopic
Definition:
socketcan_to_topic.h:38
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33