-
Notifications
You must be signed in to change notification settings - Fork 20
/
pb_talker.cpp
32 lines (26 loc) · 888 Bytes
/
pb_talker.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
#include <ros/protobuffer_traits.h>
#include <ros/serialization_protobuffer.h>
#include "ros/ros.h"
#include "publish_info.pb.h"
int main(int argc, char **argv) {
ros::init(argc, argv, "pb_talker");
ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME,
ros::console::levels::Debug);
ros::NodeHandle n;
ros::Publisher pub =
n.advertise<superbai::sample::PublishInfo>("/Sorbai", 1000);
ros::Rate loop_rate(10);
superbai::sample::PublishInfo proto_msg_info;
proto_msg_info.set_name("sorbai");
proto_msg_info.set_message_type("test_message");
proto_msg_info.set_publish_msg("sorbai is a bilibili up");
int count = 0;
while (ros::ok()) {
pub.publish(proto_msg_info);
std::cerr << "DebugMsg: " << proto_msg_info.DebugString() << std::endl;
ros::spinOnce();
loop_rate.sleep();
++count;
}
return 0;
}