moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
bullet_cast_bvh_manager.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD-2-Clause)
3 *
4 * Copyright (c) 2017, Southwest Research Institute
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 *
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 *********************************************************************/
31
32/* Author: Levi Armstrong, Jens Petit */
33
35
36#include <rclcpp/logger.hpp>
37#include <rclcpp/logging.hpp>
38#include <map>
39#include <utility>
41
43{
44BulletCastBVHManagerPtr BulletCastBVHManager::clone() const
45{
46 BulletCastBVHManagerPtr manager = std::make_shared<BulletCastBVHManager>();
47
48 for (const std::pair<const std::string, collision_detection_bullet::CollisionObjectWrapperPtr>& cow : link2cow_)
49 {
50 CollisionObjectWrapperPtr new_cow = cow.second->clone();
51
52 assert(new_cow->getCollisionShape());
53 assert(new_cow->getCollisionShape()->getShapeType() != CUSTOM_CONVEX_SHAPE_TYPE);
54
55 new_cow->setWorldTransform(cow.second->getWorldTransform());
56 new_cow->setContactProcessingThreshold(static_cast<btScalar>(contact_distance_));
57 manager->addCollisionObject(new_cow);
58 }
59
60 manager->setActiveCollisionObjects(active_);
61 manager->setContactDistanceThreshold(contact_distance_);
62
63 return manager;
64}
65
66void BulletCastBVHManager::setCastCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose1,
67 const Eigen::Isometry3d& pose2)
68{
69 // TODO: Find a way to remove this check. Need to store information in Tesseract EnvState indicating transforms with
70 // geometry
71 auto it = link2cow_.find(name);
72 if (it != link2cow_.end())
73 {
74 CollisionObjectWrapperPtr& cow = it->second;
75 assert(cow->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter);
76
77 btTransform tf1 = convertEigenToBt(pose1);
78 btTransform tf2 = convertEigenToBt(pose2);
79
80 cow->setWorldTransform(tf1);
81 link2cow_[name]->setWorldTransform(tf1);
82
83 // If collision object is disabled don't proceed
84 if (cow->m_enabled)
85 {
86 if (btBroadphaseProxy::isConvex(cow->getCollisionShape()->getShapeType()))
87 {
88 static_cast<CastHullShape*>(cow->getCollisionShape())->updateCastTransform(tf1.inverseTimes(tf2));
89 }
90 else if (btBroadphaseProxy::isCompound(cow->getCollisionShape()->getShapeType()))
91 {
92 btCompoundShape* compound = static_cast<btCompoundShape*>(cow->getCollisionShape());
93
94 for (int i = 0; i < compound->getNumChildShapes(); ++i)
95 {
96 if (btBroadphaseProxy::isConvex(compound->getChildShape(i)->getShapeType()))
97 {
98 const btTransform& local_tf = compound->getChildTransform(i);
99
100 btTransform delta_tf = (tf1 * local_tf).inverseTimes(tf2 * local_tf);
101 static_cast<CastHullShape*>(compound->getChildShape(i))->updateCastTransform(delta_tf);
102 compound->updateChildTransform(i, local_tf, false); // This is required to update the BVH tree
103 }
104 else if (btBroadphaseProxy::isCompound(compound->getChildShape(i)->getShapeType()))
105 {
106 btCompoundShape* second_compound = static_cast<btCompoundShape*>(compound->getChildShape(i));
107
108 for (int j = 0; j < second_compound->getNumChildShapes(); ++j)
109 {
110 assert(!btBroadphaseProxy::isCompound(second_compound->getChildShape(j)->getShapeType()));
111 const btTransform& local_tf = second_compound->getChildTransform(j);
112
113 btTransform delta_tf = (tf1 * local_tf).inverseTimes(tf2 * local_tf);
114 static_cast<CastHullShape*>(second_compound->getChildShape(j))->updateCastTransform(delta_tf);
115 second_compound->updateChildTransform(j, local_tf, false); // This is required to update the BVH tree
116 }
117 second_compound->recalculateLocalAabb();
118 }
119 }
120 compound->recalculateLocalAabb();
121 }
122 else
123 {
124 RCLCPP_ERROR_STREAM(getLogger(), "I can only continuous collision check convex shapes and "
125 "compound shapes made of convex shapes");
126 throw std::runtime_error(
127 "I can only continuous collision check convex shapes and compound shapes made of convex shapes");
128 }
129
130 // Now update Broadphase AABB (See BulletWorld updateSingleAabb function)
132 }
133 }
134}
135
138 const collision_detection::AllowedCollisionMatrix* acm, bool /*self*/ = false)
139{
140 ContactTestData cdata(active_, contact_distance_, collisions, req);
141 broadphase_->calculateOverlappingPairs(dispatcher_.get());
142 btOverlappingPairCache* pair_cache = broadphase_->getOverlappingPairCache();
143
144 RCLCPP_DEBUG_STREAM(getLogger(), "Number overlapping candidates " << pair_cache->getNumOverlappingPairs());
145
146 BroadphaseContactResultCallback cc(cdata, contact_distance_, acm, false, true);
147 TesseractCollisionPairCallback collision_callback(dispatch_info_, dispatcher_.get(), cc);
148 pair_cache->processAllOverlappingPairs(&collision_callback, dispatcher_.get());
149}
150
151void BulletCastBVHManager::addCollisionObject(const CollisionObjectWrapperPtr& cow)
152{
153 std::string name = cow->getName();
154 if (cow->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter)
155 {
156 CollisionObjectWrapperPtr cast_cow = makeCastCollisionObject(cow);
157 link2cow_[name] = cast_cow;
158 }
159 else
160 {
161 link2cow_[name] = cow;
162 }
163
164 btVector3 aabb_min, aabb_max;
165 link2cow_[name]->getAABB(aabb_min, aabb_max);
166
167 int type = link2cow_[name]->getCollisionShape()->getShapeType();
168 link2cow_[name]->setBroadphaseHandle(
169 broadphase_->createProxy(aabb_min, aabb_max, type, link2cow_[name].get(), link2cow_[name]->m_collisionFilterGroup,
170 link2cow_[name]->m_collisionFilterMask, dispatcher_.get()));
171}
172
173} // namespace collision_detection_bullet
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::vector< std::string > active_
A list of the active collision links.
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
double contact_distance_
The contact distance threshold.
std::map< std::string, CollisionObjectWrapperPtr > link2cow_
A map of collision objects being managed.
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collision algorithm.
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's transforms.
void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
Perform a contact test for all objects.
BulletCastBVHManagerPtr clone() const
Clone the manager.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
A callback function that is called as part of the broadphase collision checking.
btVector3 convertEigenToBt(const Eigen::Vector3d &v)
Converts eigen vector to bullet vector.
CollisionObjectWrapperPtr makeCastCollisionObject(const CollisionObjectWrapperPtr &cow)
void updateBroadphaseAABB(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Update the Broadphase AABB for the input collision object.
Representation of a collision checking request.
Representation of a collision checking result.
Callback structure for both discrete and continuous broadphase collision pair.
Casted collision shape used for checking if an object is collision free between two discrete poses.
Bundles the data for a collision query.
Definition basic_types.h:59