Go to the documentation of this file.
33 #include <boost/archive/xml_oarchive.hpp>
34 #include <boost/archive/xml_iarchive.hpp>
35 #include <boost/archive/binary_oarchive.hpp>
36 #include <boost/archive/binary_iarchive.hpp>
37 #include <boost/serialization/base_object.hpp>
38 #include <boost/serialization/nvp.hpp>
39 #include <boost/serialization/array.hpp>
40 #include <boost/serialization/vector.hpp>
41 #include <boost/serialization/map.hpp>
42 #include <boost/serialization/unordered_map.hpp>
43 #include <boost/serialization/shared_ptr.hpp>
57 template <
class Archive>
60 ar& boost::serialization::make_nvp(
"distance", g.
distance);
61 ar& boost::serialization::make_nvp(
"type_id", g.
type_id);
62 ar& boost::serialization::make_nvp(
"link_names", g.
link_names);
63 ar& boost::serialization::make_nvp(
"shape_id", g.
shape_id);
64 ar& boost::serialization::make_nvp(
"subshape_id", g.
subshape_id);
65 ar& boost::serialization::make_nvp(
"nearest_points", g.
nearest_points);
67 ar& boost::serialization::make_nvp(
"transform", g.
transform);
68 ar& boost::serialization::make_nvp(
"normal", g.
normal);
69 ar& boost::serialization::make_nvp(
"cc_time", g.
cc_time);
70 ar& boost::serialization::make_nvp(
"cc_type", g.
cc_type);
71 ar& boost::serialization::make_nvp(
"cc_transform", g.
cc_transform);
78 template <
class Archive>
81 ar& boost::serialization::make_nvp(
"container", g.
getContainer());
84 template <
class Archive>
88 ar& boost::serialization::make_nvp(
"container", container);
90 for (
const auto& c : container)
94 template <
class Archive>
97 split_free(ar, g, version);
100 template <
class Archive>
103 ar& boost::serialization::make_nvp(
"type", g.
type);
106 ar& boost::serialization::make_nvp(
"contact_limit", g.
contact_limit);
107 ar& boost::serialization::make_nvp(
"is_valid", g.
is_valid);
110 template <
class Archive>
114 ar& boost::serialization::make_nvp(
"has_default_margin", has_default_margin);
118 double default_margin{ 0 };
122 ar& boost::serialization::make_nvp(
"default_margin", default_margin);
127 ar& boost::serialization::make_nvp(
"acm", g.
acm);
132 template <
class Archive>
135 bool has_default_margin{
false };
136 ar& boost::serialization::make_nvp(
"has_default_margin", has_default_margin);
137 if (has_default_margin)
139 double default_margin{ 0 };
140 ar& boost::serialization::make_nvp(
"default_margin", default_margin);
145 ar& boost::serialization::make_nvp(
"acm", g.
acm);
150 template <
class Archive>
153 split_free(ar, g, version);
156 template <
class Archive>
159 ar& boost::serialization::make_nvp(
"contact_request", g.
contact_request);
160 ar& boost::serialization::make_nvp(
"type", g.
type);
165 template <
class Archive>
168 ar& boost::serialization::make_nvp(
"contacts", g.
contacts);
169 ar& boost::serialization::make_nvp(
"substep", g.
substep);
170 ar& boost::serialization::make_nvp(
"state0", g.
state0);
171 ar& boost::serialization::make_nvp(
"state1", g.
state1);
174 template <
class Archive>
177 ar& boost::serialization::make_nvp(
"substeps", g.
substeps);
178 ar& boost::serialization::make_nvp(
"step", g.
step);
179 ar& boost::serialization::make_nvp(
"state0", g.
state0);
180 ar& boost::serialization::make_nvp(
"state1", g.
state1);
181 ar& boost::serialization::make_nvp(
"total_substeps", g.
total_substeps);
184 template <
class Archive>
187 ar& boost::serialization::make_nvp(
"steps", g.
steps);
188 ar& boost::serialization::make_nvp(
"joint_names", g.
joint_names);
189 ar& boost::serialization::make_nvp(
"total_steps", g.
total_steps);
void serialize(Archive &ar, Eigen::Isometry3d &g, const unsigned int version)
Tesseracts Collision Forward Declarations.
void load(Archive &ar, Eigen::Isometry3d &g, const unsigned int version)
#define TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE(Type)
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
void save(Archive &ar, const Eigen::Isometry3d &g, const unsigned int version)
CollisionEvaluatorType type
Specifies the type of collision check to be performed. Default: DISCRETE.
CollisionCheckProgramType check_program_mode
Secifies the mode used when collision checking program/trajectory. Default: ALL.
ContactRequest contact_request
ContactRequest that will be used for this check. Default test type: ALL.
This is a high level structure containing common information that collision checking utilities need....
Tesseracts Collision Serialization.
#define TESSERACT_SERIALIZE_FREE_ARCHIVES_INSTANTIATE(Type)
#define TESSERACT_SERIALIZE_SAVE_LOAD_FREE_ARCHIVES_INSTANTIATE(Type)
double longest_valid_segment_length
Longest valid segment to use if type supports lvs. Default: 0.005.