moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <collision_env_bullet.h>
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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 | distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override |
Compute the distance between a robot and the world. | |
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. | |
CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0) | |
Constructor. | |
CollisionEnv (const CollisionEnv &other, const WorldPtr &world) | |
Copy constructor. | |
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. | |
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. | |
double | distanceSelf (const moveit::core::RobotState &state) const |
The distance to self-collision given the robot is at state state. | |
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) | |
double | distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const |
Compute the shortest distance between a robot and the world. | |
double | distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const |
Compute the shortest distance between a robot and the world. | |
const WorldPtr & | getWorld () |
const WorldConstPtr & | getWorld () const |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
The kinematic model corresponding to this collision model. | |
void | setLinkPadding (const std::string &link_name, double padding) |
Set the link padding for a particular link. | |
double | getLinkPadding (const std::string &link_name) const |
Get the link padding for a particular link. | |
void | setLinkPadding (const std::map< std::string, double > &padding) |
Set the link paddings using a map (from link names to padding value) | |
const std::map< std::string, double > & | getLinkPadding () const |
Get the link paddings as a map (from link names to padding value) | |
void | setLinkScale (const std::string &link_name, double scale) |
Set the scaling for a particular link. | |
double | getLinkScale (const std::string &link_name) const |
Set the scaling for a particular link. | |
void | setLinkScale (const std::map< std::string, double > &scale) |
Set the link scaling using a map (from link names to scale value) | |
const std::map< std::string, double > & | getLinkScale () const |
Get the link scaling as a map (from link names to scale value) | |
void | setPadding (double padding) |
Set the link padding (for every link) | |
void | setScale (double scale) |
Set the link scaling (for every link) | |
void | setPadding (const std::vector< moveit_msgs::msg::LinkPadding > &padding) |
Set the link padding from a vector of messages. | |
void | getPadding (std::vector< moveit_msgs::msg::LinkPadding > &padding) const |
Get the link padding as a vector of messages. | |
void | setScale (const std::vector< moveit_msgs::msg::LinkScale > &scale) |
Set the link scaling from a vector of messages. | |
void | getScale (std::vector< moveit_msgs::msg::LinkScale > &scale) const |
Get the link scaling as a vector of messages. | |
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. | |
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. | |
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 | checkSelfCollisionHelper (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const |
Bundles the different checkSelfCollision functions into a single function. | |
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. | |
void | addToManager (const World::Object *obj) |
Adds a world object to the collision managers. | |
void | updateManagedObject (const std::string &id) |
Updates a managed collision object with its world representation. | |
Protected Attributes | |
collision_detection_bullet::BulletDiscreteBVHManagerPtr | manager_ |
Handles self collision checks. | |
collision_detection_bullet::BulletCastBVHManagerPtr | manager_CCD_ |
Handles continuous robot world collision checks. | |
std::mutex | collision_env_mutex_ |
std::vector< std::string > | active_ |
The active links where active refers to the group which can collide with everything. | |
Protected Attributes inherited from collision_detection::CollisionEnv | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model corresponding to this collision model. | |
std::map< std::string, double > | link_padding_ |
The internally maintained map (from link names to padding) | |
std::map< std::string, double > | link_scale_ |
The internally maintained map (from link names to scaling) | |
Additional Inherited Members | |
Public Types inherited from collision_detection::CollisionEnv | |
using | ObjectPtr = World::ObjectPtr |
using | ObjectConstPtr = World::ObjectConstPtr |
Definition at line 47 of file collision_env_bullet.h.
|
delete |
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const moveit::core::RobotModelConstPtr & | model, |
double | padding = 0.0 , |
||
double | scale = 1.0 |
||
) |
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const moveit::core::RobotModelConstPtr & | model, |
const WorldPtr & | world, | ||
double | padding = 0.0 , |
||
double | scale = 1.0 |
||
) |
collision_detection::CollisionEnvBullet::CollisionEnvBullet | ( | const CollisionEnvBullet & | other, |
const WorldPtr & | world | ||
) |
|
override |
|
delete |
|
protected |
All of the attached objects in the robot state are wrapped into bullet collision objects.
Definition at line 335 of file collision_env_bullet.cpp.
|
protected |
Construts a bullet collision object out of a robot link.
Definition at line 389 of file collision_env_bullet.cpp.
|
protected |
Adds a world object to the collision managers.
Definition at line 253 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 robot The collision model for the robot |
state | The kinematic state for which checks are being made |
Implements collision_detection::CollisionEnv.
Definition at line 151 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 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 157 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 @robot robot The collision model for the robot |
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 164 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 @robot robot The collision model for the robot |
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 171 of file collision_env_bullet.cpp.
|
protected |
Definition at line 179 of file collision_env_bullet.cpp.
|
protected |
Definition at line 209 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 103 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 109 of file collision_env_bullet.cpp.
|
protected |
Bundles the different checkSelfCollision functions into a single function.
Definition at line 116 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 |
robot | The robot to check distance for |
state | The state for the robot to check distances from |
Implements collision_detection::CollisionEnv.
Definition at line 247 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 241 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 nullptr will result in a new empty world being created.
Reimplemented from collision_detection::CollisionEnv.
Definition at line 303 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 363 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 277 of file collision_env_bullet.cpp.
|
protected |
Updates the poses of the objects in the manager according to given robot state.
Definition at line 378 of file collision_env_bullet.cpp.
|
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.
|
mutableprotected |
Definition at line 127 of file collision_env_bullet.h.
|
protected |
Handles self collision checks.
Definition at line 117 of file collision_env_bullet.h.
|
protected |
Handles continuous robot world collision checks.
Definition at line 122 of file collision_env_bullet.h.