#!/usr/bin/env pythonimportrclpyfromrclpy.nodeimportNode# import message typefromexample_interfaces.msgimportStringclassRobotNewsStationNode(Node):def__init__(self):super().__init__("robot_news_station")# Create publisher with the proper message typeself.publisher_=self.create_publisher(String,"robot_news",10)# Create timer to triger message at 2Hzself.timer_=self.create_timer(0.5,self.publish_news)self.get_logger().info("Starting the robot news station")defpublish_news(self):# Create massage payloadmsg=String()# Add 'Hello' as the datamsg.data="Hello"# Publish the data payloadself.publisher_.publish(msg)defmain(args=None):rclpy.init(args=args)node=RobotNewsStationNode()rclpy.spin(node)rclpy.shutdown()if__name__=='__main__':main()
#include "rclcpp/rclcpp.hpp"#include "example_interfaces/msg/string.hpp"classRobotNewsStationNode:publicrclcpp::Node{public:RobotNewsStationNode():Node("robot_news_station"){publisher_=this->create_publisher<example_interfaces::msg::String>("robot_news",10);timer_=this->create_wall_timer(std::chrono::milliseconds(500),std::bind(&RobotNewsStationNode::publishNews,this));RCLCPP_INFO(this->get_logger(),"Robot News Station has been started.");}private:voidpublishNews(){automsg=example_interfaces::msg::String();msg.data=std::string("Hi, this is")+robot_name_+std::string(" from the Robot News Station");publisher_->publish(msg);}std::stringrobot_name_;rclcpp::Publisher<example_interfaces::msg::String>::SharedPtrpublisher_;rclcpp::TimerBase::SharedPtrtimer_;};intmain(intargc,char**argv){rclcpp::init(argc,argv);autonode=std::make_shared<RobotNewsStationNode>();rclcpp::spin(node);rclcpp::shutdown();return0;}