37 int main(
int argc,
char *argv[])
39 ros::init(argc, argv,
"socketcan_bridge_node");
43 std::string can_device;
44 nh_param.
param<std::string>(
"can_device", can_device,
"can0");
51 ROS_FATAL(
"Failed to initialize can_device at %s", can_device.c_str());
56 ROS_INFO(
"Successfully connected to %s.", can_device.c_str());
61 to_socketcan_bridge.setup();
64 to_topic_bridge.
setup(nh_param);
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/")
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
int main(int argc, char *argv[])
ROSCPP_DECL void waitForShutdown()