dense_laser_snapshotter.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 #include "ros/ros.h"
36 
38 
39 // Messages
40 #include "sensor_msgs/LaserScan.h"
41 #include "calibration_msgs/DenseLaserSnapshot.h"
42 #include "pr2_msgs/LaserScannerSignal.h"
43 
44 using namespace dense_laser_assembler ;
45 
50 {
51 
52 public:
53 
55  {
56  assembler_.setCacheSize(40*20);
57  prev_signal_.header.stamp = ros::Time(0, 0);
58  signal_sub_ = n_.subscribe("laser_tilt_controller/laser_scanner_signal", 2, &DenseLaserSnapshotter::scannerSignalCallback, this);
59  scan_sub_ = n_.subscribe("scan", 1, &DenseLaserSnapshotter::scanCallback, this);
60  snapshot_pub_ = n_.advertise<calibration_msgs::DenseLaserSnapshot> ("dense_laser_snapshot", 1);
61  first_time_ = true;
62  }
63 
65  {
66 
67  }
68 
69  void scanCallback(const sensor_msgs::LaserScanConstPtr& scan)
70  {
71  assembler_.add(scan);
72  }
73 
74  void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& cur_signal)
75  {
76  ROS_DEBUG("Got Scanner Signal") ;
77 
78  if (first_time_)
79  {
80  prev_signal_ = *cur_signal ;
81  first_time_ = false ;
82  }
83  else
84  {
85  if (cur_signal->signal == 1)
86  {
87  ROS_DEBUG("About to make request");
88 
89  ros::Time start = prev_signal_.header.stamp;
90  ros::Time end = cur_signal->header.stamp;
91 
92  calibration_msgs::DenseLaserSnapshot snapshot;
93 
94  assembler_.assembleSnapshot(start, end, snapshot);
95 
96  ROS_DEBUG("header.stamp: %f", snapshot.header.stamp.toSec());
97  ROS_DEBUG("header.frame_id: %s", snapshot.header.frame_id.c_str());
98  ROS_DEBUG("ranges.size()=%lu", snapshot.ranges.size());
99  ROS_DEBUG("intensities.size()=%lu", snapshot.intensities.size());
100  ROS_DEBUG("scan_start.size()=%lu", snapshot.scan_start.size());
101  snapshot_pub_.publish(snapshot);
102  }
103  else
104  ROS_DEBUG("Not making request");
105  prev_signal_ = *cur_signal;
106  }
107  }
108 
109 private:
115  pr2_msgs::LaserScannerSignal prev_signal_;
116 
117  bool first_time_ ;
118 };
119 
120 int main(int argc, char **argv)
121 {
122  ros::init(argc, argv, "dense_laser_snapshotter") ;
123  DenseLaserSnapshotter snapshotter ;
124  ros::spin() ;
125 
126  return 0;
127 }
int main(int argc, char **argv)
ROSCPP_DECL void start()
Builds a DenseLaserSnapshot message from laser scans collected in a specified time interval...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
pr2_msgs::LaserScannerSignal prev_signal_
ROSCPP_DECL void spin()
void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr &cur_signal)
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)
#define ROS_DEBUG(...)


pr2_dense_laser_snapshotter
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:57