moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
collision_detection::CollisionEnvBullet Class Reference


More...

#include <collision_env_bullet.h>

Inheritance diagram for collision_detection::CollisionEnvBullet:
Inheritance graph
[legend]
Collaboration diagram for collision_detection::CollisionEnvBullet:
Collaboration graph
[legend]

Public Member Functions

 CollisionEnvBullet ()=delete
 
 CollisionEnvBullet (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 
 CollisionEnvBullet (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0)
 
 CollisionEnvBullet (const CollisionEnvBullet &other, const WorldPtr &world)
 
 ~CollisionEnvBullet () override
 
 CollisionEnvBullet (CollisionEnvBullet &)=delete
 
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...
 
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 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 distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
 Compute the distance between a robot and the world. More...
 
void setWorld (const WorldPtr &world) override
 
- Public Member Functions inherited from collision_detection::CollisionEnv
 CollisionEnv ()=delete
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionEnv (const CollisionEnv &other, const WorldPtr &world)
 Copy constructor. More...
 
virtual ~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...
 
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 acm) 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...
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 The kinematic model corresponding to this collision model. More...
 
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding for a particular link. More...
 
double getLinkPadding (const std::string &link_name) const
 Get the link padding for a particular link. More...
 
void setLinkPadding (const std::map< std::string, double > &padding)
 Set the link paddings using a map (from link names to padding value) More...
 
const std::map< std::string, double > & getLinkPadding () const
 Get the link paddings as a map (from link names to padding value) More...
 
void setLinkScale (const std::string &link_name, double scale)
 Set the scaling for a particular link. More...
 
double getLinkScale (const std::string &link_name) const
 Set the scaling 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...
 
const std::map< std::string, double > & getLinkScale () const
 Get the link scaling as a map (from link names to scale value) More...
 
void setPadding (double padding)
 Set the link padding (for every link) More...
 
void setScale (double scale)
 Set the link scaling (for every link) More...
 
void setPadding (const std::vector< moveit_msgs::msg::LinkPadding > &padding)
 Set the link padding from a vector of messages. More...
 
void getPadding (std::vector< moveit_msgs::msg::LinkPadding > &padding) const
 Get the link padding as a vector of messages. More...
 
void setScale (const std::vector< moveit_msgs::msg::LinkScale > &scale)
 Set the link scaling from a vector of messages. More...
 
void getScale (std::vector< moveit_msgs::msg::LinkScale > &scale) const
 Get the link scaling as a vector of messages. More...
 

Protected Member Functions

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...
 
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 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 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 checkRobotCollisionHelperCCD (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const
 
void checkRobotCollisionHelper (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
 
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 updateManagedObject (const std::string &id)
 Updates a managed collision object with its world representation. More...
 

Protected Attributes

collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_
 Handles self collision checks. More...
 
collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_
 Handles continuous robot world collision checks. More...
 
std::mutex collision_env_mutex_
 
std::vector< std::string > active_
 The active links where active refers to the group which can collide with everything. More...
 
- Protected Attributes inherited from collision_detection::CollisionEnv
moveit::core::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model. More...
 
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...
 

Additional Inherited Members

- Public Types inherited from collision_detection::CollisionEnv
using ObjectPtr = World::ObjectPtr
 
using ObjectConstPtr = World::ObjectConstPtr
 

Detailed Description


Definition at line 47 of file collision_env_bullet.h.

Constructor & Destructor Documentation

◆ CollisionEnvBullet() [1/5]

collision_detection::CollisionEnvBullet::CollisionEnvBullet ( )
delete

◆ CollisionEnvBullet() [2/5]

collision_detection::CollisionEnvBullet::CollisionEnvBullet ( const moveit::core::RobotModelConstPtr &  model,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 52 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ CollisionEnvBullet() [3/5]

collision_detection::CollisionEnvBullet::CollisionEnvBullet ( const moveit::core::RobotModelConstPtr &  model,
const WorldPtr &  world,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 65 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ CollisionEnvBullet() [4/5]

collision_detection::CollisionEnvBullet::CollisionEnvBullet ( const CollisionEnvBullet other,
const WorldPtr &  world 
)

Definition at line 81 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ ~CollisionEnvBullet()

collision_detection::CollisionEnvBullet::~CollisionEnvBullet ( )
override

Definition at line 97 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ CollisionEnvBullet() [5/5]

collision_detection::CollisionEnvBullet::CollisionEnvBullet ( CollisionEnvBullet )
delete

Member Function Documentation

◆ addAttachedOjects()

void collision_detection::CollisionEnvBullet::addAttachedOjects ( const moveit::core::RobotState state,
std::vector< collision_detection_bullet::CollisionObjectWrapperPtr > &  cows 
) const
protected

All of the attached objects in the robot state are wrapped into bullet collision objects.

Definition at line 330 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ addLinkAsCollisionObject()

void collision_detection::CollisionEnvBullet::addLinkAsCollisionObject ( const urdf::LinkSharedPtr &  link)
protected

Construts a bullet collision object out of a robot link.

Definition at line 384 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ addToManager()

void collision_detection::CollisionEnvBullet::addToManager ( const World::Object obj)
protected

Adds a world object to the collision managers.

Definition at line 252 of file collision_env_bullet.cpp.

Here is the caller graph for this function:

◆ checkRobotCollision() [1/4]

void collision_detection::CollisionEnvBullet::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result @robot robot The collision model for the robot
stateThe kinematic state for which checks are being made

Implements collision_detection::CollisionEnv.

Definition at line 150 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [2/4]

void collision_detection::CollisionEnvBullet::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
overridevirtual

Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result @robot robot The collision model for the robot
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionEnv.

Definition at line 156 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [3/4]

void collision_detection::CollisionEnvBullet::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result @robot robot The collision model for the robot
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionEnv.

Definition at line 163 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [4/4]

void collision_detection::CollisionEnvBullet::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const AllowedCollisionMatrix acm 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result @robot robot The collision model for the robot
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionEnv.

Definition at line 170 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkRobotCollisionHelper()

void collision_detection::CollisionEnvBullet::checkRobotCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
protected

Definition at line 178 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkRobotCollisionHelperCCD()

void collision_detection::CollisionEnvBullet::checkRobotCollisionHelperCCD ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const AllowedCollisionMatrix acm 
) const
protected

Definition at line 208 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkSelfCollision() [1/2]

void collision_detection::CollisionEnvBullet::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
overridevirtual

Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are ignored.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
stateThe kinematic state for which checks are being made

Implements collision_detection::CollisionEnv.

Definition at line 102 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkSelfCollision() [2/2]

void collision_detection::CollisionEnvBullet::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
overridevirtual

Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionEnv.

Definition at line 108 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ checkSelfCollisionHelper()

void collision_detection::CollisionEnvBullet::checkSelfCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
protected

Bundles the different checkSelfCollision functions into a single function.

Definition at line 115 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ distanceRobot()

void collision_detection::CollisionEnvBullet::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
overridevirtual

Compute the distance between a robot and the world.

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
robotThe robot to check distance for
stateThe state for the robot to check distances from

Implements collision_detection::CollisionEnv.

Definition at line 246 of file collision_env_bullet.cpp.

◆ distanceSelf()

void collision_detection::CollisionEnvBullet::distanceSelf ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
overridevirtual

The distance to self-collision given the robot is at state state.

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
stateThe state of this robot to consider

Implements collision_detection::CollisionEnv.

Definition at line 240 of file collision_env_bullet.cpp.

◆ setWorld()

void collision_detection::CollisionEnvBullet::setWorld ( const WorldPtr &  world)
overridevirtual

set the world to use. This can be expensive unless the new and old world are empty. Passing nullptr will result in a new empty world being created.

Reimplemented from collision_detection::CollisionEnv.

Definition at line 298 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ updatedPaddingOrScaling()

void collision_detection::CollisionEnvBullet::updatedPaddingOrScaling ( const std::vector< std::string > &  links)
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 358 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ updateManagedObject()

void collision_detection::CollisionEnvBullet::updateManagedObject ( const std::string &  id)
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 272 of file collision_env_bullet.cpp.

Here is the call graph for this function:

◆ updateTransformsFromState()

void collision_detection::CollisionEnvBullet::updateTransformsFromState ( const moveit::core::RobotState state,
const collision_detection_bullet::BulletDiscreteBVHManagerPtr &  manager 
) const
protected

Updates the poses of the objects in the manager according to given robot state.

Definition at line 373 of file collision_env_bullet.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ active_

std::vector<std::string> collision_detection::CollisionEnvBullet::active_
protected

The active links where active refers to the group which can collide with everything.

Definition at line 140 of file collision_env_bullet.h.

◆ collision_env_mutex_

std::mutex collision_detection::CollisionEnvBullet::collision_env_mutex_
mutableprotected

Definition at line 127 of file collision_env_bullet.h.

◆ manager_

collision_detection_bullet::BulletDiscreteBVHManagerPtr collision_detection::CollisionEnvBullet::manager_
protected
Initial value:
{
}
A bounding volume hierarchy (BVH) implementation of a discrete bullet manager.

Handles self collision checks.

Definition at line 117 of file collision_env_bullet.h.

◆ manager_CCD_

collision_detection_bullet::BulletCastBVHManagerPtr collision_detection::CollisionEnvBullet::manager_CCD_
protected
Initial value:
{
}
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.

Handles continuous robot world collision checks.

Definition at line 122 of file collision_env_bullet.h.


The documentation for this class was generated from the following files: