28#ifndef TESSERACT_COLLISION_CONTINUOUS_CONTACT_MANAGER_H
29#define TESSERACT_COLLISION_CONTINUOUS_CONTACT_MANAGER_H
43 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 using Ptr = std::shared_ptr<ContinuousContactManager>;
46 using ConstPtr = std::shared_ptr<const ContinuousContactManager>;
47 using UPtr = std::unique_ptr<ContinuousContactManager>;
48 using ConstUPtr = std::unique_ptr<const ContinuousContactManager>;
92 bool enabled =
true) = 0;
174 const Eigen::Isometry3d&
pose1,
175 const Eigen::Isometry3d&
pose2) = 0;
247 const std::string& name2,
248 double collision_margin) = 0;
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:74
tesseract_collision::CollisionCheckConfig config(5, request, tesseract_collision::CollisionEvaluatorType::LVS_DISCRETE, 0.5)
Definition: tesseract_common_serialization_unit.cpp:154
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
Definition: bullet_cast_bvh_manager.h:49
std::vector< tesseract_geometry::Geometry::ConstPtr > CollisionShapesConst
Definition: types.h:47
std::function< bool(const std::string &, const std::string &)> IsContactAllowedFn
Should return true if contact allowed, otherwise false.
Definition: types.h:59
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
Definition: types.h:62
CollisionMarginOverrideType
Identifies how the provided contact margin data should be applied.
Definition: collision_margin_data.h:46
Tesseracts Collision Common Types.
auto pose2
Definition: tesseract_environment_collision.cpp:155
auto pose
Definition: tesseract_environment_collision.cpp:118
auto pose1
Definition: tesseract_environment_collision.cpp:153
m name
Definition: tesseract_scene_graph_link_unit.cpp:77