moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
44namespace collision_detection
45{
48{
49public:
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
64 const moveit::core::RobotState& state) const override;
65
67 const AllowedCollisionMatrix& acm) const override;
68
70 const moveit::core::RobotState& state) const override;
71
73 const AllowedCollisionMatrix& acm) const override;
74
76 const moveit::core::RobotState& state2) const override;
77
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
89protected:
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
142private:
144 void notifyObjectChange(const ObjectConstPtr& obj, World::Action action);
145
146 World::ObserverHandle observer_handle_;
147};
148} // namespace collision_detection
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_
Handles continuous robot world collision checks.
void setWorld(const WorldPtr &world) override
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.
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.
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...
std::vector< std::string > active_
The active links where active refers to the group which can collide with everything.
void checkRobotCollisionHelperCCD(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const
void addAttachedObjects(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.
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
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...
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,...
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.
CollisionEnvBullet(CollisionEnvBullet &)=delete
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
void addLinkAsCollisionObject(const urdf::LinkSharedPtr &link)
Construts a bullet collision object out of a robot link.
collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_
Handles self collision checks.
void updateManagedObject(const std::string &id)
Updates a managed collision object with its world representation.
void addToManager(const World::Object *obj)
Adds a world object to the collision managers.
Provides the interface to the individual collision checking libraries.
World::ObjectConstPtr ObjectConstPtr
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition world.h:268
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
A bounding volume hierarchy (BVH) implementation of a discrete bullet manager.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
Representation of a collision checking request.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.
A representation of an object.
Definition world.h:79