RSS.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_BV_RSS_H
39 #define FCL_BV_RSS_H
40 
41 #include "fcl/math/constants.h"
42 #include "fcl/math/geometry.h"
43 
44 namespace fcl
45 {
46 
57 template <typename S_>
58 class FCL_EXPORT RSS
59 {
60 public:
61 
62  using S = S_;
63 
71 
77 
79  S l[2];
80 
82  S r;
83 
85  RSS();
86 
88  bool overlap(const RSS<S>& other) const;
89 
92  bool overlap(const RSS<S>& other, RSS<S>& overlap_part) const;
93 
95  bool contain(const Vector3<S>& p) const;
96 
99  RSS<S>& operator += (const Vector3<S>& p);
100 
102  RSS<S>& operator += (const RSS<S>& other);
103 
105  RSS<S> operator + (const RSS<S>& other) const;
106 
108  S width() const;
109 
111  S height() const;
112 
114  S depth() const;
115 
117  S volume() const;
118 
120  S size() const;
121 
123  const Vector3<S> center() const;
124 
128  void setToFromCenter(const Vector3<S>& p_FoCenter_F);
129 
131  S distance(const RSS<S>& other,
132  Vector3<S>* P = nullptr,
133  Vector3<S>* Q = nullptr) const;
134 
135  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
136 
137 private:
138  // Internal monogram notation alias of axis.
139  Matrix3<S>& R_FT() { return axis; }
140 
141  // Internal monogram notation const alias of axis.
142  const Matrix3<S>& R_FT() const { return axis; }
143 
144  // Internal monogram notation alias of To.
145  Vector3<S>& p_FoTo_F() { return To; }
146 
147  // Internal monogram notation alias of To.
148  const Vector3<S>& p_FoTo_F() const { return To; }
149 };
150 
151 using RSSf = RSS<float>;
153 
155 template <typename S>
156 FCL_EXPORT
157 void clipToRange(S& val, S a, S b);
158 
171 template <typename S>
172 FCL_EXPORT
173 void segCoords(S& t, S& u, S a, S b,
174  S A_dot_B, S A_dot_T, S B_dot_T);
175 
181 template <typename S>
182 FCL_EXPORT
183 bool inVoronoi(S a, S b,
184  S Anorm_dot_B, S Anorm_dot_T,
185  S A_dot_B, S A_dot_T, S B_dot_T);
186 
190 template <typename S>
191 FCL_EXPORT
192 S rectDistance(
193  const Matrix3<S>& Rab,
194  const Vector3<S>& Tab,
195  const S a[2],
196  const S b[2],
197  Vector3<S>* P = nullptr,
198  Vector3<S>* Q = nullptr);
199 
203 template <typename S>
204 FCL_EXPORT
205 S rectDistance(
206  const Transform3<S>& tfab,
207  const S a[2],
208  const S b[2],
209  Vector3<S>* P = nullptr,
210  Vector3<S>* Q = nullptr);
211 
217 template <typename S, typename DerivedA, typename DerivedB>
218 FCL_EXPORT
219 S distance(
220  const Eigen::MatrixBase<DerivedA>& R0,
221  const Eigen::MatrixBase<DerivedB>& T0,
222  const RSS<S>& b1,
223  const RSS<S>& b2,
224  Vector3<S>* P = nullptr,
225  Vector3<S>* Q = nullptr);
226 
229 template <typename S, typename DerivedA, typename DerivedB>
230 FCL_EXPORT
231 bool overlap(
232  const Eigen::MatrixBase<DerivedA>& R0,
233  const Eigen::MatrixBase<DerivedB>& T0,
234  const RSS<S>& b1,
235  const RSS<S>& b2);
236 
238 template <typename S>
239 FCL_EXPORT
240 RSS<S> translate(const RSS<S>& bv, const Vector3<S>& t);
241 
242 } // namespace fcl
243 
244 #include "fcl/math/bv/RSS-inl.h"
245 
246 #endif
fcl::RSS< Shape::S >::S
Shape::S S
Definition: RSS.h:62
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::rectDistance
template double rectDistance(const Matrix3< double > &Rab, const Vector3< double > &Tab, const double a[2], const double b[2], Vector3< double > *P, Vector3< double > *Q)
fcl::RSS::R_FT
const Matrix3< S > & R_FT() const
Definition: RSS.h:142
geometry.h
fcl::distance
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
fcl::translate
AABB< S > translate(const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t)
translate the center of AABB by t
Definition: AABB-inl.h:345
fcl::overlap
bool overlap(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2)
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition: kIOS-inl.h:249
fcl::RSS::To
Vector3< S > To
Origin of frame T in frame F.
Definition: RSS.h:76
fcl::RSS
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::Matrix3
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
RSS-inl.h
fcl::inVoronoi
template bool inVoronoi(double a, double b, double Anorm_dot_B, double Anorm_dot_T, double A_dot_B, double A_dot_T, double B_dot_T)
fcl::RSS::p_FoTo_F
Vector3< S > & p_FoTo_F()
Definition: RSS.h:145
fcl::RSS::r
S r
Radius of sphere summed with rectangle to form RSS.
Definition: RSS.h:82
constants.h
fcl::segCoords
template void segCoords(double &t, double &u, double a, double b, double A_dot_B, double A_dot_T, double B_dot_T)
fcl::RSS::R_FT
Matrix3< S > & R_FT()
Definition: RSS.h:139
fcl::clipToRange
template void clipToRange(double &val, double a, double b)
fcl::RSS::axis
Matrix3< S > axis
Frame T's orientation in frame F.
Definition: RSS.h:70
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::RSS::p_FoTo_F
const Vector3< S > & p_FoTo_F() const
Definition: RSS.h:148
fcl::operator+
template TMatrix3< double > operator+(const Matrix3< double > &m1, const TMatrix3< double > &m2)


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