Go to the documentation of this file.
24 #include <Eigen/Geometry>
25 #include <Eigen/StdVector>
27 #include <unordered_map>
37 using AlignedVector = std::vector<T, Eigen::aligned_allocator<T>>;
39 template <
typename Key,
typename Value>
40 using AlignedMap = std::map<Key, Value, std::less<Key>, Eigen::aligned_allocator<std::pair<const Key, Value>>>;
42 template <
typename Key,
typename Value>
43 using AlignedUnorderedMap = std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>,
44 Eigen::aligned_allocator<std::pair<const Key, Value>>>;
60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 const std::vector<std::string>&
active;
@ SDF
Use the mesh and rpresent it by a signed distance fields collision object.
std::map< Key, Value, std::less< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >> AlignedMap
Representation of a collision checking request.
Representation of a collision checking result.
std::unordered_map< Key, Value, std::hash< Key >, std::equal_to< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >> AlignedUnorderedMap
@ MULTI_SPHERE
Use the mesh and represent it by multiple spheres collision object.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Mon May 27 2024 02:26:53