geometry/shape/halfspace-inl.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
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 Open Source Robotics Foundation 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 
38 #ifndef FCL_SHAPE_HALFSPACE_INL_H
39 #define FCL_SHAPE_HALFSPACE_INL_H
40 
41 #include <iomanip>
42 #include <sstream>
43 
46 
47 namespace fcl
48 {
49 
50 //==============================================================================
51 extern template
52 class FCL_EXPORT Halfspace<double>;
53 
54 //==============================================================================
55 extern template
56 Halfspace<double> transform(const Halfspace<double>& a, const Transform3<double>& tf);
57 
58 //==============================================================================
59 template <typename S>
61  : ShapeBase<S>(), n(n), d(d)
62 {
64 }
65 
66 //==============================================================================
67 template <typename S>
69  : ShapeBase<S>(), n(a, b, c), d(d)
70 {
72 }
73 
74 //==============================================================================
75 template <typename S>
76 Halfspace<S>::Halfspace() : ShapeBase<S>(), n(1, 0, 0), d(0)
77 {
78  // Do nothing
79 }
80 
81 //==============================================================================
82 template <typename S>
84 {
85  return n.dot(p) - d;
86 }
87 
88 //==============================================================================
89 template <typename S>
91 {
92  return std::abs(n.dot(p) - d);
93 }
94 
95 //==============================================================================
96 template <typename S>
98 {
99  this->aabb_local.min_.setConstant(-std::numeric_limits<S>::max());
100  this->aabb_local.max_.setConstant(std::numeric_limits<S>::max());
101  if(n[1] == (S)0.0 && n[2] == (S)0.0)
102  {
103  // normal aligned with x axis
104  if(n[0] < 0)
105  this->aabb_local.min_[0] = -d;
106  else if(n[0] > 0)
107  this->aabb_local.max_[0] = d;
108  }
109  else if(n[0] == (S)0.0 && n[2] == (S)0.0)
110  {
111  // normal aligned with y axis
112  if(n[1] < 0)
113  this->aabb_local.min_[1] = -d;
114  else if(n[1] > 0)
115  this->aabb_local.max_[1] = d;
116  }
117  else if(n[0] == (S)0.0 && n[1] == (S)0.0)
118  {
119  // normal aligned with z axis
120  if(n[2] < 0)
121  this->aabb_local.min_[2] = -d;
122  else if(n[2] > 0)
123  this->aabb_local.max_[2] = d;
124  }
125 
126  this->aabb_center = this->aabb_local.center();
127  this->aabb_radius = (this->aabb_local.min_ - this->aabb_center).norm();
128 }
129 
130 //==============================================================================
131 template <typename S>
133 {
134  return GEOM_HALFSPACE;
135 }
136 
137 //==============================================================================
138 template <typename S>
139 std::string Halfspace<S>::representation(int precision) const {
140  const char* S_str = detail::ScalarRepr<S>::value();
141  std::stringstream ss;
142  ss << std::setprecision(precision);
143  ss << "Halfspace<" << S_str << ">(" << n[0] << ", " << n[1] << ", " << n[2]
144  << ", " << d << ");";
145  return ss.str();
146 }
147 
148 //==============================================================================
149 template <typename S>
151 {
152  S l = n.norm();
153  if(l > 0)
154  {
155  S inv_l = 1.0 / l;
156  n *= inv_l;
157  d *= inv_l;
158  }
159  else
160  {
161  n << 1, 0, 0;
162  d = 0;
163  }
164 }
165 
166 //==============================================================================
167 template <typename S>
169 {
175 
176  Vector3<S> n = tf.linear() * a.n;
177  S d = a.d + n.dot(tf.translation());
178 
179  return Halfspace<S>(n, d);
180 }
181 
182 } // namespace fcl
183 
184 #endif
fcl::detail::ScalarRepr::value
static const char * value()
Definition: representation.h:47
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::Halfspace::getNodeType
NODE_TYPE getNodeType() const override
Get node type: a half space.
Definition: geometry/shape/halfspace-inl.h:132
fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_geometry.h:54
fcl::Halfspace::S
S_ S
Definition: geometry/shape/halfspace.h:64
fcl::Halfspace::computeLocalAABB
void computeLocalAABB() override
Compute AABB.
Definition: geometry/shape/halfspace-inl.h:97
halfspace.h
max
static T max(T x, T y)
Definition: svm.cpp:52
fcl::transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
fcl::ShapeBase
Base class for all basic geometric shapes.
Definition: shape_base.h:48
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
representation.h
fcl::Halfspace::unitNormalTest
void unitNormalTest()
Turn non-unit normal into unit.
Definition: geometry/shape/halfspace-inl.h:150
fcl::Halfspace< double >
template class FCL_EXPORT Halfspace< double >
fcl::Halfspace
Half Space: this is equivalent to the Planed in ODE. The separation plane is defined as n * x = d....
Definition: geometry/shape/halfspace.h:60
fcl::Halfspace::signedDistance
S signedDistance(const Vector3< S > &p) const
Definition: geometry/shape/halfspace-inl.h:83
fcl::Halfspace::n
Vector3< S > n
Planed normal.
Definition: geometry/shape/halfspace.h:85
fcl::Halfspace::d
S d
Planed offset.
Definition: geometry/shape/halfspace.h:88
fcl::Halfspace::distance
S distance(const Vector3< S > &p) const
Definition: geometry/shape/halfspace-inl.h:90
fcl::Halfspace::Halfspace
Halfspace()
Definition: geometry/shape/halfspace-inl.h:76
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::Halfspace::representation
std::string representation(int precision=20) const
Create a string that should be sufficient to recreate this shape. This is akin to the repr() implemen...
Definition: geometry/shape/halfspace-inl.h:139


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48