Go to the documentation of this file.
54 can_msgs::Frame m = *msg.get();
65 ROS_ERROR(
"Invalid frame from topic: id: %#04x, length: %d, is_extended: %d", m.id, m.dlc, m.is_extended);
81 driver_->translateError(
s.internal_error, err);
82 if (!
s.internal_error)
84 ROS_INFO(
"State: %s, asio: %s", err.c_str(),
s.error_code.message().c_str());
88 ROS_ERROR(
"Error: %s, asio: %s", err.c_str(),
s.error_code.message().c_str());
can::StateListenerConstSharedPtr state_listener_
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
can::DriverInterfaceSharedPtr driver_
std::string tostring(const Frame &f, bool lc)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber can_topic_
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
void stateCallback(const can::State &s)
T param(const std::string ¶m_name, const T &default_val) const
TopicToSocketCAN(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void msgCallback(const can_msgs::Frame::ConstPtr &msg)
socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33