joint_imager_unittest.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 <gtest/gtest.h>
37 
38 using namespace std;
39 using namespace laser_joint_processor;
41 
42 static const float eps = 1e-6;
43 
45 
46 void populateCache(DeflatedDeque& cache, const ros::Time& start, const unsigned int N)
47 {
48  for (unsigned int i=0; i<N; i++)
49  {
51  deflated.header.stamp = start + ros::Duration(i,0);
52  deflated.channels_.resize(2);
53  deflated.channels_[0] = 10*i;
54  deflated.channels_[1] = 100*i;
55 
56  cache.add(deflated);
57  }
58 }
59 
60 
61 class JointImager_EasyTests : public ::testing::Test
62 {
63 protected:
64  virtual void SetUp()
65  {
66  cache_.setMaxSize(1000);
67  populateCache(cache_, ros::Time(0,0), 100);
68 
69  snapshot_.time_increment = 1;
70  snapshot_.readings_per_scan = 3;
71  snapshot_.num_scans = 4;
72  snapshot_.scan_start.resize(4);
73  snapshot_.scan_start[0] = ros::Time(.5);
74  snapshot_.scan_start[1] = ros::Time(10);
75  snapshot_.scan_start[2] = ros::Time(35);
76  snapshot_.scan_start[3] = ros::Time(50.5);
77 
78  bool success;
79  success =imager_.update(snapshot_, cache_, ros::Duration(2,0));
80  ASSERT_TRUE(success);
81 
82  image0_ = imager_.getJointImage(0);
83  image1_ = imager_.getJointImage(1);
84  }
85 
87  calibration_msgs::DenseLaserSnapshot snapshot_;
89 
90  IplImage* image0_;
91  IplImage* image1_;
92 };
93 
94 float imageAt(IplImage* image, int row, int col, int channel)
95 {
96  return *(((float*)(image->imageData + row*image->widthStep)) + image->nChannels*col + channel);
97 }
98 
100 {
101  EXPECT_NEAR(imageAt(image0_, 0, 0, 0), 5, eps);
102  EXPECT_NEAR(imageAt(image0_, 1, 0, 0), 100, eps);
103  EXPECT_NEAR(imageAt(image0_, 2, 0, 0), 350, eps);
104  EXPECT_NEAR(imageAt(image0_, 0, 2, 0), 25, eps);
105  EXPECT_NEAR(imageAt(image0_, 3, 2, 0), 525, eps);
106 
107  EXPECT_NEAR(imageAt(image1_, 0, 0, 0), 50, eps);
108  EXPECT_NEAR(imageAt(image1_, 3, 2, 0), 5250, eps);
109 
110 }
111 
113 {
114  EXPECT_NEAR(imageAt(image0_, 0, 0, 1), 10, eps);
115  EXPECT_NEAR(imageAt(image0_, 0, 1, 1), 10, eps);
116  EXPECT_NEAR(imageAt(image0_, 0, 2, 1), 10, eps);
117  EXPECT_NEAR(imageAt(image0_, 3, 0, 1), 10, eps);
118  EXPECT_NEAR(imageAt(image0_, 3, 1, 1), 10, eps);
119  EXPECT_NEAR(imageAt(image0_, 3, 2, 1), 10, eps);
120 
121  EXPECT_NEAR(imageAt(image1_, 0, 0, 1), 100, eps);
122  EXPECT_NEAR(imageAt(image1_, 0, 1, 1), 100, eps);
123  EXPECT_NEAR(imageAt(image1_, 0, 2, 1), 100, eps);
124  EXPECT_NEAR(imageAt(image1_, 3, 0, 1), 100, eps);
125  EXPECT_NEAR(imageAt(image1_, 3, 1, 1), 100, eps);
126  EXPECT_NEAR(imageAt(image1_, 3, 2, 1), 100, eps);
127 }
128 
129 int main(int argc, char **argv){
130  testing::InitGoogleTest(&argc, argv);
131  return RUN_ALL_TESTS();
132 }
static const float eps
settlerlib::SortedDeque< joint_states_settler::DeflatedJointStates > DeflatedDeque
void populateCache(DeflatedDeque &cache, const ros::Time &start, const unsigned int N)
std_msgs::Header header
int main(int argc, char **argv)
std::vector< double > channels_
float imageAt(IplImage *image, int row, int col, int channel)
void add(const M &msg)
calibration_msgs::DenseLaserSnapshot snapshot_
TEST_F(JointImager_EasyTests, positions)


laser_joint_processor
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:55