43int main(
int argc,
char** argv)
45 rclcpp::init(argc, argv);
46 auto node = std::make_shared<rclcpp::Node>(
"boring_string_publisher");
49 std::string topic, content_path;
50 node->declare_parameter(
"topic", rclcpp::ParameterType::PARAMETER_STRING);
51 node->get_parameter(
"topic", topic);
52 node->declare_parameter(
"content_path", rclcpp::ParameterType::PARAMETER_STRING);
53 node->get_parameter(
"content_path", content_path);
55 if (content_path.empty())
57 RCLCPP_FATAL(node->get_logger(),
"content_path parameter was not specified or is empty");
62 struct stat statistics;
63 if (stat(content_path.c_str(), &statistics) != 0)
65 RCLCPP_FATAL(node->get_logger(),
"%s does not exist!", content_path.c_str());
70 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr string_publisher =
71 node->create_publisher<std_msgs::msg::String>(topic, rclcpp::QoS(1).transient_local());
74 std::ifstream content_stream(content_path.c_str());
75 std::stringstream buffer;
76 buffer << content_stream.rdbuf();
79 std_msgs::msg::String msg;
80 msg.data = buffer.str();
81 string_publisher->publish(msg);