Go to the documentation of this file.
44 #include <boost/thread/mutex.hpp>
58 class CollisionEnvDistanceField :
public CollisionEnv
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
64 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
65 std::map<std::string, std::vector<CollisionSphere>>(),
75 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
76 std::map<std::string, std::vector<CollisionSphere>>(),
87 void initialize(
const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
89 double resolution,
double collision_tolerance,
double max_propogation_distance);
103 GroupStateRepresentationPtr& gsr)
const;
106 visualization_msgs::MarkerArray& model_markers)
const;
119 void distanceSelf(
const DistanceRequest& , DistanceResult& ,
139 struct DistanceFieldCacheEntryWorld
151 GroupStateRepresentationPtr& gsr)
const;
170 GroupStateRepresentationPtr& gsr)
const;
186 bool verbose =
false)
const
200 void setWorld(
const WorldPtr& world)
override;
224 GroupStateRepresentationPtr& gsr)
const;
232 GroupStateRepresentationPtr& gsr)
const;
235 GroupStateRepresentationPtr& gsr)
const;
239 GroupStateRepresentationPtr& gsr,
bool generate_distance_field)
const;
241 DistanceFieldCacheEntryConstPtr
248 bool generate_distance_field)
const;
253 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions);
256 unsigned int ind)
const;
261 GroupStateRepresentationPtr& gsr)
const;
273 void updateDistanceObject(
const std::string&
id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr& dfce,
277 const distance_field::DistanceFieldConstPtr& env_distance_field,
278 GroupStateRepresentationPtr& gsr)
const;
281 GroupStateRepresentationPtr& gsr)
const;
A link from the robot. Contains the constant transform applied to the link and its geometry.
Core components of MoveIt.
World::ObserverHandle observer_handle_
~CollisionEnvDistanceField() override
void updateGroupStateRepresentationState(const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
bool use_signed_distance_field_
static const double DEFAULT_COLLISION_TOLERANCE
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel *ls) const
DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry() const
DistanceFieldCacheEntryPtr distance_field_cache_entry_
void checkSelfCollisionHelper(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
bool getIntraGroupProximityGradients(GroupStateRepresentationPtr &gsr) const
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
static const double DEFAULT_MAX_PROPOGATION_DISTANCE
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
bool compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const
planning_scene::PlanningScenePtr planning_scene_
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....
std::map< std::string, GroupStateRepresentationPtr > pregenerated_group_state_representation_map_
Representation of a collision checking request.
static const double DEFAULT_SIZE_X
bool getEnvironmentCollisions(const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_
Definition of a structure for the allowed collision matrix.
boost::mutex update_cache_lock_
bool getSelfProximityGradients(GroupStateRepresentationPtr &gsr) const
static const double DEFAULT_SIZE_Z
double collision_tolerance_
virtual double distanceSelf(const moveit::core::RobotState &) const
std::map< std::string, std::vector< PosedBodyPointDecompositionPtr > > posed_body_point_decompositions_
bool compareCacheEntryToAllowedCollisionMatrix(const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
static const double DEFAULT_SIZE_Y
Representation of a collision checking result.
std::map< std::string, std::map< std::string, bool > > in_group_update_map_
boost::mutex update_cache_lock_world_
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
std::vector< BodyDecompositionConstPtr > link_body_decomposition_vector_
void setWorld(const WorldPtr &world) override
distance_field::DistanceFieldPtr distance_field_
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition(const moveit::core::LinkModel *ls, unsigned int ind) const
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
World::ObjectConstPtr ObjectConstPtr
void generateCollisionCheckingStructures(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const
bool getSelfCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
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,...
std::map< std::string, unsigned int > link_body_decomposition_index_map_
collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const
distance_field::DistanceFieldConstPtr getDistanceField() const
void getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
void updateDistanceObject(const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
void addLinkBodyDecompositions(double resolution)
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Result of a distance request.
DistanceFieldCacheEntryConstPtr getDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
virtual double distanceRobot(const moveit::core::RobotState &state, bool verbose=false) const
MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntryWorld)
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) 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)
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)
bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
GroupStateRepresentationPtr last_gsr_
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...
bool getIntraGroupCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld()
Representation of a distance-reporting request.
double max_propogation_distance_
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,...
void createCollisionModelMarker(const moveit::core::RobotState &state, visualization_msgs::MarkerArray &model_markers) const
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD
Vec3fX< details::Vec3Data< double > > Vector3d
static const double DEFAULT_RESOLUTION
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14