Go to the documentation of this file.
30 #include <can_msgs/Frame.h>
40 uint32_t
id =
static_cast<int>(t);
45 return tofilter(
static_cast<std::string
>(t));
56 nh_param->
param(
"received_messages_queue_size", 10));
72 std::placeholders::_1),
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);
113 msg.header.frame_id =
"";
123 driver_->translateError(
s.internal_error, err);
124 if (!
s.internal_error)
126 ROS_INFO(
"State: %s, asio: %s", err.c_str(),
s.error_code.message().c_str());
130 ROS_ERROR(
"Error: %s, asio: %s", err.c_str(),
s.error_code.message().c_str());
FilteredFrameListener::FilterVector tofilters(const T &v)
bool getParam(const std::string &key, bool &b) const
SocketCANToTopic(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void frameCallback(const can::Frame &f)
void stateCallback(const can::State &s)
void publish(const boost::shared_ptr< M > &message) const
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
Publisher advertise(AdvertiseOptions &ops)
std::vector< FrameFilterSharedPtr > FilterVector
std::string tostring(const Frame &f, bool lc)
can::StateListenerConstSharedPtr state_listener_
can::FrameListenerConstSharedPtr frame_listener_
can::DriverInterfaceSharedPtr driver_
ros::Publisher can_topic_
FrameFilterSharedPtr tofilter(const char *s)
std::shared_ptr< FrameFilter > FrameFilterSharedPtr
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
T param(const std::string ¶m_name, const T &default_val) const
socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33