2 #include <sensor_msgs/LaserScan.h> 4 int main(
int argc,
char** argv){
5 ros::init(argc, argv,
"laser_scan_publisher");
10 unsigned int num_readings = 100;
11 double laser_frequency = 40;
12 double ranges[num_readings];
13 double intensities[num_readings];
19 for(
unsigned int i = 0; i < num_readings; ++i){
21 intensities[i] = 100 + count;
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);
34 scan.range_max = 100.0;
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];
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)