DART  6.6.2
BackwardCompatibility.hpp File Reference
#include "dart/config.hpp"
#include <Eigen/Dense>
#include <fcl/config.h>
#include <fcl/math/vec_3f.h>
#include <fcl/math/matrix_3f.h>
#include <fcl/math/transform.h>
#include <fcl/BV/OBBRSS.h>
#include <fcl/BVH/BVH_model.h>
#include <fcl/collision.h>
#include <fcl/collision_data.h>
#include <fcl/collision_object.h>
#include <fcl/distance.h>
#include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
#include <boost/weak_ptr.hpp>
#include <boost/make_shared.hpp>

Go to the source code of this file.

Namespaces

 dart
 
 dart::collision
 
 dart::collision::fcl
 

Macros

#define FCL_VERSION_AT_LEAST(x, y, z)
 
#define FCL_MAJOR_MINOR_VERSION_AT_MOST(x, y)
 

Typedefs

template<class T >
using fcl_shared_ptr = boost::shared_ptr< T >
 
template<class T >
using fcl_weak_ptr = boost::weak_ptr< T >
 
using dart::collision::fcl::Vector3 = ::fcl::Vec3f
 
using dart::collision::fcl::Matrix3 = ::fcl::Matrix3f
 
using dart::collision::fcl::Transform3 = ::fcl::Transform3f
 
using dart::collision::fcl::Box = ::fcl::Box
 
using dart::collision::fcl::Cylinder = ::fcl::Cylinder
 
using dart::collision::fcl::Halfspace = ::fcl::Halfspace
 
using dart::collision::fcl::Sphere = ::fcl::Sphere
 
using dart::collision::fcl::CollisionObject = ::fcl::CollisionObject
 
using dart::collision::fcl::CollisionGeometry = ::fcl::CollisionGeometry
 
using dart::collision::fcl::DynamicAABBTreeCollisionManager = ::fcl::DynamicAABBTreeCollisionManager
 
using dart::collision::fcl::OBBRSS = ::fcl::OBBRSS
 
using dart::collision::fcl::CollisionRequest = ::fcl::CollisionRequest
 
using dart::collision::fcl::CollisionResult = ::fcl::CollisionResult
 
using dart::collision::fcl::DistanceRequest = ::fcl::DistanceRequest
 
using dart::collision::fcl::DistanceResult = ::fcl::DistanceResult
 
using dart::collision::fcl::Contact = ::fcl::Contact
 

Functions

template<class T , class... Args>
fcl_shared_ptr< T > fcl_make_shared (Args &&... args)
 
double dart::collision::fcl::length (const dart::collision::fcl::Vector3 &t)
 Returns norm of a 3-dim vector. More...
 
double dart::collision::fcl::length2 (const dart::collision::fcl::Vector3 &t)
 Returns squared norm of a 3-dim vector. More...
 
dart::collision::fcl::Vector3 dart::collision::fcl::getTranslation (const dart::collision::fcl::Transform3 &T)
 Returns translation component of a transform. More...
 
void dart::collision::fcl::setTranslation (dart::collision::fcl::Transform3 &T, const dart::collision::fcl::Vector3 &t)
 Sets translation component of a transform. More...
 
dart::collision::fcl::Matrix3 dart::collision::fcl::getRotation (const dart::collision::fcl::Transform3 &T)
 Returns rotation component of a transform. More...
 
void dart::collision::fcl::setRotation (dart::collision::fcl::Transform3 &T, const dart::collision::fcl::Matrix3 &R)
 Sets rotation component of a transform. More...
 
void dart::collision::fcl::setEulerZYX (dart::collision::fcl::Matrix3 &rot, double eulerX, double eulerY, double eulerZ)
 Sets a rotation matrix given Euler-XYZ angles. More...
 
dart::collision::fcl::Vector3 dart::collision::fcl::transform (const dart::collision::fcl::Transform3 &t, const dart::collision::fcl::Vector3 &v)
 Transforms a 3-dim vector by a transform and returns the result. More...
 

Macro Definition Documentation

◆ FCL_MAJOR_MINOR_VERSION_AT_MOST

#define FCL_MAJOR_MINOR_VERSION_AT_MOST (   x,
 
)
Value:
(FCL_MAJOR_VERSION < x || (FCL_MAJOR_VERSION <= x && \
(FCL_MINOR_VERSION < y || (FCL_MINOR_VERSION <= y))))

◆ FCL_VERSION_AT_LEAST

#define FCL_VERSION_AT_LEAST (   x,
  y,
 
)
Value:
(FCL_MAJOR_VERSION > x || (FCL_MAJOR_VERSION >= x && \
(FCL_MINOR_VERSION > y || (FCL_MINOR_VERSION >= y && \
FCL_PATCH_VERSION >= z))))

Typedef Documentation

◆ fcl_shared_ptr

template<class T >
using fcl_shared_ptr = boost::shared_ptr<T>

◆ fcl_weak_ptr

template<class T >
using fcl_weak_ptr = boost::weak_ptr<T>

Function Documentation

◆ fcl_make_shared()

template<class T , class... Args>
fcl_shared_ptr<T> fcl_make_shared ( Args &&...  args)