publisher_rate.cpp
Go to the documentation of this file.
1 // Publish big data chunks
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include <ros/publisher.h>
5 #include <ros/init.h>
6 #include <ros/node_handle.h>
7 
8 #include <std_msgs/Int8MultiArray.h>
9 
10 int main(int argc, char** argv)
11 {
12  ros::init(argc, argv, "publisher");
14 
15  const size_t NUM_BYTES = 8;
16  std_msgs::Int8MultiArray data;
17  data.data.reserve(NUM_BYTES);
18 
19  assert(argc > 1);
20  float frequency = atof(argv[1]);
21 
22  ros::Publisher pub = n.advertise<std_msgs::Int8MultiArray>("data", 1);
23  ros::Rate rate(frequency);
24 
25  size_t start = 0;
26  while(ros::ok())
27  {
28  data.data.clear();
29  for(size_t i = 0; i < NUM_BYTES; ++i)
30  {
31  data.data.push_back(start + i);
32  }
33  pub.publish(data);
34  rate.sleep();
35  start++;
36  }
37  return 0;
38 }
ROSCPP_DECL void start()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
dictionary NUM_BYTES


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:01