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
00030
00031
00032
00033
00034
00035
00036
00041 #include <boost/thread.hpp>
00042 #include <ros/ros.h>
00043 #include <tf/transform_broadcaster.h>
00044 #include <sensor_msgs/LaserScan.h>
00045 #include <pr2_msgs/LaserScannerSignal.h>
00046
00047
00048 void runLoop()
00049 {
00050 ros::NodeHandle nh;
00051
00052 ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("dummy_scan", 100);
00053 ros::Publisher signal_pub = nh.advertise<pr2_msgs::LaserScannerSignal>("dummy_signal", 100);
00054 ros::Rate loop_rate(20);
00055
00056
00057 tf::TransformBroadcaster broadcaster;
00058 tf::Transform laser_transform(btQuaternion(0,0,0,1));
00059
00060
00061 sensor_msgs::LaserScan scan;
00062 scan.header.frame_id = "dummy_laser_link";
00063 scan.angle_min = 0.0;
00064 scan.angle_max = 99.0;
00065 scan.angle_increment = 1.0;
00066 scan.time_increment = .001;
00067 scan.scan_time = .05;
00068 scan.range_min = .01;
00069 scan.range_max = 100.0;
00070
00071 const unsigned int N = 100;
00072 scan.ranges.resize(N);
00073 scan.intensities.resize(N);
00074
00075 for (unsigned int i=0; i<N; i++)
00076 {
00077 scan.ranges[i] = 10.0;
00078 scan.intensities[i] = 10.0;
00079 }
00080
00081 unsigned int cloud_count = 0;
00082
00083
00084 pr2_msgs::LaserScannerSignal signal;
00085 signal.header.stamp = scan.header.stamp;
00086 signal.signal = 1;
00087 signal_pub.publish(signal);
00088
00089
00090
00091 while (nh.ok())
00092 {
00093 unsigned int scan_count = 0;
00094
00095 while (nh.ok() & scan_count < 10)
00096 {
00097 scan.header.stamp = ros::Time::now();
00098 scan_pub.publish(scan);
00099 broadcaster.sendTransform(tf::StampedTransform(laser_transform, scan.header.stamp, "dummy_laser_link", "dummy_base_link"));
00100 scan_count++;
00101 loop_rate.sleep();
00102 }
00103
00104 signal.header.stamp = scan.header.stamp;
00105 signal.signal = cloud_count % 2;
00106 signal_pub.publish(signal);
00107
00108 ROS_INFO("Done publishing cloud [%u]", cloud_count);
00109 cloud_count++;
00110 }
00111 }
00112
00113 int main(int argc, char** argv)
00114 {
00115 ros::init(argc, argv, "scan_producer");
00116 ros::NodeHandle nh;
00117 boost::thread run_thread(&runLoop);
00118 ros::spin();
00119 run_thread.join();
00120 return 0;
00121 }