topic_to_socketcan.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 <string>
31 
32 namespace socketcan_bridge
33 {
36  {
37  can_topic_ = nh->subscribe<can_msgs::Frame>("sent_messages", 10,
38  boost::bind(&TopicToSocketCAN::msgCallback, this, _1));
39  driver_ = driver;
40  };
41 
43  {
44  state_listener_ = driver_->createStateListener(
46  };
47 
48  void TopicToSocketCAN::msgCallback(const can_msgs::Frame::ConstPtr& msg)
49  {
50  // ROS_DEBUG("Message came from sent_messages topic");
51 
52  // translate it to the socketcan frame type.
53 
54  can_msgs::Frame m = *msg.get(); // ROS message
55  can::Frame f; // socketcan type
56 
57  // converts the can_msgs::Frame (ROS msg) to can::Frame (socketcan.h)
59 
60  if (!f.isValid()) // check if the id and flags are appropriate.
61  {
62  // ROS_WARN("Refusing to send invalid frame: %s.", can::tostring(f, true).c_str());
63  // can::tostring cannot be used for dlc > 8 frames. It causes an crash
64  // due to usage of boost::array for the data array. The should always work.
65  ROS_ERROR("Invalid frame from topic: id: %#04x, length: %d, is_extended: %d", m.id, m.dlc, m.is_extended);
66  return;
67  }
68 
69  bool res = driver_->send(f);
70  if (!res)
71  {
72  ROS_ERROR("Failed to send message: %s.", can::tostring(f, true).c_str());
73  }
74  };
75 
76 
77 
79  {
80  std::string err;
81  driver_->translateError(s.internal_error, err);
82  if (!s.internal_error)
83  {
84  ROS_INFO("State: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
85  }
86  else
87  {
88  ROS_ERROR("Error: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
89  }
90  };
91 }; // namespace socketcan_bridge
can::StateListenerConstSharedPtr state_listener_
std::string tostring(const Header &h, bool lc)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
can::DriverInterfaceSharedPtr driver_
TopicToSocketCAN(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
#define ROS_INFO(...)
void stateCallback(const can::State &s)
bool isValid() const
unsigned int internal_error
void msgCallback(const can_msgs::Frame::ConstPtr &msg)
#define ROS_ERROR(...)
boost::system::error_code error_code


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