AlignedBox.h
Go to the documentation of this file.
1 // This file is part of Eigen, a lightweight C++ template library
2 // for linear algebra.
3 //
4 // Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
5 //
6 // This Source Code Form is subject to the terms of the Mozilla
7 // Public License v. 2.0. If a copy of the MPL was not distributed
8 // with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
9 
10 // Function void Eigen::AlignedBox::transform(const Transform& transform)
11 // is provided under the following license agreement:
12 //
13 // Software License Agreement (BSD License)
14 //
15 // Copyright (c) 2011-2014, Willow Garage, Inc.
16 // Copyright (c) 2014-2015, Open Source Robotics Foundation
17 // All rights reserved.
18 //
19 // Redistribution and use in source and binary forms, with or without
20 // modification, are permitted provided that the following conditions
21 // are met:
22 //
23 // * Redistributions of source code must retain the above copyright
24 // notice, this list of conditions and the following disclaimer.
25 // * Redistributions in binary form must reproduce the above
26 // copyright notice, this list of conditions and the following
27 // disclaimer in the documentation and/or other materials provided
28 // with the distribution.
29 // * Neither the name of Open Source Robotics Foundation nor the names of its
30 // contributors may be used to endorse or promote products derived
31 // from this software without specific prior written permission.
32 //
33 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
34 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
35 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
36 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
37 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
39 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
40 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
41 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
42 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
43 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
44 // POSSIBILITY OF SUCH DAMAGE.
45 
46 #ifndef EIGEN_ALIGNEDBOX_H
47 #define EIGEN_ALIGNEDBOX_H
48 
49 namespace Eigen {
50 
65 template <typename _Scalar, int _AmbientDim>
66 class AlignedBox
67 {
68 public:
70  enum { AmbientDimAtCompileTime = _AmbientDim };
71  typedef _Scalar Scalar;
73  typedef Eigen::Index Index;
74  typedef typename ScalarTraits::Real RealScalar;
75  typedef typename ScalarTraits::NonInteger NonInteger;
78 
81  {
83  Min=0, Max=1,
97  };
98 
99 
103 
105  EIGEN_DEVICE_FUNC inline explicit AlignedBox(Index _dim) : m_min(_dim), m_max(_dim)
106  { setEmpty(); }
107 
110  template<typename OtherVectorType1, typename OtherVectorType2>
111  EIGEN_DEVICE_FUNC inline AlignedBox(const OtherVectorType1& _min, const OtherVectorType2& _max) : m_min(_min), m_max(_max) {}
112 
114  template<typename Derived>
116  { }
117 
119 
122 
124  EIGEN_DEVICE_FUNC inline bool isNull() const { return isEmpty(); }
125 
127  EIGEN_DEVICE_FUNC inline void setNull() { setEmpty(); }
128 
131  EIGEN_DEVICE_FUNC inline bool isEmpty() const { return (m_min.array() > m_max.array()).any(); }
132 
136  {
137  m_min.setConstant( ScalarTraits::highest() );
138  m_max.setConstant( ScalarTraits::lowest() );
139  }
140 
142  EIGEN_DEVICE_FUNC inline const VectorType& (min)() const { return m_min; }
144  EIGEN_DEVICE_FUNC inline VectorType& (min)() { return m_min; }
146  EIGEN_DEVICE_FUNC inline const VectorType& (max)() const { return m_max; }
148  EIGEN_DEVICE_FUNC inline VectorType& (max)() { return m_max; }
149 
152  center() const
153  { return (m_min+m_max)/RealScalar(2); }
154 
160  { return m_max - m_min; }
161 
164  { return sizes().prod(); }
165 
171  { return sizes(); }
172 
183  {
184  EIGEN_STATIC_ASSERT(_AmbientDim <= 3, THIS_METHOD_IS_ONLY_FOR_VECTORS_OF_A_SPECIFIC_SIZE);
185 
186  VectorType res;
187 
188  Index mult = 1;
189  for(Index d=0; d<dim(); ++d)
190  {
191  if( mult & corner ) res[d] = m_max[d];
192  else res[d] = m_min[d];
193  mult *= 2;
194  }
195  return res;
196  }
197 
201  {
202  VectorType r(dim());
203  for(Index d=0; d<dim(); ++d)
204  {
206  {
207  r[d] = m_min[d] + (m_max[d]-m_min[d])
208  * internal::random<Scalar>(Scalar(0), Scalar(1));
209  }
210  else
211  r[d] = internal::random(m_min[d], m_max[d]);
212  }
213  return r;
214  }
215 
217  template<typename Derived>
219  {
220  typename internal::nested_eval<Derived,2>::type p_n(p.derived());
221  return (m_min.array()<=p_n.array()).all() && (p_n.array()<=m_max.array()).all();
222  }
223 
225  EIGEN_DEVICE_FUNC inline bool contains(const AlignedBox& b) const
226  { return (m_min.array()<=(b.min)().array()).all() && ((b.max)().array()<=m_max.array()).all(); }
227 
230  EIGEN_DEVICE_FUNC inline bool intersects(const AlignedBox& b) const
231  { return (m_min.array()<=(b.max)().array()).all() && ((b.min)().array()<=m_max.array()).all(); }
232 
235  template<typename Derived>
237  {
238  typename internal::nested_eval<Derived,2>::type p_n(p.derived());
239  m_min = m_min.cwiseMin(p_n);
240  m_max = m_max.cwiseMax(p_n);
241  return *this;
242  }
243 
247  {
248  m_min = m_min.cwiseMin(b.m_min);
249  m_max = m_max.cwiseMax(b.m_max);
250  return *this;
251  }
252 
257  {
258  m_min = m_min.cwiseMax(b.m_min);
259  m_max = m_max.cwiseMin(b.m_max);
260  return *this;
261  }
262 
267  {return AlignedBox(m_min.cwiseMax(b.m_min), m_max.cwiseMin(b.m_max)); }
268 
273  { return AlignedBox(m_min.cwiseMin(b.m_min), m_max.cwiseMax(b.m_max)); }
274 
276  template<typename Derived>
278  {
279  const typename internal::nested_eval<Derived,2>::type t(a_t.derived());
280  m_min += t;
281  m_max += t;
282  return *this;
283  }
284 
286  template<typename Derived>
288  {
290  result.translate(a_t);
291  return result;
292  }
293 
298  template<typename Derived>
300 
306 
311  template<typename Derived>
314 
321 
325  template<int Mode, int Options>
328  {
329  this->translate(translation);
330  }
331 
338  template<int Mode, int Options>
340  {
341  // Only Affine and Isometry transforms are currently supported.
342  EIGEN_STATIC_ASSERT(Mode == Affine || Mode == AffineCompact || Mode == Isometry, THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS);
343 
344  // Method adapted from FCL src/shape/geometric_shapes_utility.cpp#computeBV<AABB, Box>(...)
345  // https://github.com/flexible-collision-library/fcl/blob/fcl-0.4/src/shape/geometric_shapes_utility.cpp#L292
346  //
347  // Here's a nice explanation why it works: https://zeuxcg.org/2010/10/17/aabb-from-obb-with-component-wise-abs/
348 
349  // two times rotated extent
350  const VectorType rotated_extent_2 = transform.linear().cwiseAbs() * sizes();
351  // two times new center
352  const VectorType rotated_center_2 = transform.linear() * (this->m_max + this->m_min) +
353  Scalar(2) * transform.translation();
354 
355  this->m_max = (rotated_center_2 + rotated_extent_2) / Scalar(2);
356  this->m_min = (rotated_center_2 - rotated_extent_2) / Scalar(2);
357  }
358 
363  template<int Mode, int Options>
365  {
367  result.transform(transform);
368  return result;
369  }
370 
376  template<typename NewScalarType>
379  {
380  return typename internal::cast_return_type<AlignedBox,
382  }
383 
385  template<typename OtherScalarType>
387  {
388  m_min = (other.min)().template cast<Scalar>();
389  m_max = (other.max)().template cast<Scalar>();
390  }
391 
396  EIGEN_DEVICE_FUNC bool isApprox(const AlignedBox& other, const RealScalar& prec = ScalarTraits::dummy_precision()) const
397  { return m_min.isApprox(other.m_min, prec) && m_max.isApprox(other.m_max, prec); }
398 
399 protected:
400 
402 };
403 
404 
405 
406 template<typename Scalar,int AmbientDim>
407 template<typename Derived>
409 {
411  Scalar dist2(0);
412  Scalar aux;
413  for (Index k=0; k<dim(); ++k)
414  {
415  if( m_min[k] > p[k] )
416  {
417  aux = m_min[k] - p[k];
418  dist2 += aux*aux;
419  }
420  else if( p[k] > m_max[k] )
421  {
422  aux = p[k] - m_max[k];
423  dist2 += aux*aux;
424  }
425  }
426  return dist2;
427 }
428 
429 template<typename Scalar,int AmbientDim>
431 {
432  Scalar dist2(0);
433  Scalar aux;
434  for (Index k=0; k<dim(); ++k)
435  {
436  if( m_min[k] > b.m_max[k] )
437  {
438  aux = m_min[k] - b.m_max[k];
439  dist2 += aux*aux;
440  }
441  else if( b.m_min[k] > m_max[k] )
442  {
443  aux = b.m_min[k] - m_max[k];
444  dist2 += aux*aux;
445  }
446  }
447  return dist2;
448 }
449 
466 #define EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Size, SizeSuffix) \
467  \
468 typedef AlignedBox<Type, Size> AlignedBox##SizeSuffix##TypeSuffix;
469 
470 #define EIGEN_MAKE_TYPEDEFS_ALL_SIZES(Type, TypeSuffix) \
471 EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 1, 1) \
472 EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 2, 2) \
473 EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 3, 3) \
474 EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 4, 4) \
475 EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Dynamic, X)
476 
480 
481 #undef EIGEN_MAKE_TYPEDEFS_ALL_SIZES
482 #undef EIGEN_MAKE_TYPEDEFS
483 
484 } // end namespace Eigen
485 
486 #endif // EIGEN_ALIGNEDBOX_H
Eigen::AlignedBox::RealScalar
ScalarTraits::Real RealScalar
Definition: AlignedBox.h:74
EIGEN_DEVICE_FUNC
#define EIGEN_DEVICE_FUNC
Definition: Macros.h:976
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Eigen::internal::cast_return_type
Definition: XprHelper.h:509
Eigen::AlignedBox::~AlignedBox
EIGEN_DEVICE_FUNC ~AlignedBox()
Definition: AlignedBox.h:118
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
Eigen::AlignedBox::AmbientDimAtCompileTime
@ AmbientDimAtCompileTime
Definition: AlignedBox.h:70
Eigen::Transform
Represents an homogeneous transformation in a N dimensional space.
Definition: ForwardDeclarations.h:294
EIGEN_USING_STD
#define EIGEN_USING_STD(FUNC)
Definition: Macros.h:1185
Eigen::AlignedBox::merged
EIGEN_DEVICE_FUNC AlignedBox merged(const AlignedBox &b) const
Definition: AlignedBox.h:272
Eigen::CwiseBinaryOp
Generic expression where a coefficient-wise binary operator is applied to two expressions.
Definition: CwiseBinaryOp.h:77
d
static const double d[K][N]
Definition: igam.h:11
Eigen::Affine
@ Affine
Definition: Constants.h:460
Eigen::AlignedBox::isApprox
EIGEN_DEVICE_FUNC bool isApprox(const AlignedBox &other, const RealScalar &prec=ScalarTraits::dummy_precision()) const
Definition: AlignedBox.h:396
b
Scalar * b
Definition: benchVecAdd.cpp:17
Eigen::AlignedBox::m_min
VectorType m_min
Definition: AlignedBox.h:401
Eigen::AlignedBox::BottomRightFloor
@ BottomRightFloor
Definition: AlignedBox.h:92
Eigen::AlignedBox::min
const EIGEN_DEVICE_FUNC VectorType &() min() const
Definition: AlignedBox.h:142
Eigen::AlignedBox::max
const EIGEN_DEVICE_FUNC VectorType &() max() const
Definition: AlignedBox.h:146
Eigen::AlignedBox::TopLeftCeil
@ TopLeftCeil
Definition: AlignedBox.h:95
Eigen::AlignedBox::TopRightCeil
@ TopRightCeil
Definition: AlignedBox.h:95
type
Definition: pytypes.h:1491
Eigen::AlignedBox::intersection
EIGEN_DEVICE_FUNC AlignedBox intersection(const AlignedBox &b) const
Definition: AlignedBox.h:266
Eigen::AlignedBox::BottomLeftCeil
@ BottomLeftCeil
Definition: AlignedBox.h:94
res
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Definition: PartialRedux_count.cpp:3
Eigen::AlignedBox::clamp
EIGEN_DEVICE_FUNC AlignedBox & clamp(const AlignedBox &b)
Definition: AlignedBox.h:256
Eigen::AlignedBox::extend
EIGEN_DEVICE_FUNC AlignedBox & extend(const AlignedBox &b)
Definition: AlignedBox.h:246
result
Values result
Definition: OdometryOptimize.cpp:8
Eigen::AlignedBox::transform
EIGEN_DEVICE_FUNC void transform(const Transform< Scalar, AmbientDimAtCompileTime, Mode, Options > &transform)
Definition: AlignedBox.h:339
Eigen::AlignedBox
An axis aligned box.
Definition: ForwardDeclarations.h:292
Eigen::AlignedBox::sample
EIGEN_DEVICE_FUNC VectorType sample() const
Definition: AlignedBox.h:200
Eigen::AlignedBox::BottomLeftFloor
@ BottomLeftFloor
Definition: AlignedBox.h:92
Eigen::PlainObjectBase::setConstant
EIGEN_DEVICE_FUNC Derived & setConstant(Index size, const Scalar &val)
Definition: CwiseNullaryOp.h:361
Eigen::AlignedBox::translate
EIGEN_DEVICE_FUNC AlignedBox & translate(const MatrixBase< Derived > &a_t)
Definition: AlignedBox.h:277
Eigen::internal::true_type
Definition: Meta.h:96
Eigen::AlignedBox::TopLeft
@ TopLeft
Definition: AlignedBox.h:88
Eigen::AlignedBox::Index
Eigen::Index Index
Definition: AlignedBox.h:73
Eigen::AlignedBox::isEmpty
EIGEN_DEVICE_FUNC bool isEmpty() const
Definition: AlignedBox.h:131
Eigen::AlignedBox::dim
EIGEN_DEVICE_FUNC Index dim() const
Definition: AlignedBox.h:121
Eigen::Isometry
@ Isometry
Definition: Constants.h:457
Eigen::AlignedBox::Scalar
_Scalar Scalar
Definition: AlignedBox.h:71
Eigen::AlignedBox::EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE
const EIGEN_DEVICE_FUNC EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(VectorTypeSum, RealScalar, quotient) center() const
Definition: AlignedBox.h:151
Eigen::AlignedBox::ScalarTraits
NumTraits< Scalar > ScalarTraits
Definition: AlignedBox.h:72
Eigen::Dynamic
const int Dynamic
Definition: Constants.h:22
Eigen::all
static const Eigen::internal::all_t all
Definition: IndexedViewHelper.h:171
Eigen::AlignedBox::min
EIGEN_DEVICE_FUNC VectorType &() min()
Definition: AlignedBox.h:144
Eigen::AlignedBox::setNull
EIGEN_DEVICE_FUNC void setNull()
Definition: AlignedBox.h:127
Eigen::AlignedBox::contains
EIGEN_DEVICE_FUNC bool contains(const MatrixBase< Derived > &p) const
Definition: AlignedBox.h:218
Eigen::AlignedBox::VectorType
Matrix< Scalar, AmbientDimAtCompileTime, 1 > VectorType
Definition: AlignedBox.h:76
Eigen::AlignedBox::transform
EIGEN_DEVICE_FUNC void transform(const typename Transform< Scalar, AmbientDimAtCompileTime, Mode, Options >::TranslationType &translation)
Definition: AlignedBox.h:326
Eigen::AlignedBox::diagonal
EIGEN_DEVICE_FUNC CwiseBinaryOp< internal::scalar_difference_op< Scalar, Scalar >, const VectorType, const VectorType > diagonal() const
Definition: AlignedBox.h:170
Eigen::AlignedBox::isNull
EIGEN_DEVICE_FUNC bool isNull() const
Definition: AlignedBox.h:124
Eigen::AlignedBox::BottomRightCeil
@ BottomRightCeil
Definition: AlignedBox.h:94
Eigen::AlignedBox::setEmpty
EIGEN_DEVICE_FUNC void setEmpty()
Definition: AlignedBox.h:135
Eigen::AlignedBox::transformed
EIGEN_DEVICE_FUNC AlignedBox transformed(const Transform< Scalar, AmbientDimAtCompileTime, Mode, Options > &transform) const
Definition: AlignedBox.h:364
Eigen::AlignedBox::extend
EIGEN_DEVICE_FUNC AlignedBox & extend(const MatrixBase< Derived > &p)
Definition: AlignedBox.h:236
Eigen::AlignedBox::Min
@ Min
Definition: AlignedBox.h:83
Eigen::GenericNumTraits< Scalar >::IsInteger
@ IsInteger
Definition: NumTraits.h:155
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
Eigen::AlignedBox::Max
@ Max
Definition: AlignedBox.h:83
Eigen::AlignedBox::AlignedBox
EIGEN_DEVICE_FUNC AlignedBox(const OtherVectorType1 &_min, const OtherVectorType2 &_max)
Definition: AlignedBox.h:111
Eigen::AlignedBox::AlignedBox
EIGEN_DEVICE_FUNC AlignedBox(const AlignedBox< OtherScalarType, AmbientDimAtCompileTime > &other)
Definition: AlignedBox.h:386
EIGEN_MAKE_TYPEDEFS_ALL_SIZES
#define EIGEN_MAKE_TYPEDEFS_ALL_SIZES(Type, TypeSuffix)
Definition: AlignedBox.h:470
Eigen::AlignedBox::BottomLeft
@ BottomLeft
Definition: AlignedBox.h:87
EIGEN_STATIC_ASSERT
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
Definition: StaticAssert.h:127
Eigen::AlignedBox::TopRight
@ TopRight
Definition: AlignedBox.h:88
gtsam::internal::translation
Point3 translation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Definition: slam/expressions.h:84
Eigen::Transform::translation
EIGEN_DEVICE_FUNC ConstTranslationPart translation() const
Definition: Transform.h:404
Eigen::AlignedBox::cast
EIGEN_DEVICE_FUNC internal::cast_return_type< AlignedBox, AlignedBox< NewScalarType, AmbientDimAtCompileTime > >::type cast() const
Definition: AlignedBox.h:378
p
float * p
Definition: Tutorial_Map_using.cpp:9
Eigen::AlignedBox::squaredExteriorDistance
EIGEN_DEVICE_FUNC Scalar squaredExteriorDistance(const MatrixBase< Derived > &p) const
Definition: AlignedBox.h:408
Eigen::AlignedBox::translated
EIGEN_DEVICE_FUNC AlignedBox translated(const MatrixBase< Derived > &a_t) const
Definition: AlignedBox.h:287
Eigen::Translation
Represents a translation transformation.
Definition: ForwardDeclarations.h:291
Eigen::AlignedBox::max
EIGEN_DEVICE_FUNC VectorType &() max()
Definition: AlignedBox.h:148
Eigen::AlignedBox::contains
EIGEN_DEVICE_FUNC bool contains(const AlignedBox &b) const
Definition: AlignedBox.h:225
Eigen::AlignedBox::CornerType
CornerType
Definition: AlignedBox.h:80
EIGEN_CONST_CONDITIONAL
#define EIGEN_CONST_CONDITIONAL(cond)
Definition: Macros.h:1153
Eigen::Matrix< Scalar, AmbientDimAtCompileTime, 1 >
Eigen::AlignedBox::BottomRight
@ BottomRight
Definition: AlignedBox.h:87
Eigen::AlignedBox::TopRightFloor
@ TopRightFloor
Definition: AlignedBox.h:93
Eigen::AlignedBox::AlignedBox
EIGEN_DEVICE_FUNC AlignedBox(const MatrixBase< Derived > &p)
Definition: AlignedBox.h:115
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
Eigen::AffineCompact
@ AffineCompact
Definition: Constants.h:462
Eigen::AlignedBox::AlignedBox
EIGEN_DEVICE_FUNC AlignedBox(Index _dim)
Definition: AlignedBox.h:105
Eigen::AlignedBox::AlignedBox
EIGEN_DEVICE_FUNC AlignedBox()
Definition: AlignedBox.h:101
align_3::t
Point2 t(10, 10)
Eigen::AlignedBox::volume
EIGEN_DEVICE_FUNC Scalar volume() const
Definition: AlignedBox.h:163
Eigen::AlignedBox::VectorTypeSum
CwiseBinaryOp< internal::scalar_sum_op< Scalar >, const VectorType, const VectorType > VectorTypeSum
Definition: AlignedBox.h:77
Eigen::AlignedBox::NonInteger
ScalarTraits::NonInteger NonInteger
Definition: AlignedBox.h:75
Eigen::AlignedBox::sizes
const EIGEN_DEVICE_FUNC CwiseBinaryOp< internal::scalar_difference_op< Scalar, Scalar >, const VectorType, const VectorType > sizes() const
Definition: AlignedBox.h:159
Eigen::AlignedBox::corner
EIGEN_DEVICE_FUNC VectorType corner(CornerType corner) const
Definition: AlignedBox.h:182
Eigen::NumTraits< Scalar >
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
Eigen::AlignedBox::m_max
VectorType m_max
Definition: AlignedBox.h:401
Eigen::AlignedBox::intersects
EIGEN_DEVICE_FUNC bool intersects(const AlignedBox &b) const
Definition: AlignedBox.h:230
Eigen::AlignedBox::exteriorDistance
EIGEN_DEVICE_FUNC NonInteger exteriorDistance(const AlignedBox &b) const
Definition: AlignedBox.h:319
Eigen::AlignedBox::TopLeftFloor
@ TopLeftFloor
Definition: AlignedBox.h:93
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar, Size)
Definition: Memory.h:842
Eigen::AlignedBox::exteriorDistance
EIGEN_DEVICE_FUNC NonInteger exteriorDistance(const MatrixBase< Derived > &p) const
Definition: AlignedBox.h:312
Eigen::GenericNumTraits< Scalar >::Real
Scalar Real
Definition: NumTraits.h:164
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:25