Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <socketcan_bridge/socketcan_to_topic.h>
00029 #include <socketcan_interface/string.h>
00030 #include <can_msgs/Frame.h>
00031 #include <string>
00032
00033 namespace socketcan_bridge
00034 {
00035 SocketCANToTopic::SocketCANToTopic(ros::NodeHandle* nh, ros::NodeHandle* nh_param,
00036 boost::shared_ptr<can::DriverInterface> driver)
00037 {
00038 can_topic_ = nh->advertise<can_msgs::Frame>("received_messages", 10);
00039 driver_ = driver;
00040 };
00041
00042 void SocketCANToTopic::setup()
00043 {
00044
00045 frame_listener_ = driver_->createMsgListener(
00046 can::CommInterface::FrameDelegate(this, &SocketCANToTopic::frameCallback));
00047
00048 state_listener_ = driver_->createStateListener(
00049 can::StateInterface::StateDelegate(this, &SocketCANToTopic::stateCallback));
00050 };
00051
00052 void SocketCANToTopic::frameCallback(const can::Frame& f)
00053 {
00054
00055 can::Frame frame = f;
00056 if (!frame.isValid())
00057 {
00058 ROS_ERROR("Invalid frame from SocketCAN: id: %#04x, length: %d, is_extended: %d, is_error: %d, is_rtr: %d",
00059 f.id, f.dlc, f.is_extended, f.is_error, f.is_rtr);
00060 return;
00061 }
00062 else
00063 {
00064 if (f.is_error)
00065 {
00066
00067
00068 ROS_WARN("Received frame is error: %s", can::tostring(f, true).c_str());
00069 }
00070 }
00071
00072 can_msgs::Frame msg;
00073
00074 convertSocketCANToMessage(frame, msg);
00075
00076 msg.header.frame_id = "";
00077 msg.header.stamp = ros::Time::now();
00078
00079 can_topic_.publish(msg);
00080 };
00081
00082
00083 void SocketCANToTopic::stateCallback(const can::State & s)
00084 {
00085 std::string err;
00086 driver_->translateError(s.internal_error, err);
00087 if (!s.internal_error)
00088 {
00089 ROS_INFO("State: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
00090 }
00091 else
00092 {
00093 ROS_ERROR("Error: %s, asio: %s", err.c_str(), s.error_code.message().c_str());
00094 }
00095 };
00096 };