Go to the documentation of this file.
5 #ifndef COAL_SERIALIZATION_COLLISION_DATA_H
6 #define COAL_SERIALIZATION_COLLISION_DATA_H
12 namespace serialization {
14 template <
class Archive>
16 const unsigned int ) {
17 ar& make_nvp(
"b1", contact.
b1);
18 ar& make_nvp(
"b2", contact.
b2);
19 ar& make_nvp(
"normal", contact.
normal);
21 ar& make_nvp(
"pos", contact.
pos);
25 template <
class Archive>
27 ar >> make_nvp(
"b1", contact.
b1);
28 ar >> make_nvp(
"b2", contact.
b2);
29 ar >> make_nvp(
"normal", contact.
normal);
30 std::array<coal::Vec3s, 2> nearest_points;
31 ar >> make_nvp(
"nearest_points", nearest_points);
34 ar >> make_nvp(
"pos", contact.
pos);
42 template <
class Archive>
44 const unsigned int ) {
49 ar& make_nvp(
"enable_cached_gjk_guess",
53 ar& make_nvp(
"cached_support_func_guess",
57 ar& make_nvp(
"gjk_variant", query_request.
gjk_variant);
58 ar& make_nvp(
"gjk_convergence_criterion",
60 ar& make_nvp(
"gjk_convergence_criterion_type",
64 ar& make_nvp(
"collision_distance_threshold",
69 template <
class Archive>
71 const unsigned int ) {
73 ar& make_nvp(
"cached_support_func_guess",
77 template <
class Archive>
79 const unsigned int ) {
80 ar& make_nvp(
"base", boost::serialization::base_object<coal::QueryRequest>(
86 ar& make_nvp(
"enable_distance_lower_bound",
94 template <
class Archive>
96 const unsigned int ) {
97 ar& make_nvp(
"base", boost::serialization::base_object<coal::QueryResult>(
99 ar& make_nvp(
"contacts", collision_result.
getContacts());
102 ar& make_nvp(
"normal", collision_result.
normal);
105 template <
class Archive>
107 const unsigned int ) {
108 ar >> make_nvp(
"base", boost::serialization::base_object<coal::QueryResult>(
110 std::vector<coal::Contact> contacts;
111 ar >> make_nvp(
"contacts", contacts);
112 collision_result.
clear();
113 for (
size_t k = 0; k < contacts.size(); ++k)
116 std::array<coal::Vec3s, 2> nearest_points;
117 ar >> make_nvp(
"nearest_points", nearest_points);
120 ar >> make_nvp(
"normal", collision_result.
normal);
125 template <
class Archive>
127 const unsigned int ) {
128 ar& make_nvp(
"base", boost::serialization::base_object<coal::QueryRequest>(
132 ar& make_nvp(
"enable_nearest_points", distance_request.enable_nearest_points);
134 ar& make_nvp(
"enable_signed_distance",
136 ar& make_nvp(
"rel_err", distance_request.
rel_err);
137 ar& make_nvp(
"abs_err", distance_request.
abs_err);
140 template <
class Archive>
142 const unsigned int ) {
143 ar& make_nvp(
"base", boost::serialization::base_object<coal::QueryResult>(
145 ar& make_nvp(
"min_distance", distance_result.
min_distance);
147 ar& make_nvp(
"normal", distance_result.
normal);
148 ar& make_nvp(
"b1", distance_result.
b1);
149 ar& make_nvp(
"b2", distance_result.
b2);
152 template <
class Archive>
154 const unsigned int ) {
155 ar >> make_nvp(
"base", boost::serialization::base_object<coal::QueryResult>(
157 ar >> make_nvp(
"min_distance", distance_result.
min_distance);
158 std::array<coal::Vec3s, 2> nearest_points;
159 ar >> make_nvp(
"nearest_points", nearest_points);
162 ar >> make_nvp(
"normal", distance_result.
normal);
163 ar >> make_nvp(
"b1", distance_result.
b1);
164 ar >> make_nvp(
"b2", distance_result.
b2);
165 distance_result.
o1 = NULL;
166 distance_result.
o2 = NULL;
179 #endif // ifndef COAL_SERIALIZATION_COLLISION_DATA_H
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
GJKConvergenceCriterion gjk_convergence_criterion
convergence criterion used to stop GJK
void load(Archive &ar, coal::BVSplitter< BV > &splitter_, const unsigned int)
const CollisionGeometry * o1
collision object 1
CoalScalar gjk_tolerance
tolerance for the GJK algorithm. Note: This tolerance determines the precision on the estimated dista...
GJKInitialGuess gjk_initial_guess
CoalScalar epa_tolerance
tolerance for EPA. Note: This tolerance determines the precision on the estimated distance between tw...
bool enable_contact
whether the contact information (normal, penetration depth and contact position) will return.
support_func_guess_t cached_support_func_guess
the support function initial guess set by user
#define COAL_COMPILER_DIAGNOSTIC_PUSH
int b1
information about the nearest point in object 1 if object 1 is mesh or point cloud,...
void serialize(Archive &ar, coal::AABB &aabb, const unsigned int)
base class for all query results
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Vec3s cached_gjk_guess
stores the last GJK ray when relevant.
bool enable_distance_lower_bound
Whether a lower bound on distance is returned when objects are disjoint.
bool enable_timings
enable timings when performing collision/distance request
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
#define COAL_SERIALIZATION_DECLARE_EXPORT(T)
Vec3s cached_gjk_guess
the gjk initial guess set by user
const CollisionGeometry * o2
collision object 2
GJKConvergenceCriterionType gjk_convergence_criterion_type
convergence criterion used to stop GJK
CoalScalar distance_lower_bound
#define COAL_SERIALIZATION_SPLIT(Type)
size_t gjk_max_iterations
maximum iteration for the GJK algorithm
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
request to the distance computation
void clear()
clear the results obtained
void addContact(const Contact &c)
add one contact into result structure
request to the collision algorithm
size_t epa_max_iterations
max number of iterations for EPA
base class for all query requests
int b2
information about the nearest point in object 2 if object 2 is mesh or point cloud,...
GJKVariant gjk_variant
whether to enable the Nesterov accleration of GJK
CoalScalar rel_err
error threshold for approximate distance
size_t num_max_contacts
The maximum number of contacts that can be returned.
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
#define COAL_COMPILER_DIAGNOSTIC_POP
bool enable_signed_distance
whether to compute the penetration depth when objects are in collision. Turning this off can save com...
#define COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
void save(Archive &ar, const coal::BVSplitter< BV > &splitter_, const unsigned int)
void getContacts(std::vector< Contact > &contacts_) const
get all the contacts
bool enable_cached_gjk_guess
whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead
CoalScalar collision_distance_threshold
threshold below which a collision is considered.
CoalScalar break_distance
Distance below which bounding volumes are broken down. See Collision.
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
CoalScalar distance_upper_bound
Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points w...
hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57