BV/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-2015, 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 HPP_FCL_RSS_H
39 #define HPP_FCL_RSS_H
40 
41 #include <hpp/fcl/data_types.h>
42 #include <boost/math/constants/constants.hpp>
43 
44 namespace hpp {
45 namespace fcl {
46 
47 struct CollisionRequest;
48 
51 
53 struct HPP_FCL_DLLAPI RSS {
60 
63 
65  FCL_REAL length[2];
66 
69 
71  RSS() : axes(Matrix3f::Zero()), Tr(Vec3f::Zero()), radius(-1) {
72  length[0] = 0;
73  length[1] = 0;
74  }
75 
77  bool operator==(const RSS& other) const {
78  return axes == other.axes && Tr == other.Tr &&
79  length[0] == other.length[0] && length[1] == other.length[1] &&
80  radius == other.radius;
81  }
82 
84  bool operator!=(const RSS& other) const { return !(*this == other); }
85 
87  bool contain(const Vec3f& p) const;
88 
90  bool overlap(const RSS& other) const;
91 
93  bool overlap(const RSS& other, const CollisionRequest&,
94  FCL_REAL& sqrDistLowerBound) const {
95  sqrDistLowerBound = sqrt(-1);
96  return overlap(other);
97  }
98 
101  FCL_REAL distance(const RSS& other, Vec3f* P = NULL, Vec3f* Q = NULL) const;
102 
105  RSS& operator+=(const Vec3f& p);
106 
108  inline RSS& operator+=(const RSS& other) {
109  *this = *this + other;
110  return *this;
111  }
112 
114  RSS operator+(const RSS& other) const;
115 
117  inline FCL_REAL size() const {
118  return (std::sqrt(length[0] * length[0] + length[1] * length[1]) +
119  2 * radius);
120  }
121 
123  inline const Vec3f& center() const { return Tr; }
124 
126  inline FCL_REAL width() const { return length[0] + 2 * radius; }
127 
129  inline FCL_REAL height() const { return length[1] + 2 * radius; }
130 
132  inline FCL_REAL depth() const { return 2 * radius; }
133 
135  inline FCL_REAL volume() const {
136  return (length[0] * length[1] * 2 * radius +
137  4 * boost::math::constants::pi<FCL_REAL>() * radius * radius *
138  radius);
139  }
140 
144  bool overlap(const RSS& other, RSS& /*overlap_part*/) const {
145  return overlap(other);
146  }
147 };
148 
154 HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f& R0, const Vec3f& T0,
155  const RSS& b1, const RSS& b2, Vec3f* P = NULL,
156  Vec3f* Q = NULL);
157 
160 HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1,
161  const RSS& b2);
162 
165 HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1,
166  const RSS& b2, const CollisionRequest& request,
167  FCL_REAL& sqrDistLowerBound);
168 
169 } // namespace fcl
170 
171 } // namespace hpp
172 
173 #endif
hpp::fcl::RSS::height
FCL_REAL height() const
Height of the RSS.
Definition: BV/RSS.h:129
data_types.h
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::RSS::RSS
RSS()
&#160;
Definition: BV/RSS.h:71
hpp::fcl::RSS::axes
Matrix3f axes
Orientation of RSS. axis[i] is the ith column of the orientation matrix for the RSS; it is also the i...
Definition: BV/RSS.h:59
hpp::fcl::RSS::depth
FCL_REAL depth() const
Depth of the RSS.
Definition: BV/RSS.h:132
hpp::fcl::RSS::operator!=
bool operator!=(const RSS &other) const
Difference operator.
Definition: BV/RSS.h:84
hpp::fcl::RSS::operator==
bool operator==(const RSS &other) const
Equality operator.
Definition: BV/RSS.h:77
hpp::fcl::distance
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
hpp::fcl::RSS::Tr
Vec3f Tr
Origin of the rectangle in RSS.
Definition: BV/RSS.h:62
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition: collision_data.h:235
hpp::fcl::RSS::overlap
bool overlap(const RSS &other, RSS &) const
Check collision between two RSS and return the overlap part. For RSS, we return nothing,...
Definition: BV/RSS.h:144
hpp::fcl::RSS::overlap
bool overlap(const RSS &other, const CollisionRequest &, FCL_REAL &sqrDistLowerBound) const
Not implemented.
Definition: BV/RSS.h:93
hpp::fcl::Matrix3f
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:68
hpp::fcl::RSS
A class for rectangle sphere-swept bounding volume.
Definition: BV/RSS.h:53
hpp::fcl::RSS::operator+=
RSS & operator+=(const RSS &other)
Merge the RSS and another RSS.
Definition: BV/RSS.h:108
hpp::fcl::overlap
HPP_FCL_DLLAPI bool overlap(const Matrix3f &R0, const Vec3f &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition: AABB.cpp:134
hpp::fcl::RSS::center
const Vec3f & center() const
The RSS center.
Definition: BV/RSS.h:123
hpp::fcl::RSS::size
FCL_REAL size() const
Size of the RSS (used in BV_Splitter to order two RSSs)
Definition: BV/RSS.h:117
hpp::fcl::RSS::width
FCL_REAL width() const
Width of the RSS.
Definition: BV/RSS.h:126
hpp::fcl::RSS::length
FCL_REAL length[2]
Side lengths of rectangle.
Definition: BV/RSS.h:65
hpp::fcl::RSS::radius
FCL_REAL radius
Radius of sphere summed with rectangle to form RSS.
Definition: BV/RSS.h:68
hpp::fcl::RSS::volume
FCL_REAL volume() const
Volume of the RSS.
Definition: BV/RSS.h:135


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:15