45 const moveit::core::RobotModelConstPtr& robot_model,
46 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
double size_x,
double size_y,
47 double size_z,
const Eigen::Vector3d& origin,
bool use_signed_distance_field,
double resolution,
48 double collision_tolerance,
double max_propogation_distance,
double padding,
double scale)
51 robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
52 resolution, collision_tolerance, max_propogation_distance, padding, scale))
57 const moveit::core::RobotModelConstPtr& robot_model,
const WorldPtr& world,
58 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
double size_x,
double size_y,
59 double size_z,
const Eigen::Vector3d& origin,
bool use_signed_distance_field,
double resolution,
60 double collision_tolerance,
double max_propogation_distance,
double padding,
double scale)
63 robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field,
64 resolution, collision_tolerance, max_propogation_distance, padding, scale))
71 *other.getCollisionWorldDistanceField(), world))
85 GroupStateRepresentationPtr& gsr)
const
102 GroupStateRepresentationPtr& gsr)
const
115 GroupStateRepresentationPtr& gsr)
const
130 GroupStateRepresentationPtr& gsr)
const
143 GroupStateRepresentationPtr& gsr)
const
158 GroupStateRepresentationPtr& gsr)
const
174 GroupStateRepresentationPtr& gsr)
const
181 GroupStateRepresentationPtr& gsr)
const
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static const std::string NAME
FCL implementation of the CollisionEnv.
void setWorld(const WorldPtr &world) override
This hybrid collision environment combines FCL and a distance field. Both can be used to calculate co...
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
void checkRobotCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const
CollisionEnvDistanceFieldPtr cenv_distance_
void setWorld(const WorldPtr &world) override
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionEnvHybrid(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)
void checkCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
const WorldPtr & getWorld()
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Vec3fX< details::Vec3Data< double > > Vector3d
Representation of a collision checking request.
Representation of a collision checking result.