-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathtalker2.cpp
36 lines (36 loc) · 1.08 KB
/
talker2.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
#include <sstream>
// #include "ros/ros.h"
#include "rclcpp/rclcpp.hpp"
// #include "std_msgs/String.h"
#include "std_msgs/msg/string.hpp"
int main(int argc, char **argv)
{
// ros::init(argc, argv, "talker");
// ros::NodeHandle n;
rclcpp::init(argc, argv);
rclcpp::init(argc);
auto node = rclcpp::Node::make_shared("talker");
// ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
// ros::Rate loop_rate(10);
auto chatter_pub = node->create_publisher<std_msgs::msg::String>("chatter", rmw_qos_profile_default);
rclcpp::Rate loop_rate(10);
int count = 0;
// std_msgs::String msg;
auto msg = std::make_shared<std_msgs::msg::String>();
// while (ros::ok())
while (rclcpp::ok())
{
std::stringstream ss;
ss << "hello world " << count++;
// msg.data = ss.str();
msg->data = ss.str();
// ROS_INFO("%s", msg.data.c_str());
RCLCPP_INFO(node->get_logger(), "%s\n", msg->data.c_str());
// chatter_pub.publish(msg);
chatter_pub->publish(msg);
// ros::spinOnce();
rclcpp::spin_some(node);
loop_rate.sleep();
}
return 0;
}