socketcan_to_topic.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 
30 #include <can_msgs/Frame.h>
31 #include <string>
32 
33 namespace can
34 {
36 {
37  XmlRpc::XmlRpcValue t(ct);
38  try // try to read as integer
39  {
40  uint32_t id = static_cast<int>(t);
41  return tofilter(id);
42  }
43  catch(...) // else read as string
44  {
45  return tofilter(static_cast<std::string>(t));
46  }
47 }
48 } // namespace can
49 
50 namespace socketcan_bridge
51 {
54  {
55  can_topic_ = nh->advertise<can_msgs::Frame>("received_messages",
56  nh_param->param("received_messages_queue_size", 10));
57  driver_ = driver;
58  };
59 
61  {
62  // register handler for frames and state changes.
63  frame_listener_ = driver_->createMsgListenerM(this, &SocketCANToTopic::frameCallback);
64  state_listener_ = driver_->createStateListenerM(this, &SocketCANToTopic::stateCallback);
65  };
66 
68  {
71  this,
72  std::placeholders::_1),
73  filters));
74 
75  state_listener_ = driver_->createStateListenerM(this, &SocketCANToTopic::stateCallback);
76  }
77 
79  {
80  setup(can::tofilters(filters));
81  }
83  {
84  XmlRpc::XmlRpcValue filters;
85  if (nh.getParam("can_ids", filters)) return setup(filters);
86  return setup();
87  }
88 
89 
91  {
92  // ROS_DEBUG("Message came in: %s", can::tostring(f, true).c_str());
93  if (!f.isValid())
94  {
95  ROS_ERROR("Invalid frame from SocketCAN: id: %#04x, length: %d, is_extended: %d, is_error: %d, is_rtr: %d",
96  f.id, f.dlc, f.is_extended, f.is_error, f.is_rtr);
97  return;
98  }
99  else
100  {
101  if (f.is_error)
102  {
103  // can::tostring cannot be used for dlc > 8 frames. It causes an crash
104  // due to usage of boost::array for the data array. The should always work.
105  ROS_WARN("Received frame is error: %s", can::tostring(f, true).c_str());
106  }
107  }
108 
109  can_msgs::Frame msg;
110  // converts the can::Frame (socketcan.h) to can_msgs::Frame (ROS msg)
112 
113  msg.header.frame_id = ""; // empty frame is the de-facto standard for no frame.
114  msg.header.stamp = ros::Time::now();
115 
116  can_topic_.publish(msg);
117  };
118 
119 
121  {
122  std::string err;
123  driver_->translateError(s.internal_error, err);
124  if (!s.internal_error)
125  {
126  ROS_INFO("State: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
127  }
128  else
129  {
130  ROS_ERROR("Error: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
131  }
132  };
133 }; // namespace socketcan_bridge
socketcan_to_topic.h
can::tofilters
FilteredFrameListener::FilterVector tofilters(const T &v)
can::Frame
can::FilteredFrameListener
s
XmlRpcServer s
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
socketcan_bridge::SocketCANToTopic::SocketCANToTopic
SocketCANToTopic(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
Definition: socketcan_to_topic.cpp:52
socketcan_bridge::SocketCANToTopic::frameCallback
void frameCallback(const can::Frame &f)
Definition: socketcan_to_topic.cpp:90
socketcan_bridge::SocketCANToTopic::stateCallback
void stateCallback(const can::State &s)
Definition: socketcan_to_topic.cpp:120
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
can::DriverInterfaceSharedPtr
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
socketcan_bridge
Definition: socketcan_to_topic.h:36
f
f
can::FilteredFrameListener::FilterVector
std::vector< FrameFilterSharedPtr > FilterVector
can::tostring
std::string tostring(const Frame &f, bool lc)
socketcan_bridge::SocketCANToTopic::state_listener_
can::StateListenerConstSharedPtr state_listener_
Definition: socketcan_to_topic.h:52
socketcan_bridge::SocketCANToTopic::frame_listener_
can::FrameListenerConstSharedPtr frame_listener_
Definition: socketcan_to_topic.h:51
socketcan_bridge::SocketCANToTopic::driver_
can::DriverInterfaceSharedPtr driver_
Definition: socketcan_to_topic.h:49
ROS_WARN
#define ROS_WARN(...)
socketcan_bridge::SocketCANToTopic::can_topic_
ros::Publisher can_topic_
Definition: socketcan_to_topic.h:48
can
can::tofilter
FrameFilterSharedPtr tofilter(const char *s)
can::FrameFilterSharedPtr
std::shared_ptr< FrameFilter > FrameFilterSharedPtr
string.h
socketcan_bridge::SocketCANToTopic::setup
void setup()
Definition: socketcan_to_topic.cpp:60
socketcan_bridge::convertSocketCANToMessage
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
Definition: socketcan_to_topic.h:59
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
can::State
ROS_INFO
#define ROS_INFO(...)
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Time::now
static Time now()


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33