#include <collision_env_distance_field.h>

Classes | |
| struct | DistanceFieldCacheEntryWorld |
Public Member Functions | |
| void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override |
| 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... | |
| void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override |
| 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... | |
| virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const |
| virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) 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 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... | |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const |
| 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 collision_detection::CollisionRequest &req, collision_detection::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 collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm) const override |
| Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More... | |
| void | checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const |
| void | checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const |
| CollisionEnvDistanceField (const CollisionEnvDistanceField &other, const WorldPtr &world) | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | CollisionEnvDistanceField (const moveit::core::RobotModelConstPtr &robot_model, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0) |
| CollisionEnvDistanceField (const moveit::core::RobotModelConstPtr &robot_model, const WorldPtr &world, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0) | |
| void | createCollisionModelMarker (const moveit::core::RobotState &state, visualization_msgs::MarkerArray &model_markers) const |
| void | distanceRobot (const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override |
| Compute the distance between a robot and the world. More... | |
| virtual double | distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const |
| virtual double | distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const |
| void | distanceSelf (const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override |
| The distance to self-collision given the robot is at state state. More... | |
| virtual double | distanceSelf (const moveit::core::RobotState &) const |
| virtual double | distanceSelf (const moveit::core::RobotState &, const collision_detection::AllowedCollisionMatrix &) const |
| void | getAllCollisions (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const |
| void | getCollisionGradients (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const |
| distance_field::DistanceFieldConstPtr | getDistanceField () const |
| DistanceFieldCacheEntryConstPtr | getLastDistanceFieldEntry () const |
| collision_detection::GroupStateRepresentationConstPtr | getLastGroupStateRepresentation () const |
| void | initialize (const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance) |
| MOVEIT_STRUCT_FORWARD (DistanceFieldCacheEntryWorld) | |
| void | setWorld (const WorldPtr &world) override |
| ~CollisionEnvDistanceField () override | |
Public Member Functions inherited from collision_detection::CollisionEnv | |
| 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 | addLinkBodyDecompositions (double resolution) |
| void | addLinkBodyDecompositions (double resolution, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions) |
| void | checkSelfCollisionHelper (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const |
| bool | compareCacheEntryToAllowedCollisionMatrix (const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const |
| bool | compareCacheEntryToState (const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const |
| void | generateCollisionCheckingStructures (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const |
| DistanceFieldCacheEntryPtr | generateDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const |
| DistanceFieldCacheEntryWorldPtr | generateDistanceFieldCacheEntryWorld () |
| DistanceFieldCacheEntryConstPtr | getDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const |
| bool | getEnvironmentCollisions (const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const |
| bool | getEnvironmentProximityGradients (const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const |
| void | getGroupStateRepresentation (const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const |
| bool | getIntraGroupCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const |
| bool | getIntraGroupProximityGradients (GroupStateRepresentationPtr &gsr) const |
| PosedBodyPointDecompositionPtr | getPosedLinkBodyPointDecomposition (const moveit::core::LinkModel *ls) const |
| PosedBodySphereDecompositionPtr | getPosedLinkBodySphereDecomposition (const moveit::core::LinkModel *ls, unsigned int ind) const |
| bool | getSelfCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const |
| bool | getSelfProximityGradients (GroupStateRepresentationPtr &gsr) const |
| void | notifyObjectChange (const ObjectConstPtr &obj, World::Action action) |
| void | updateDistanceObject (const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points) |
| void | updatedPaddingOrScaling (const std::vector< std::string > &) override |
| When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes. More... | |
| void | updateGroupStateRepresentationState (const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const |
Protected Attributes | |
| double | collision_tolerance_ |
| DistanceFieldCacheEntryPtr | distance_field_cache_entry_ |
| DistanceFieldCacheEntryWorldPtr | distance_field_cache_entry_world_ |
| std::map< std::string, std::map< std::string, bool > > | in_group_update_map_ |
| GroupStateRepresentationPtr | last_gsr_ |
| std::map< std::string, unsigned int > | link_body_decomposition_index_map_ |
| std::vector< BodyDecompositionConstPtr > | link_body_decomposition_vector_ |
| double | max_propogation_distance_ |
| World::ObserverHandle | observer_handle_ |
| Eigen::Vector3d | origin_ |
| planning_scene::PlanningScenePtr | planning_scene_ |
| std::map< std::string, GroupStateRepresentationPtr > | pregenerated_group_state_representation_map_ |
| double | resolution_ |
| Eigen::Vector3d | size_ |
| boost::mutex | update_cache_lock_ |
| boost::mutex | update_cache_lock_world_ |
| bool | use_signed_distance_field_ |
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... | |
Additional Inherited Members | |
Public Types inherited from collision_detection::CollisionEnv | |
| using | ObjectConstPtr = World::ObjectConstPtr |
| using | ObjectPtr = World::ObjectPtr |
Definition at line 90 of file collision_env_distance_field.h.
| collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const std::map< std::string, std::vector< CollisionSphere >> & | link_body_decompositions = std::map<std::string, std::vector<CollisionSphere>>(), |
||
| double | size_x = DEFAULT_SIZE_X, |
||
| double | size_y = DEFAULT_SIZE_Y, |
||
| double | size_z = DEFAULT_SIZE_Z, |
||
| const Eigen::Vector3d & | origin = Eigen::Vector3d(0, 0, 0), |
||
| bool | use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, |
||
| double | resolution = DEFAULT_RESOLUTION, |
||
| double | collision_tolerance = DEFAULT_COLLISION_TOLERANCE, |
||
| double | max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, |
||
| double | padding = 0.0, |
||
| double | scale = 1.0 |
||
| ) |
Definition at line 89 of file collision_env_distance_field.cpp.
| collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const WorldPtr & | world, | ||
| const std::map< std::string, std::vector< CollisionSphere >> & | link_body_decompositions = std::map<std::string, std::vector<CollisionSphere>>(), |
||
| double | size_x = DEFAULT_SIZE_X, |
||
| double | size_y = DEFAULT_SIZE_Y, |
||
| double | size_z = DEFAULT_SIZE_Z, |
||
| const Eigen::Vector3d & | origin = Eigen::Vector3d(0, 0, 0), |
||
| bool | use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, |
||
| double | resolution = DEFAULT_RESOLUTION, |
||
| double | collision_tolerance = DEFAULT_COLLISION_TOLERANCE, |
||
| double | max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, |
||
| double | padding = 0.0, |
||
| double | scale = 1.0 |
||
| ) |
Definition at line 108 of file collision_env_distance_field.cpp.
| collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField | ( | const CollisionEnvDistanceField & | other, |
| const WorldPtr & | world | ||
| ) |
Definition at line 127 of file collision_env_distance_field.cpp.
|
override |
Definition at line 150 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1009 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1097 of file collision_env_distance_field.cpp.
|
overridevirtual |
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.
| 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 |
Reimplemented from collision_detection::CollisionEnv.
Definition at line 1433 of file collision_env_distance_field.cpp.
|
overridevirtual |
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.
| 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. |
Reimplemented from collision_detection::CollisionEnv.
Definition at line 1465 of file collision_env_distance_field.cpp.
|
virtual |
Definition at line 1473 of file collision_env_distance_field.cpp.
|
virtual |
Definition at line 1440 of file collision_env_distance_field.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 1498 of file collision_env_distance_field.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 1524 of file collision_env_distance_field.cpp.
|
virtual |
Definition at line 1532 of file collision_env_distance_field.cpp.
|
virtual |
Definition at line 1505 of file collision_env_distance_field.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 1561 of file collision_env_distance_field.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 1553 of file collision_env_distance_field.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 270 of file collision_env_distance_field.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 286 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::checkSelfCollision | ( | const collision_detection::CollisionRequest & | req, |
| collision_detection::CollisionResult & | res, | ||
| const moveit::core::RobotState & | state, | ||
| const collision_detection::AllowedCollisionMatrix & | acm, | ||
| GroupStateRepresentationPtr & | gsr | ||
| ) | const |
Definition at line 295 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::checkSelfCollision | ( | const collision_detection::CollisionRequest & | req, |
| collision_detection::CollisionResult & | res, | ||
| const moveit::core::RobotState & | state, | ||
| GroupStateRepresentationPtr & | gsr | ||
| ) | const |
Definition at line 278 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 214 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1362 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1302 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::createCollisionModelMarker | ( | const moveit::core::RobotState & | state, |
| visualization_msgs::MarkerArray & | model_markers | ||
| ) | const |
Definition at line 1029 of file collision_env_distance_field.cpp.
|
inlineoverridevirtual |
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 226 of file collision_env_distance_field.h.
|
inlinevirtual |
Definition at line 210 of file collision_env_distance_field.h.
|
inlinevirtual |
Definition at line 217 of file collision_env_distance_field.h.
|
inlineoverridevirtual |
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 151 of file collision_env_distance_field.h.
|
inlinevirtual |
Definition at line 140 of file collision_env_distance_field.h.
|
inlinevirtual |
Definition at line 145 of file collision_env_distance_field.h.
|
protected |
Definition at line 195 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 760 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1833 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::getAllCollisions | ( | const CollisionRequest & | req, |
| CollisionResult & | res, | ||
| const moveit::core::RobotState & | state, | ||
| const AllowedCollisionMatrix * | acm, | ||
| GroupStateRepresentationPtr & | gsr | ||
| ) | const |
Definition at line 1591 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::getCollisionGradients | ( | const CollisionRequest & | req, |
| CollisionResult & | res, | ||
| const moveit::core::RobotState & | state, | ||
| const AllowedCollisionMatrix * | acm, | ||
| GroupStateRepresentationPtr & | gsr | ||
| ) | const |
Definition at line 1568 of file collision_env_distance_field.cpp.
|
inline |
Definition at line 234 of file collision_env_distance_field.h.
|
protected |
Definition at line 239 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1612 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1696 of file collision_env_distance_field.cpp.
|
protected |
std::cerr << "Attached " << dfce->attached_body_names_[i] << " index " << dfce->attached_body_link_state_indices_[i] << std::endl;
Definition at line 1204 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 465 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 694 of file collision_env_distance_field.cpp.
|
inline |
Definition at line 157 of file collision_env_distance_field.h.
|
inline |
Definition at line 239 of file collision_env_distance_field.h.
|
protected |
Definition at line 1137 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1128 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 309 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 390 of file collision_env_distance_field.cpp.
| void collision_detection::CollisionEnvDistanceField::initialize | ( | const std::map< std::string, std::vector< CollisionSphere >> & | link_body_decompositions, |
| const Eigen::Vector3d & | size, | ||
| const Eigen::Vector3d & | origin, | ||
| bool | use_signed_distance_field, | ||
| double | resolution, | ||
| double | collision_tolerance, | ||
| double | max_propogation_distance | ||
| ) |
Definition at line 155 of file collision_env_distance_field.cpp.
| collision_detection::CollisionEnvDistanceField::MOVEIT_STRUCT_FORWARD | ( | DistanceFieldCacheEntryWorld | ) |
|
protected |
Definition at line 1755 of file collision_env_distance_field.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 1734 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 1781 of file collision_env_distance_field.cpp.
|
inlineoverrideprotectedvirtual |
When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes.
| links | the names of the links whose padding or scaling were updated |
Reimplemented from collision_detection::CollisionEnv.
Definition at line 301 of file collision_env_distance_field.h.
|
protected |
Definition at line 1150 of file collision_env_distance_field.cpp.
|
protected |
Definition at line 321 of file collision_env_distance_field.h.
|
protected |
Definition at line 328 of file collision_env_distance_field.h.
|
protected |
Definition at line 335 of file collision_env_distance_field.h.
|
protected |
Definition at line 329 of file collision_env_distance_field.h.
|
protected |
Definition at line 336 of file collision_env_distance_field.h.
|
protected |
Definition at line 325 of file collision_env_distance_field.h.
|
protected |
Definition at line 324 of file collision_env_distance_field.h.
|
protected |
Definition at line 322 of file collision_env_distance_field.h.
|
protected |
Definition at line 337 of file collision_env_distance_field.h.
|
protected |
Definition at line 318 of file collision_env_distance_field.h.
|
protected |
Definition at line 332 of file collision_env_distance_field.h.
|
protected |
Definition at line 330 of file collision_env_distance_field.h.
|
protected |
Definition at line 320 of file collision_env_distance_field.h.
|
protected |
Definition at line 317 of file collision_env_distance_field.h.
|
mutableprotected |
Definition at line 327 of file collision_env_distance_field.h.
|
mutableprotected |
Definition at line 334 of file collision_env_distance_field.h.
|
protected |
Definition at line 319 of file collision_env_distance_field.h.