basic_types.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (Apache License)
3  *
4  * Copyright (c) 2013, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  *********************************************************************/
18 
19 /* Author: Levi Armstrong */
20 
21 #pragma once
22 
23 #include <Eigen/Core>
24 #include <Eigen/Geometry>
25 #include <Eigen/StdVector>
27 #include <unordered_map>
28 #include <vector>
29 #include <memory>
30 #include <functional>
31 #include <map>
33 
35 {
36 template <typename T>
37 using AlignedVector = std::vector<T, Eigen::aligned_allocator<T>>;
38 
39 template <typename Key, typename Value>
40 using AlignedMap = std::map<Key, Value, std::less<Key>, Eigen::aligned_allocator<std::pair<const Key, Value>>>;
41 
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>>>;
45 
46 enum class CollisionObjectType
47 {
48  USE_SHAPE_TYPE = 0,
50  // all of the following convert the meshes to custom collision objects
51  CONVEX_HULL = 1,
54  SDF = 3
55 };
56 
58 struct ContactTestData
59 {
60  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 
62  ContactTestData(const std::vector<std::string>& active, const double& contact_distance,
65  {
66  }
67 
68  const std::vector<std::string>& active;
69 
71  const double& contact_distance;
72 
75 
77  bool done;
78 
80  bool pair_done;
81 };
82 
83 } // namespace collision_detection_bullet
collision_detection_bullet::ContactTestData::pair_done
bool pair_done
Indicates if search between a single pair is finished.
Definition: basic_types.h:96
collision_detection_bullet::ContactTestData::ContactTestData
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ContactTestData(const std::vector< std::string > &active, const double &contact_distance, collision_detection::CollisionResult &res, const collision_detection::CollisionRequest &req)
Definition: basic_types.h:78
collision_detection_bullet
Definition: basic_types.h:34
collision_detection_bullet::CollisionObjectType::SDF
@ SDF
Use the mesh and rpresent it by a signed distance fields collision object.
collision_detection_bullet::CollisionObjectType
CollisionObjectType
Definition: basic_types.h:62
collision_detection_bullet::AlignedMap
std::map< Key, Value, std::less< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >> AlignedMap
Definition: basic_types.h:56
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
collision_common.h
collision_detection_bullet::ContactTestData::contact_distance
const double & contact_distance
If after a positive broadphase check the distance is below this threshold, a contact is added.
Definition: basic_types.h:87
collision_detection_bullet::ContactTestData::res
collision_detection::CollisionResult & res
Definition: basic_types.h:89
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
collision_detection_bullet::AlignedUnorderedMap
std::unordered_map< Key, Value, std::hash< Key >, std::equal_to< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >> AlignedUnorderedMap
Definition: basic_types.h:60
shapes.h
collision_detection_bullet::ContactTestData::req
const collision_detection::CollisionRequest & req
Definition: basic_types.h:90
collision_detection_bullet::ContactTestData::done
bool done
Indicates if search is finished.
Definition: basic_types.h:93
collision_detection_bullet::CollisionObjectType::MULTI_SPHERE
@ MULTI_SPHERE
Use the mesh and represent it by multiple spheres collision object.
collision_detection_bullet::AlignedVector
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Definition: basic_types.h:53
collision_detection_bullet::CollisionObjectType::CONVEX_HULL
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
collision_detection_bullet::CollisionObjectType::USE_SHAPE_TYPE
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
collision_detection_bullet::ContactTestData::active
const std::vector< std::string > & active
Definition: basic_types.h:84
collision_detection_bullet::ContactTestData
Bundles the data for a collision query.
Definition: basic_types.h:74


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:40