dense_laser_imager.cpp
Go to the documentation of this file.
1 
2 /*********************************************************************
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
40 #include <ros/ros.h>
41 #include "sensor_msgs/Image.h"
42 #include "calibration_msgs/DenseLaserSnapshot.h"
43 
44 using namespace std ;
45 using namespace ros ;
46 
47 
52 {
53 public:
54 
56  {
57  sub_ = n_.subscribe("dense_laser_snapshot", 1, &LaserImager::snapshotCallback, this) ;
58  intensity_pub_ = n_.advertise<sensor_msgs::Image> ("dense_laser_intensity", 1) ;
59  range_pub_ = n_.advertise<sensor_msgs::Image> ("dense_laser_intensity", 1) ;
60 
61  }
62 
63  void snapshotCallback(const calibration_msgs::DenseLaserSnapshotConstPtr& msg)
64  {
65  sensor_msgs::Image image ;
66  const unsigned int N = msg->num_scans * msg->readings_per_scan ;
67 
68 
69  image.header.stamp = msg->header.stamp ;
70  image.encoding = "mono8" ;
71  image.height = msg->num_scans;
72  image.width = msg->readings_per_scan;
73  image.step = msg->readings_per_scan;
74 
75  image.data.resize(msg->num_scans*msg->readings_per_scan) ;
76 
77  for(unsigned int i=0; i<N; i++)
78  {
79  image.data[i] = (unsigned int) ((fmin(3000, fmax(2000, msg->intensities[i])) - 2000) / 1000.0 * 255) ;
80  }
81  intensity_pub_.publish(image) ;
82  }
83 
84 private:
89 
90 };
91 
92 int main(int argc, char** argv)
93 {
94  ros::init(argc, argv, "laser_imager") ;
95 
96  LaserImager imager ;
97 
98  ros::spin() ;
99 
100  return 0 ;
101 }
void snapshotCallback(const calibration_msgs::DenseLaserSnapshotConstPtr &msg)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher range_pub_
Publisher intensity_pub_
ROSCPP_DECL void spin()


dense_laser_assembler
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:54