dummy_scan_producer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Vijay Pradeep */
36 
41 #include <boost/thread.hpp>
42 #include <ros/ros.h>
44 #include <sensor_msgs/LaserScan.h>
45 
46 void runLoop()
47 {
48  ros::NodeHandle nh;
49 
50  ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("dummy_scan", 100);
51  ros::Rate loop_rate(5);
52 
53  // Configure the Transform broadcaster
54  tf::TransformBroadcaster broadcaster;
55  tf::Transform laser_transform(tf::Quaternion(0,0,0,1));
56 
57  // Populate the dummy laser scan
58  sensor_msgs::LaserScan scan;
59  scan.header.frame_id = "/dummy_laser_link";
60  scan.angle_min = 0.0;
61  scan.angle_max = 99.0;
62  scan.angle_increment = 1.0;
63  scan.time_increment = .001;
64  scan.scan_time = .05;
65  scan.range_min = .01;
66  scan.range_max = 100.0;
67 
68  const unsigned int N = 100;
69  scan.ranges.resize(N);
70  scan.intensities.resize(N);
71 
72  for (unsigned int i=0; i<N; i++)
73  {
74  scan.ranges[i] = 10.0;
75  scan.intensities[i] = 10.0;
76  }
77 
78  // Keep sending scans until the assembler is done
79  while (nh.ok())
80  {
81  scan.header.stamp = ros::Time::now();
82  scan_pub.publish(scan);
83  broadcaster.sendTransform(tf::StampedTransform(laser_transform, scan.header.stamp, "dummy_laser_link", "dummy_base_link"));
84  loop_rate.sleep();
85  ROS_INFO("Publishing scan");
86  }
87 }
88 
89 int main(int argc, char** argv)
90 {
91  ros::init(argc, argv, "scan_producer");
92  ros::NodeHandle nh;
93  boost::thread run_thread(&runLoop);
94  ros::spin();
95  run_thread.join();
96  return 0;
97 }
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)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
void sendTransform(const StampedTransform &transform)
void runLoop()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
bool ok() const
int main(int argc, char **argv)


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Thu Jun 27 2019 19:56:21