test_kinect_filtering.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  */
30 
39 #include <ar_track_alvar/kinect_filtering.h>
40 
41 namespace a=ar_track_alvar;
42 namespace gm=geometry_msgs;
43 
44 using std::cerr;
45 
46 // Random float between a and b
47 float randFloat (float a, float b)
48 {
49  const float u = static_cast<float>(rand())/RAND_MAX;
50  return a + u*(b-a);
51 }
52 
53 // Generate points in a square in space of form p+av+bw where
54 // a and b range from 0 to 1
55 a::ARCloud::Ptr generateCloud(const double px, const double py, const double pz,
56  const double vx, const double vy, const double vz,
57  const double wx, const double wy, const double wz)
58 {
59  const double INC=0.1;
60  const double NOISE=0.01;
61 
62  a::ARCloud::Ptr cloud(boost::make_shared<a::ARCloud>());
63  for (double u=0; u<1+INC/2; u+=INC)
64  {
65  for (double v=0; v<1+INC/2; v+=INC)
66  {
67  a::ARPoint p;
68  p.x = px+u*vx+v*wx+randFloat(-NOISE, NOISE);
69  p.y = py+u*vy+v*wy+randFloat(-NOISE, NOISE);
70  p.z = pz+u*vz+v*wz+randFloat(-NOISE, NOISE);
71  cloud->points.push_back(p);
72  }
73  }
74  return cloud;
75 }
76 
77 int main (int argc, char** argv)
78 {
79  if (argc != 12)
80  {
81  cerr << "Usage: " << argv[0] << " PX PY PZ VX VY VZ WX WY WZ I1 I2 I3\n";
82  return 1;
83  }
84 
85  const double px = atof(argv[1]);
86  const double py = atof(argv[2]);
87  const double pz = atof(argv[3]);
88  const double vx = atof(argv[4]);
89  const double vy = atof(argv[5]);
90  const double vz = atof(argv[6]);
91  const double wx = atof(argv[7]);
92  const double wy = atof(argv[8]);
93  const double wz = atof(argv[9]);
94 
95  a::ARCloud::ConstPtr cloud =
96  generateCloud(px, py, pz, vx, vy, vz, wx, wy, wz);
97  const size_t n = cloud->size();
98  ROS_INFO("Generated cloud with %zu points such as (%.4f, %.4f, %.4f)"
99  " and (%.4f, %.4f, %.4f)", n, (*cloud)[0].x, (*cloud)[0].y,
100  (*cloud)[0].z, (*cloud)[n-1].x, (*cloud)[n-1].y, (*cloud)[n-1].z);
101 
102  const size_t i1 = atoi(argv[10]);
103  const size_t i2 = atoi(argv[11]);
104  const size_t i3 = atoi(argv[12]);
105  a::ARPoint p1 = (*cloud)[i1];
106  a::ARPoint p2 = (*cloud)[i2];
107  a::ARPoint p3 = (*cloud)[i3];
108  ROS_INFO("Points are (%.4f, %.4f, %.4f) and (%.4f, %.4f, %.4f)",
109  p1.x, p1.y, p1.z, p2.x, p2.y, p2.z);
110 
112  ROS_INFO("Plane equation is %.3fx + %.3fy + %.3fz + %.3f = 0",
113  res.coeffs.values[0], res.coeffs.values[1], res.coeffs.values[2],
114  res.coeffs.values[3]);
115 
116  gm::Quaternion q = a::extractOrientation(res.coeffs, p1, p2, p3, p1);
117  ROS_INFO_STREAM("Orientation is " << q);
118 
119 
120  return 0;
121 }
pcl::PointXYZRGB ARPoint
int main(int argc, char **argv)
int extractOrientation(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, geometry_msgs::Quaternion &retQ)
TFSIMD_FORCE_INLINE const tfScalar & y() const
float randFloat(float a, float b)
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_INFO_STREAM(args)
pcl::ModelCoefficients coeffs
a::ARCloud::Ptr generateCloud(const double px, const double py, const double pz, const double vx, const double vy, const double vz, const double wx, const double wy, const double wz)
const int res
PlaneFitResult fitPlane(ARCloud::ConstPtr cloud)


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04