#include <collision_env_bullet.h>
Public Member Functions | |
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 the world are considered. Self collisions are not checked. More... | |
void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override |
Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked. More... | |
void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const override |
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked. More... | |
void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix &acm) const override |
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked. More... | |
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, NO collisions are ignored. More... | |
void | checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override |
Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More... | |
CollisionEnvBullet ()=delete | |
CollisionEnvBullet (CollisionEnvBullet &)=delete | |
CollisionEnvBullet (const CollisionEnvBullet &other, const WorldPtr &world) | |
CollisionEnvBullet (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0) | |
CollisionEnvBullet (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0) | |
void | distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override |
Compute the distance between a robot and the world. More... | |
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. More... | |
void | setWorld (const WorldPtr &world) override |
~CollisionEnvBullet () override | |
Public Member Functions inherited from collision_detection::CollisionEnv | |
virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const |
Check whether the robot model is in collision with itself or the world at a particular state. Any collision between any pair of links is checked for, NO collisions are ignored. More... | |
virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const |
Check whether the robot model is in collision with itself or the world at a particular state. Allowed collisions specified by the allowed collision matrix are taken into account. More... | |
CollisionEnv ()=delete | |
CollisionEnv (const CollisionEnv &other, const WorldPtr &world) | |
Copy constructor. More... | |
CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0) | |
Constructor. More... | |
CollisionEnv (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0) | |
Constructor. More... | |
double | distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const |
Compute the shortest distance between a robot and the world. More... | |
double | distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const |
Compute the shortest distance between a robot and the world. More... | |
double | distanceSelf (const moveit::core::RobotState &state) const |
The distance to self-collision given the robot is at state state. More... | |
double | distanceSelf (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const |
The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by. More... | |
const std::map< std::string, double > & | getLinkPadding () const |
Get the link paddings as a map (from link names to padding value) More... | |
double | getLinkPadding (const std::string &link_name) const |
Get the link padding for a particular link. More... | |
const std::map< std::string, double > & | getLinkScale () const |
Get the link scaling as a map (from link names to scale value) More... | |
double | getLinkScale (const std::string &link_name) const |
Set the scaling for a particular link. More... | |
void | getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const |
Get the link padding as a vector of messages. More... | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
The kinematic model corresponding to this collision model. More... | |
void | getScale (std::vector< moveit_msgs::LinkScale > &scale) const |
Get the link scaling as a vector of messages. More... | |
const WorldPtr & | getWorld () |
const WorldConstPtr & | getWorld () const |
void | setLinkPadding (const std::map< std::string, double > &padding) |
Set the link paddings using a map (from link names to padding value) More... | |
void | setLinkPadding (const std::string &link_name, double padding) |
Set the link padding for a particular link. More... | |
void | setLinkScale (const std::map< std::string, double > &scale) |
Set the link scaling using a map (from link names to scale value) More... | |
void | setLinkScale (const std::string &link_name, double scale) |
Set the scaling for a particular link. More... | |
void | setPadding (const std::vector< moveit_msgs::LinkPadding > &padding) |
Set the link padding from a vector of messages. More... | |
void | setPadding (double padding) |
Set the link padding (for every link) More... | |
void | setScale (const std::vector< moveit_msgs::LinkScale > &scale) |
Set the link scaling from a vector of messages. More... | |
void | setScale (double scale) |
Set the link scaling (for every link) More... | |
virtual | ~CollisionEnv () |
Protected Member Functions | |
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. More... | |
void | addLinkAsCollisionObject (const urdf::LinkSharedPtr &link) |
Construts a bullet collision object out of a robot link. More... | |
void | addToManager (const World::Object *obj) |
Adds a world object to the collision managers. More... | |
void | checkRobotCollisionHelper (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const |
void | checkRobotCollisionHelperCCD (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const |
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. More... | |
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 links. More... | |
void | updateManagedObject (const std::string &id) |
Updates a managed collision object with its world representation. More... | |
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. More... | |
Protected Attributes | |
std::vector< std::string > | active_ |
The active links where active refers to the group which can collide with everything. More... | |
std::mutex | collision_env_mutex_ |
collision_detection_bullet::BulletDiscreteBVHManagerPtr | manager_ |
Handles self collision checks. More... | |
collision_detection_bullet::BulletCastBVHManagerPtr | manager_CCD_ |
Handles continuous robot world collision checks. More... | |
Protected Attributes inherited from collision_detection::CollisionEnv | |
std::map< std::string, double > | link_padding_ |
The internally maintained map (from link names to padding) More... | |
std::map< std::string, double > | link_scale_ |
The internally maintained map (from link names to scaling) More... | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model corresponding to this collision model. More... | |
Private Member Functions | |
void | notifyObjectChange (const ObjectConstPtr &obj, World::Action action) |
Callback function executed for each change to the world environment. More... | |
Private Attributes | |
World::ObserverHandle | observer_handle_ |
Additional Inherited Members | |
Public Types inherited from collision_detection::CollisionEnv | |
using | ObjectConstPtr = World::ObjectConstPtr |
using | ObjectPtr = World::ObjectPtr |
Definition at line 79 of file collision_env_bullet.h.
|
delete |
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const moveit::core::RobotModelConstPtr & | model, |
double | padding = 0.0 , |
||
double | scale = 1.0 |
||
) |
Definition at line 85 of file collision_env_bullet.cpp.
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const moveit::core::RobotModelConstPtr & | model, |
const WorldPtr & | world, | ||
double | padding = 0.0 , |
||
double | scale = 1.0 |
||
) |
Definition at line 98 of file collision_env_bullet.cpp.
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const CollisionEnvBullet & | other, |
const WorldPtr & | world | ||
) |
Definition at line 114 of file collision_env_bullet.cpp.
|
override |
Definition at line 130 of file collision_env_bullet.cpp.
|
delete |
|
protected |
All of the attached objects in the robot state are wrapped into bullet collision objects.
Definition at line 363 of file collision_env_bullet.cpp.
|
protected |
Construts a bullet collision object out of a robot link.
Definition at line 417 of file collision_env_bullet.cpp.
|
protected |
Adds a world object to the collision managers.
Definition at line 285 of file collision_env_bullet.cpp.
|
overridevirtual |
Check whether the robot model is in collision with the world. Any collisions between a robot link and the world are considered. Self collisions are not checked.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
robot | The collision model for the robot |
state | The kinematic state for which checks are being made |
Implements collision_detection::CollisionEnv.
Definition at line 183 of file collision_env_bullet.cpp.
|
overridevirtual |
Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
robot | The collision model for the robot |
state | The kinematic state for which checks are being made |
acm | The allowed collision matrix. |
Implements collision_detection::CollisionEnv.
Definition at line 189 of file collision_env_bullet.cpp.
|
overridevirtual |
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
state1 | The kinematic state at the start of the segment for which checks are being made |
state2 | The kinematic state at the end of the segment for which checks are being made |
Implements collision_detection::CollisionEnv.
Definition at line 196 of file collision_env_bullet.cpp.
|
overridevirtual |
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
state1 | The kinematic state at the start of the segment for which checks are being made |
state2 | The kinematic state at the end of the segment for which checks are being made |
acm | The allowed collision matrix. |
Implements collision_detection::CollisionEnv.
Definition at line 203 of file collision_env_bullet.cpp.
|
protected |
Definition at line 211 of file collision_env_bullet.cpp.
|
protected |
Definition at line 241 of file collision_env_bullet.cpp.
|
overridevirtual |
Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are ignored.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
state | The kinematic state for which checks are being made |
Implements collision_detection::CollisionEnv.
Definition at line 135 of file collision_env_bullet.cpp.
|
overridevirtual |
Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.
req | A CollisionRequest object that encapsulates the collision request |
res | A CollisionResult object that encapsulates the collision result |
state | The kinematic state for which checks are being made |
acm | The allowed collision matrix. |
Implements collision_detection::CollisionEnv.
Definition at line 141 of file collision_env_bullet.cpp.
|
protected |
Bundles the different checkSelfCollision functions into a single function.
Definition at line 148 of file collision_env_bullet.cpp.
|
overridevirtual |
Compute the distance between a robot and the world.
req | A DistanceRequest object that encapsulates the distance request |
res | A DistanceResult object that encapsulates the distance result |
state | The state for the robot to check distances from |
Implements collision_detection::CollisionEnv.
Definition at line 279 of file collision_env_bullet.cpp.
|
overridevirtual |
The distance to self-collision given the robot is at state state.
req | A DistanceRequest object that encapsulates the distance request |
res | A DistanceResult object that encapsulates the distance result |
state | The state of this robot to consider |
Implements collision_detection::CollisionEnv.
Definition at line 273 of file collision_env_bullet.cpp.
|
private |
Callback function executed for each change to the world environment.
Definition at line 349 of file collision_env_bullet.cpp.
|
overridevirtual |
set the world to use. This can be expensive unless the new and old world are empty. Passing NULL will result in a new empty world being created.
Reimplemented from collision_detection::CollisionEnv.
Definition at line 331 of file collision_env_bullet.cpp.
|
overrideprotectedvirtual |
Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot links.
Reimplemented from collision_detection::CollisionEnv.
Definition at line 391 of file collision_env_bullet.cpp.
|
protected |
Updates a managed collision object with its world representation.
We have three cases: 1) the object is part of the manager and not of world --> delete it 2) the object is not in the manager, therefore register to manager, 3) the object is in the manager then delete and add the modified
Definition at line 305 of file collision_env_bullet.cpp.
|
protected |
Updates the poses of the objects in the manager according to given robot state.
Definition at line 406 of file collision_env_bullet.cpp.
|
protected |
The active links where active refers to the group which can collide with everything.
Definition at line 204 of file collision_env_bullet.h.
|
mutableprotected |
Definition at line 191 of file collision_env_bullet.h.
|
protected |
Handles self collision checks.
Definition at line 181 of file collision_env_bullet.h.
|
protected |
Handles continuous robot world collision checks.
Definition at line 186 of file collision_env_bullet.h.
|
private |
Definition at line 210 of file collision_env_bullet.h.