moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
26#include <geometric_shapes/shapes.h>
27#include <unordered_map>
28#include <vector>
29#include <memory>
30#include <functional>
31#include <map>
33
35{
36template <typename T>
37using AlignedVector = std::vector<T, Eigen::aligned_allocator<T>>;
38
39template <typename Key, typename Value>
40using AlignedMap = std::map<Key, Value, std::less<Key>, Eigen::aligned_allocator<std::pair<const Key, Value>>>;
41
42template <typename Key, typename Value>
43using AlignedUnorderedMap = std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>,
44 Eigen::aligned_allocator<std::pair<const Key, Value>>>;
45
47{
48 USE_SHAPE_TYPE = 0,
50 // all of the following convert the meshes to custom collision objects
51 CONVEX_HULL = 1,
53 MULTI_SPHERE = 2,
54 SDF = 3
55};
56
82
83} // namespace collision_detection_bullet
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Definition basic_types.h:37
std::map< Key, Value, std::less< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > > > AlignedMap
Definition basic_types.h:40
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:44
@ MULTI_SPHERE
Use the mesh and represent it by multiple spheres collision object.
@ SDF
Use the mesh and rpresent it by a signed distance fields collision object.
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
Representation of a collision checking request.
Representation of a collision checking result.
Bundles the data for a collision query.
Definition basic_types.h:59
const collision_detection::CollisionRequest & req
Definition basic_types.h:74
const double & contact_distance
If after a positive broadphase check the distance is below this threshold, a contact is added.
Definition basic_types.h:71
bool done
Indicates if search is finished.
Definition basic_types.h:77
collision_detection::CollisionResult & res
Definition basic_types.h:73
const std::vector< std::string > & active
Definition basic_types.h:68
bool pair_done
Indicates if search between a single pair is finished.
Definition basic_types.h:80
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:62