cv_laser_bridge_unittest.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <gtest/gtest.h>
00036 
00037 
00038 #include <calibration_msgs/DenseLaserSnapshot.h>
00039 #include <laser_cb_detector/cv_laser_bridge.h>
00040 
00041 using namespace std;
00042 using namespace laser_cb_detector;
00043 
00044 static const bool DEBUG=false;
00045 
00046 calibration_msgs::DenseLaserSnapshot buildSnapshot(double start_range, double start_intensity, double increment,
00047                                                    const unsigned int H, const unsigned int W)
00048 {
00049   calibration_msgs::DenseLaserSnapshot snapshot;
00050 
00051   snapshot.readings_per_scan = W;
00052   snapshot.num_scans = H;
00053 
00054   snapshot.ranges.resize(H*W);
00055   snapshot.intensities.resize(H*W);
00056 
00057   for (unsigned int i=0; i<H*W; i++)
00058   {
00059     snapshot.ranges[i]      = start_range     + i*increment;
00060     snapshot.intensities[i] = start_intensity + i*increment;
00061   }
00062 
00063   return snapshot;
00064 }
00065 
00066 static const unsigned int NUM_SCANS = 5;
00067 static const unsigned int RAYS_PER_SCAN = 10;
00068 static const double eps = 1e-8;
00069 
00070 void displayImage(cv::Mat &image)
00071 {
00072   for (int i=0; i<image.rows; i++)
00073   {
00074     for (int j=0; j<image.cols; j++)
00075     {
00076       printf("%3u  ", image.at<unsigned char>(i, j));
00077     }
00078     printf("\n");
00079   }
00080 }
00081 
00082 TEST(CvLaserBridge, easy)
00083 {
00084   CvLaserBridge bridge;
00085 
00086   calibration_msgs::DenseLaserSnapshot snapshot;
00087 
00088   snapshot = buildSnapshot(100.0, 0.0, 1.0, NUM_SCANS, RAYS_PER_SCAN);
00089 
00090   bool result;
00091 
00092   result = bridge.fromIntensity(snapshot, 0, 49);
00093   cv::Mat image = bridge.toCvMat();
00094 
00095   ASSERT_TRUE(result);
00096   ASSERT_TRUE(image.data);
00097 
00098   EXPECT_EQ(image.rows, (int) NUM_SCANS);
00099   EXPECT_EQ(image.cols,  (int) RAYS_PER_SCAN);
00100 
00101   if (DEBUG)
00102     displayImage(image);
00103 
00104   // Check the first and last pixel in the image
00105   EXPECT_EQ( (int) *((unsigned char*)(image.data)+0), 0);
00106   EXPECT_EQ( (int) *((unsigned char*)(image.data)+4*image.step + 9), 255);
00107 }
00108 
00109 TEST(CvLaserBridge, saturationTest)
00110 {
00111   CvLaserBridge bridge;
00112   calibration_msgs::DenseLaserSnapshot snapshot;
00113   snapshot = buildSnapshot(100.0, 0.0, 1.0, NUM_SCANS, RAYS_PER_SCAN);
00114 
00115   bool result;
00116   result = bridge.fromIntensity(snapshot, 10, 20);
00117   cv::Mat image = bridge.toCvMat();
00118   ASSERT_TRUE(result);
00119   ASSERT_TRUE(image.data);
00120 
00121   EXPECT_EQ(image.rows, (int) NUM_SCANS);
00122   EXPECT_EQ(image.cols,  (int) RAYS_PER_SCAN);
00123 
00124   if (DEBUG)
00125     displayImage(image);
00126 
00127   // Check to make sure some of the pixels saturated near the beginning and end of the range
00128   EXPECT_EQ( (int) *((unsigned char*)(image.data)+5), 0);
00129   EXPECT_EQ( (int) *((unsigned char*)(image.data)+45), 255);
00130 }
00131 
00132 
00133 
00134 int main(int argc, char **argv){
00135   testing::InitGoogleTest(&argc, argv);
00136   return RUN_ALL_TESTS();
00137 }


laser_cb_detector
Author(s): Vijay Pradeep
autogenerated on Sat Jun 8 2019 19:41:58