test_scan.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <sensor_msgs/LaserScan.h>
3 
4 int main(int argc, char** argv){
5  ros::init(argc, argv, "laser_scan_publisher");
6 
8  ros::Publisher scan_pub = n.advertise<sensor_msgs::LaserScan>("scan", 50); //这是要传递的信息。
9 
10  unsigned int num_readings = 100;
11  double laser_frequency = 40;
12  double ranges[num_readings];
13  double intensities[num_readings]; // 准备创建虚拟的激光信息,这分别是平率,不太懂。。。
14 
15  int count = 0;
16  ros::Rate r(1.0); //发送数据的速率
17  while(n.ok()){
18  //generate some fake data for our laser scan
19  for(unsigned int i = 0; i < num_readings; ++i){
20  ranges[i] = count;
21  intensities[i] = 100 + count;
22  }
23  ros::Time scan_time = ros::Time::now(); //每隔一秒产生一个虚假的数据
24 
25  //populate the LaserScan message
26  sensor_msgs::LaserScan scan;
27  scan.header.stamp = scan_time;
28  scan.header.frame_id = "laser_frame";
29  scan.angle_min = -1.57;
30  scan.angle_max = 1.57;
31  scan.angle_increment = 3.14 / num_readings;
32  scan.time_increment = (1 / laser_frequency) / (num_readings);
33  scan.range_min = 0.0;
34  scan.range_max = 100.0; //这些是消息内容。与前一节交相辉映
35 
36  scan.ranges.resize(num_readings);
37  scan.intensities.resize(num_readings);
38  for(unsigned int i = 0; i < num_readings; ++i){
39  scan.ranges[i] = ranges[i];
40  scan.intensities[i] = intensities[i];
41  }
42 
43  scan_pub.publish(scan);
44  ++count;
45  r.sleep();
46  }
47 }
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: test_scan.cpp:4
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
static Time now()
bool ok() const


cht10_node
Author(s): Carl <1271087623@qq.comd>
autogenerated on Mon Jun 10 2019 12:48:57