Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <iostream>
00030 #include <boost/bind.hpp>
00031 #include <boost/thread.hpp>
00032 #include <boost/foreach.hpp>
00033
00034 #include <ros/ros.h>
00035 #include <random_numbers/random_numbers.h>
00036 #include <sensor_msgs/LaserScan.h>
00037 #include <geometry_msgs/Twist.h>
00038
00039 using namespace std;
00040
00041 #define foreach BOOST_FOREACH
00042
00043 void publishRandomLaserScan(ros::Publisher& laserScanPublisher) {
00044 static random_numbers::RandomNumberGenerator randomizer;
00045 sensor_msgs::LaserScan scan;
00046 scan.angle_min = 0;
00047 scan.angle_increment = 0.05;
00048 scan.header.frame_id = "/map";
00049 scan.header.stamp = ros::Time::now();
00050 scan.range_min = 0.001;
00051 scan.range_max = 30;
00052
00053 static double first = randomizer.uniformReal(0.1, 1.5);
00054
00055 for (int i = 0; i < 50; ++i) {
00056 first += randomizer.gaussian(0, 0.03);
00057 first = fmin(1.5, fmax(0.1, first));
00058 scan.ranges.push_back(first);
00059 }
00060
00061 laserScanPublisher.publish(scan);
00062 }
00063
00064 int main(int argc, char **argv) {
00065 ros::init(argc, argv, "fsm_wandering_events");
00066 ros::Publisher laserScanPublisher = ros::NodeHandle().advertise<sensor_msgs::LaserScan>("/fsm_wandering/scan", 1, false);
00067
00068 ROS_INFO("Starting wandering events publisher...");
00069
00070 while (ros::ok()) {
00071 publishRandomLaserScan(laserScanPublisher);
00072 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00073 }
00074 return 0;
00075 }