38 #include <sensor_msgs/LaserScan.h> 40 int main(
int argc,
char** argv){
41 ros::init(argc, argv,
"laser_scan_publisher");
46 unsigned int num_readings = 100;
47 double laser_frequency = 40;
48 double ranges[num_readings];
49 double intensities[num_readings];
55 for(
unsigned int i = 0; i < num_readings; ++i){
57 intensities[i] = 100 + count;
62 sensor_msgs::LaserScan scan;
63 scan.header.stamp = scan_time;
64 scan.header.frame_id =
"laser_frame";
65 scan.angle_min = -1.57;
66 scan.angle_max = 1.57;
67 scan.angle_increment = 3.14 / num_readings;
68 scan.time_increment = (1 / laser_frequency) / (num_readings);
70 scan.range_max = 100.0;
72 scan.ranges.resize(num_readings);
73 scan.intensities.resize(num_readings);
74 for(
unsigned int i = 0; i < num_readings; ++i){
75 scan.ranges[i] = ranges[i];
76 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)