44#include <rclcpp/rclcpp.hpp>
49static const double DEFAULT_SIZE_X = 3.0;
50static const double DEFAULT_SIZE_Y = 3.0;
51static const double DEFAULT_SIZE_Z = 4.0;
52static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD =
false;
53static const double DEFAULT_RESOLUTION = .02;
54static const double DEFAULT_COLLISION_TOLERANCE = 0.0;
55static const double DEFAULT_MAX_PROPOGATION_DISTANCE = .25;
65 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
66 std::map<std::string, std::vector<CollisionSphere>>(),
67 double size_x = DEFAULT_SIZE_X,
double size_y = DEFAULT_SIZE_Y,
68 double size_z = DEFAULT_SIZE_Z,
const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
69 bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
70 double resolution = DEFAULT_RESOLUTION,
71 double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
72 double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE,
double padding = 0.0,
76 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions =
77 std::map<std::string, std::vector<CollisionSphere>>(),
78 double size_x = DEFAULT_SIZE_X,
double size_y = DEFAULT_SIZE_Y,
79 double size_z = DEFAULT_SIZE_Z,
const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0),
80 bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
81 double resolution = DEFAULT_RESOLUTION,
82 double collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
83 double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE,
double padding = 0.0,
88 void initialize(
const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
89 const Eigen::Vector3d& size,
const Eigen::Vector3d& origin,
bool use_signed_distance_field,
90 double resolution,
double collision_tolerance,
double max_propogation_distance);
104 GroupStateRepresentationPtr& gsr)
const;
107 visualization_msgs::msg::MarkerArray& model_markers)
const;
123 RCLCPP_ERROR(
logger_,
"Not implemented");
152 GroupStateRepresentationPtr& gsr)
const;
171 GroupStateRepresentationPtr& gsr)
const;
187 bool verbose =
false)
const
198 RCLCPP_ERROR(
logger_,
"Not implemented");
201 void setWorld(
const WorldPtr& world)
override;
225 GroupStateRepresentationPtr& gsr)
const;
233 GroupStateRepresentationPtr& gsr)
const;
236 GroupStateRepresentationPtr& gsr)
const;
240 GroupStateRepresentationPtr& gsr,
bool generate_distance_field)
const;
242 DistanceFieldCacheEntryConstPtr
249 bool generate_distance_field)
const;
254 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions);
257 unsigned int ind)
const;
262 GroupStateRepresentationPtr& gsr)
const;
274 void updateDistanceObject(
const std::string&
id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr& dfce,
275 EigenSTL::vector_Vector3d& add_points, EigenSTL::vector_Vector3d& subtract_points);
278 const distance_field::DistanceFieldConstPtr& env_distance_field,
279 GroupStateRepresentationPtr& gsr)
const;
282 GroupStateRepresentationPtr& gsr)
const;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
virtual double distanceSelf(const moveit::core::RobotState &) const
DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_
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...
DistanceFieldCacheEntryConstPtr getDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
std::map< std::string, std::map< std::string, bool > > in_group_update_map_
double max_propogation_distance_
DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld()
bool getSelfCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
void distanceRobot(const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override
Compute the distance between a robot and the world.
DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry() const
virtual double distanceRobot(const moveit::core::RobotState &state, bool verbose=false) const
bool compareCacheEntryToAllowedCollisionMatrix(const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
double collision_tolerance_
std::map< std::string, unsigned int > link_body_decomposition_index_map_
bool getIntraGroupCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
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 distance_field_cache_entry_
~CollisionEnvDistanceField() override
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 use_signed_distance_field_
bool compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const
std::vector< BodyDecompositionConstPtr > link_body_decomposition_vector_
bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
std::map< std::string, GroupStateRepresentationPtr > pregenerated_group_state_representation_map_
bool getSelfProximityGradients(GroupStateRepresentationPtr &gsr) const
bool getEnvironmentCollisions(const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
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....
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition(const moveit::core::LinkModel *ls, unsigned int ind) const
void updateGroupStateRepresentationState(const moveit::core::RobotState &state, 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)
bool getIntraGroupProximityGradients(GroupStateRepresentationPtr &gsr) const
void setWorld(const WorldPtr &world) override
void updateDistanceObject(const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
std::mutex update_cache_lock_
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
std::mutex update_cache_lock_world_
void addLinkBodyDecompositions(double resolution)
planning_scene::PlanningScenePtr planning_scene_
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel *ls) 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.
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
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,...
void createCollisionModelMarker(const moveit::core::RobotState &state, visualization_msgs::msg::MarkerArray &model_markers) const
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,...
MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntryWorld)
collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const
void getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
GroupStateRepresentationPtr last_gsr_
World::ObserverHandle observer_handle_
distance_field::DistanceFieldConstPtr getDistanceField() const
virtual double distanceSelf(const moveit::core::RobotState &, const collision_detection::AllowedCollisionMatrix &) const
Provides the interface to the individual collision checking libraries.
World::ObjectConstPtr ObjectConstPtr
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
A link from the robot. Contains the constant transform applied to the link and its geometry.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::map< std::string, std::vector< PosedBodyPointDecompositionPtr > > posed_body_point_decompositions_
distance_field::DistanceFieldPtr distance_field_
Representation of a collision checking request.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.