frustum.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2018, Simbe Robotics, 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 Simbe Robotics, Inc. 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  * Author: Steve Macenski (steven.macenski@simberobotics.com)
36  * Purpose: Abstract class for a frustum model implementation
37  *********************************************************************/
38 
39 #ifndef FRUSTUM_H_
40 #define FRUSTUM_H_
41 
42 // Eigen
43 #include <Eigen/Geometry>
44 // STL
45 #include <vector>
46 #include <cassert>
47 // OpenVDB
48 #include <openvdb/openvdb.h>
49 // msgs
50 #include <geometry_msgs/Point.h>
51 #include <visualization_msgs/Marker.h>
52 #include <visualization_msgs/MarkerArray.h>
53 #include <geometry_msgs/Quaternion.h>
54 #include <geometry_msgs/PointStamped.h>
55 #include <geometry_msgs/Pose.h>
56 // ROS
57 #include <ros/ros.h>
58 
59 namespace geometry
60 {
61 
62 // A structure for maintaining vectors and points in world spaces
64 {
65  VectorWithPt3D(const double& x_, const double& y_, \
66  const double& z_, const Eigen::Vector3d& p0) : \
67  x(x_), y(y_), z(z_), initial_point(p0)
68  {
69  }
70 
71  VectorWithPt3D(void) : x(0.), y(0.), z(0.)
72  {
73  }
74 
75  inline VectorWithPt3D operator*(double a)
76  {
77  return VectorWithPt3D(a*x, a*y, a*z, initial_point);
78  }
79 
80  // given a transform, transform its information
81  void TransformFrames(const Eigen::Affine3d& homogeneous_transform)
82  {
83  Eigen::Vector3d vec_t = homogeneous_transform.rotation() * Eigen::Vector3d(x,y,z);
84  vec_t.normalize();
85  x = vec_t[0]; y = vec_t[1]; z = vec_t[2];
86  initial_point = homogeneous_transform * initial_point;
87  return;
88  }
89 
90  double x, y, z;
91  Eigen::Vector3d initial_point;
92 };
93 
94 // A class to model a depth sensor frustum in world space
95 class Frustum
96 {
97 public:
98  Frustum() {};
99  virtual ~Frustum(void) {};
100 
101  // determine if a point is inside of the transformed frustum
102  virtual bool IsInside(const openvdb::Vec3d& pt) = 0;
103 
104  // set pose of depth camera in global space
105  virtual void SetPosition(const geometry_msgs::Point& origin) = 0;
106  virtual void SetOrientation(const geometry_msgs::Quaternion& quat) = 0;
107 
108  // transform model to the current coordinates
109  virtual void TransformModel(void) = 0;
110 
111 private:
112  Eigen::Vector3d _position;
113  Eigen::Quaterniond _orientation;
115 };
116 
117 } // end namespace
118 
119 #endif
Eigen::Vector3d initial_point
Definition: frustum.hpp:91
Eigen::Quaterniond _orientation
Definition: frustum.hpp:113
void TransformFrames(const Eigen::Affine3d &homogeneous_transform)
Definition: frustum.hpp:81
virtual ~Frustum(void)
Definition: frustum.hpp:99
VectorWithPt3D(const double &x_, const double &y_, const double &z_, const Eigen::Vector3d &p0)
Definition: frustum.hpp:65
VectorWithPt3D operator*(double a)
Definition: frustum.hpp:75
Eigen::Vector3d _position
Definition: frustum.hpp:112


spatio_temporal_voxel_layer
Author(s):
autogenerated on Sat Dec 21 2019 04:06:19