collision_env_bullet.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Jens Petit
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  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jens Petit */
36 
37 #pragma once
38 
42 #include <mutex>
43 
44 namespace collision_detection
45 {
47 class CollisionEnvBullet : public CollisionEnv
48 {
49 public:
50  CollisionEnvBullet() = delete;
51 
52  CollisionEnvBullet(const moveit::core::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0);
53 
54  CollisionEnvBullet(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world, double padding = 0.0,
55  double scale = 1.0);
56 
57  CollisionEnvBullet(const CollisionEnvBullet& other, const WorldPtr& world);
58 
59  ~CollisionEnvBullet() override;
60 
62 
63  void checkSelfCollision(const CollisionRequest& req, CollisionResult& res,
64  const moveit::core::RobotState& state) const override;
65 
66  void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
67  const AllowedCollisionMatrix& acm) const override;
68 
69  void checkRobotCollision(const CollisionRequest& req, CollisionResult& res,
70  const moveit::core::RobotState& state) const override;
71 
72  void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state,
73  const AllowedCollisionMatrix& acm) const override;
74 
75  void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
76  const moveit::core::RobotState& state2) const override;
77 
78  void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const moveit::core::RobotState& state1,
79  const moveit::core::RobotState& state2, const AllowedCollisionMatrix& acm) const override;
80 
81  void distanceSelf(const DistanceRequest& req, DistanceResult& res,
82  const moveit::core::RobotState& state) const override;
83 
84  void distanceRobot(const DistanceRequest& req, DistanceResult& res,
85  const moveit::core::RobotState& state) const override;
86 
87  void setWorld(const WorldPtr& world) override;
88 
89 protected:
92  const collision_detection_bullet::BulletDiscreteBVHManagerPtr& manager) const;
93 
96  void updatedPaddingOrScaling(const std::vector<std::string>& links) override;
97 
100  std::vector<collision_detection_bullet::CollisionObjectWrapperPtr>& cows) const;
101 
104  const moveit::core::RobotState& state, const AllowedCollisionMatrix* acm) const;
105 
107  const moveit::core::RobotState& state1, const moveit::core::RobotState& state2,
108  const AllowedCollisionMatrix* acm) const;
109 
111  const moveit::core::RobotState& state, const AllowedCollisionMatrix* acm) const;
112 
114  void addLinkAsCollisionObject(const urdf::LinkSharedPtr& link);
115 
117  collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_{
119  };
120 
122  collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_{
124  };
125 
126  // Lock manager_ and manager_CCD_, for thread-safe collision tests
127  mutable std::mutex collision_env_mutex_;
128 
130  void addToManager(const World::Object* obj);
131 
137  void updateManagedObject(const std::string& id);
138 
140  std::vector<std::string> active_;
141 
142 private:
144  void notifyObjectChange(const ObjectConstPtr& obj, World::Action action);
145 
146  World::ObserverHandle observer_handle_;
147 };
148 } // namespace collision_detection
collision_detection::CollisionEnvBullet::updateTransformsFromState
void updateTransformsFromState(const moveit::core::RobotState &state, const collision_detection_bullet::BulletDiscreteBVHManagerPtr &manager) const
Updates the poses of the objects in the manager according to given robot state.
Definition: collision_env_bullet.cpp:406
collision_detection::CollisionEnvBullet::checkRobotCollisionHelperCCD
void checkRobotCollisionHelperCCD(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const
Definition: collision_env_bullet.cpp:241
collision_detection::CollisionEnvBullet::CollisionEnvBullet
CollisionEnvBullet()=delete
bullet_cast_bvh_manager.h
collision_detection::CollisionEnvBullet::setWorld
void setWorld(const WorldPtr &world) override
Definition: collision_env_bullet.cpp:331
collision_detection::CollisionEnvBullet::checkSelfCollision
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
Definition: collision_env_bullet.cpp:135
collision_detection_bullet::BulletDiscreteBVHManager
A bounding volume hierarchy (BVH) implementaiton of a discrete bullet manager.
Definition: bullet_discrete_bvh_manager.h:74
collision_detection::CollisionEnvBullet::distanceSelf
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
Definition: collision_env_bullet.cpp:273
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
collision_detection::CollisionEnvBullet::updateManagedObject
void updateManagedObject(const std::string &id)
Updates a managed collision object with its world representation.
Definition: collision_env_bullet.cpp:305
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
collision_detection::CollisionEnvBullet::distanceRobot
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
Definition: collision_env_bullet.cpp:279
collision_detection::CollisionEnvBullet::collision_env_mutex_
std::mutex collision_env_mutex_
Definition: collision_env_bullet.h:191
collision_detection::CollisionEnvBullet::checkSelfCollisionHelper
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkSelfCollision functions into a single function.
Definition: collision_env_bullet.cpp:148
collision_detection::AllowedCollisionMatrix
Definition of a structure for the allowed collision matrix.
Definition: collision_matrix.h:112
collision_detection::CollisionEnvBullet::addLinkAsCollisionObject
void addLinkAsCollisionObject(const urdf::LinkSharedPtr &link)
Construts a bullet collision object out of a robot link.
Definition: collision_env_bullet.cpp:417
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
collision_env.h
collision_detection::CollisionEnvBullet::notifyObjectChange
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Callback function executed for each change to the world environment.
Definition: collision_env_bullet.cpp:349
collision_detection::CollisionEnvBullet::checkRobotCollisionHelper
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Definition: collision_env_bullet.cpp:211
collision_detection::CollisionEnv::ObjectConstPtr
World::ObjectConstPtr ObjectConstPtr
Definition: collision_env.h:279
collision_detection::CollisionEnvBullet::addAttachedOjects
void addAttachedOjects(const moveit::core::RobotState &state, std::vector< collision_detection_bullet::CollisionObjectWrapperPtr > &cows) const
All of the attached objects in the robot state are wrapped into bullet collision objects.
Definition: collision_env_bullet.cpp:363
bullet_discrete_bvh_manager.h
collision_detection::CollisionEnvBullet::updatedPaddingOrScaling
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot l...
Definition: collision_env_bullet.cpp:391
collision_detection::CollisionEnvBullet::manager_CCD_
collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_
Handles continuous robot world collision checks.
Definition: collision_env_bullet.h:186
collision_detection::CollisionEnvBullet::checkRobotCollision
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
Definition: collision_env_bullet.cpp:183
collision_detection::CollisionEnvBullet::~CollisionEnvBullet
~CollisionEnvBullet() override
Definition: collision_env_bullet.cpp:130
collision_detection::DistanceResult
Result of a distance request.
Definition: include/moveit/collision_detection/collision_common.h:357
collision_detection::CollisionEnvBullet::addToManager
void addToManager(const World::Object *obj)
Adds a world object to the collision managers.
Definition: collision_env_bullet.cpp:285
collision_detection::CollisionEnvBullet::active_
std::vector< std::string > active_
The active links where active refers to the group which can collide with everything.
Definition: collision_env_bullet.h:204
collision_detection_bullet::BulletCastBVHManager
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
Definition: bullet_cast_bvh_manager.h:74
collision_detection::DistanceRequest
Representation of a distance-reporting request.
Definition: include/moveit/collision_detection/collision_common.h:241
collision_detection::CollisionEnvBullet::manager_
collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_
Handles self collision checks.
Definition: collision_env_bullet.h:181
collision_detection::CollisionEnvBullet::observer_handle_
World::ObserverHandle observer_handle_
Definition: collision_env_bullet.h:210
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Tue Dec 24 2024 03:27:14