serialization.cpp
Go to the documentation of this file.
1 
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>
46 
50 
51 namespace boost::serialization
52 {
53 /************************************************/
54 /****** tesseract_collision::ContactResult ******/
55 /************************************************/
56 
57 template <class Archive>
58 void serialize(Archive& ar, tesseract_collision::ContactResult& g, const unsigned int /*version*/)
59 {
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);
66  ar& boost::serialization::make_nvp("nearest_points_local", g.nearest_points_local);
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);
72  ar& boost::serialization::make_nvp("single_contact_point", g.single_contact_point);
73 }
74 
75 /***************************************************/
76 /****** tesseract_collision::ContactResultMap ******/
77 /***************************************************/
78 template <class Archive>
79 void save(Archive& ar, const tesseract_collision::ContactResultMap& g, const unsigned int /*version*/)
80 {
81  ar& boost::serialization::make_nvp("container", g.getContainer());
82 }
83 
84 template <class Archive>
85 void load(Archive& ar, tesseract_collision::ContactResultMap& g, const unsigned int /*version*/)
86 {
88  ar& boost::serialization::make_nvp("container", container);
89 
90  for (const auto& c : container)
91  g.addContactResult(c.first, c.second);
92 }
93 
94 template <class Archive>
95 void serialize(Archive& ar, tesseract_collision::ContactResultMap& g, const unsigned int version)
96 {
97  split_free(ar, g, version);
98 }
99 
100 template <class Archive>
101 void serialize(Archive& ar, tesseract_collision::ContactRequest& g, const unsigned int /*version*/)
102 {
103  ar& boost::serialization::make_nvp("type", g.type);
104  ar& boost::serialization::make_nvp("calculate_penetration", g.calculate_penetration);
105  ar& boost::serialization::make_nvp("calculate_distance", g.calculate_distance);
106  ar& boost::serialization::make_nvp("contact_limit", g.contact_limit);
107  ar& boost::serialization::make_nvp("is_valid", g.is_valid);
108 }
109 
110 template <class Archive>
111 void save(Archive& ar, const tesseract_collision::ContactManagerConfig& g, const unsigned int /*version*/)
112 {
113  bool has_default_margin{ g.default_margin.has_value() };
114  ar& boost::serialization::make_nvp("has_default_margin", has_default_margin);
115 
116  if (g.default_margin.has_value())
117  {
118  double default_margin{ 0 };
119  if (g.default_margin.has_value())
120  default_margin = g.default_margin.value();
121 
122  ar& boost::serialization::make_nvp("default_margin", default_margin);
123  }
124 
125  ar& boost::serialization::make_nvp("pair_margin_override_type", g.pair_margin_override_type);
126  ar& boost::serialization::make_nvp("pair_margin_data", g.pair_margin_data);
127  ar& boost::serialization::make_nvp("acm", g.acm);
128  ar& boost::serialization::make_nvp("acm_override_type", g.acm_override_type);
129  ar& boost::serialization::make_nvp("modify_object_enabled", g.modify_object_enabled);
130 }
131 
132 template <class Archive>
133 void load(Archive& ar, tesseract_collision::ContactManagerConfig& g, const unsigned int /*version*/)
134 {
135  bool has_default_margin{ false };
136  ar& boost::serialization::make_nvp("has_default_margin", has_default_margin);
137  if (has_default_margin)
138  {
139  double default_margin{ 0 };
140  ar& boost::serialization::make_nvp("default_margin", default_margin);
141  g.default_margin = default_margin;
142  }
143  ar& boost::serialization::make_nvp("pair_margin_override_type", g.pair_margin_override_type);
144  ar& boost::serialization::make_nvp("pair_margin_data", g.pair_margin_data);
145  ar& boost::serialization::make_nvp("acm", g.acm);
146  ar& boost::serialization::make_nvp("acm_override_type", g.acm_override_type);
147  ar& boost::serialization::make_nvp("modify_object_enabled", g.modify_object_enabled);
148 }
149 
150 template <class Archive>
151 void serialize(Archive& ar, tesseract_collision::ContactManagerConfig& g, const unsigned int version)
152 {
153  split_free(ar, g, version);
154 }
155 
156 template <class Archive>
157 void serialize(Archive& ar, tesseract_collision::CollisionCheckConfig& g, const unsigned int /*version*/)
158 {
159  ar& boost::serialization::make_nvp("contact_request", g.contact_request);
160  ar& boost::serialization::make_nvp("type", g.type);
161  ar& boost::serialization::make_nvp("longest_valid_segment_length", g.longest_valid_segment_length);
162  ar& boost::serialization::make_nvp("check_program_mode", g.check_program_mode);
163 }
164 
165 template <class Archive>
166 void serialize(Archive& ar, tesseract_collision::ContactTrajectorySubstepResults& g, const unsigned int /*version*/)
167 {
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);
172 }
173 
174 template <class Archive>
175 void serialize(Archive& ar, tesseract_collision::ContactTrajectoryStepResults& g, const unsigned int /*version*/)
176 {
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);
182 }
183 
184 template <class Archive>
185 void serialize(Archive& ar, tesseract_collision::ContactTrajectoryResults& g, const unsigned int /*version*/)
186 {
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);
190 }
191 } // namespace boost::serialization
192 
202 
204 BOOST_CLASS_EXPORT_IMPLEMENT(tesseract_collision::ContactResultAnyPoly)
205 
207 BOOST_CLASS_EXPORT_IMPLEMENT(tesseract_collision::ContactResultMapAnyPoly)
208 
210 BOOST_CLASS_EXPORT_IMPLEMENT(tesseract_collision::ContactResultMapVectorAnyPoly)
tesseract_collision::ContactManagerConfig
Contains parameters used to configure a contact manager before a series of contact checks.
Definition: types.h:420
tesseract_collision::ContactRequest::calculate_distance
bool calculate_distance
This enables the calculation of distance data if two objects are within the contact threshold.
Definition: types.h:309
tesseract_collision::ContactResult::cc_time
std::array< double, 2 > cc_time
This is between 0 and 1 indicating the point of contact.
Definition: types.h:111
tesseract_collision::ContactTrajectoryStepResults::total_substeps
int total_substeps
Definition: types.h:555
boost::serialization::serialize
void serialize(Archive &ar, Eigen::Isometry3d &g, const unsigned int version)
types.h
Tesseracts Collision Forward Declarations.
tesseract_collision::ContactResult::shape_id
std::array< int, 2 > shape_id
The two shapes that are in contact. Each link can be made up of multiple shapes.
Definition: types.h:94
boost::serialization::load
void load(Archive &ar, Eigen::Isometry3d &g, const unsigned int version)
tesseract_collision::ContactResultMap::addContactResult
ContactResult & addContactResult(const KeyType &key, ContactResult result)
Add contact results for the provided key.
Definition: types.cpp:103
tesseract_collision::ContactRequest::type
ContactTestType type
This controls the exit condition for the contact test type.
Definition: types.h:303
TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE
#define TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE(Type)
tesseract_collision::ContactResult::normal
Eigen::Vector3d normal
The normal vector to move the two objects out of contact in world coordinates.
Definition: types.h:109
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_common::AnyWrapper
tesseract_collision::ContactTrajectoryStepResults::substeps
std::vector< ContactTrajectorySubstepResults > substeps
Definition: types.h:551
tesseract_collision::ContactTrajectoryResults::total_steps
int total_steps
Definition: types.h:593
tesseract_collision::ContactRequest::contact_limit
long contact_limit
This is used if the ContactTestType is set to LIMITED, where the test will exit when number of contac...
Definition: types.h:313
boost::serialization::save
void save(Archive &ar, const Eigen::Isometry3d &g, const unsigned int version)
tesseract_collision::ContactTrajectoryResults
The ContactTrajectoryResults struct is the top level struct for tracking contacts in a trajectory....
Definition: types.h:563
tesseract_collision::CollisionCheckConfig::type
CollisionEvaluatorType type
Specifies the type of collision check to be performed. Default: DISCRETE.
Definition: types.h:480
tesseract_collision::ContactResultMap::getContainer
const ContainerType & getContainer() const
Get the underlying container.
Definition: types.cpp:256
tesseract_collision::ContactManagerConfig::modify_object_enabled
std::unordered_map< std::string, bool > modify_object_enabled
Each key is an object name. Objects will be enabled/disabled based on the value. Objects that aren't ...
Definition: types.h:440
tesseract_collision::CollisionCheckConfig::check_program_mode
CollisionCheckProgramType check_program_mode
Secifies the mode used when collision checking program/trajectory. Default: ALL.
Definition: types.h:486
tesseract_collision::ContactResult::subshape_id
std::array< int, 2 > subshape_id
Some shapes like octomap and mesh have subshape (boxes and triangles)
Definition: types.h:96
tesseract_collision::ContactResultMap
This structure hold contact results for link pairs.
Definition: types.h:155
tesseract_collision::ContactResultMap::ContainerType
tesseract_common::AlignedMap< KeyType, MappedType > ContainerType
Definition: types.h:161
tesseract_collision::CollisionCheckConfig::contact_request
ContactRequest contact_request
ContactRequest that will be used for this check. Default test type: ALL.
Definition: types.h:477
tesseract_collision::ContactManagerConfig::default_margin
std::optional< double > default_margin
override the default contact margin
Definition: types.h:426
tesseract_collision::ContactTrajectorySubstepResults
The ContactTrajectorySubstepResults struct is the lowest level struct for tracking contacts in a traj...
Definition: types.h:497
tesseract_collision::CollisionCheckConfig
This is a high level structure containing common information that collision checking utilities need....
Definition: types.h:469
serialization.h
tesseract_collision::ContactTrajectoryStepResults::state0
Eigen::VectorXd state0
Definition: types.h:553
tesseract_collision::ContactTrajectorySubstepResults::contacts
tesseract_collision::ContactResultMap contacts
Definition: types.h:513
tesseract_collision::ContactTrajectoryStepResults::step
int step
Definition: types.h:552
tesseract_collision::ContactRequest::is_valid
std::shared_ptr< const ContactResultValidator > is_valid
This provides a user defined function approve/reject contact results.
Definition: types.h:316
boost::serialization
tesseract_collision::ContactResult::type_id
std::array< int, 2 > type_id
A user defined type id that is added to the contact shapes.
Definition: types.h:90
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
contact_result_validator.h
Contact result validator.
tesseract_collision::ContactTrajectorySubstepResults::state1
Eigen::VectorXd state1
Definition: types.h:516
tesseract_collision::ContactTrajectorySubstepResults::substep
int substep
Definition: types.h:514
tesseract_collision::ContactManagerConfig::pair_margin_override_type
CollisionMarginPairOverrideType pair_margin_override_type
Identify how the collision margin pair data should be applied to the contact manager.
Definition: types.h:429
tesseract_collision::ContactResult::distance
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double distance
The distance between two links.
Definition: types.h:88
tesseract_collision::ContactResult::cc_transform
std::array< Eigen::Isometry3d, 2 > cc_transform
The transform of link in world coordinates at its desired final location. Note: This is not the locat...
Definition: types.h:120
tesseract_collision::ContactResult::transform
std::array< Eigen::Isometry3d, 2 > transform
The transform of link in world coordinates.
Definition: types.h:102
serialization.h
Tesseracts Collision Serialization.
tesseract_collision::ContactTrajectoryStepResults
The ContactTrajectoryStepResults struct is the second level struct for tracking contacts in a traject...
Definition: types.h:524
tesseract_collision::ContactTrajectoryResults::joint_names
std::vector< std::string > joint_names
Definition: types.h:592
TESSERACT_SERIALIZE_FREE_ARCHIVES_INSTANTIATE
#define TESSERACT_SERIALIZE_FREE_ARCHIVES_INSTANTIATE(Type)
tesseract_collision::ContactResult::single_contact_point
bool single_contact_point
Some collision checkers only provide a single contact point for a given pair. This is used to indicat...
Definition: types.h:125
tesseract_collision::ContactManagerConfig::pair_margin_data
CollisionMarginPairData pair_margin_data
Stores collision margin pair data.
Definition: types.h:431
tesseract_collision::ContactResult::nearest_points
std::array< Eigen::Vector3d, 2 > nearest_points
The nearest point on both links in world coordinates.
Definition: types.h:98
tesseract_collision::ContactManagerConfig::acm
tesseract_common::AllowedCollisionMatrix acm
Additional AllowedCollisionMatrix to consider for this collision check.
Definition: types.h:434
tesseract_collision::ContactResult::nearest_points_local
std::array< Eigen::Vector3d, 2 > nearest_points_local
The nearest point on both links in local(link) coordinates.
Definition: types.h:100
macros.h
TESSERACT_SERIALIZE_SAVE_LOAD_FREE_ARCHIVES_INSTANTIATE
#define TESSERACT_SERIALIZE_SAVE_LOAD_FREE_ARCHIVES_INSTANTIATE(Type)
tesseract_collision::ContactTrajectoryResults::steps
std::vector< ContactTrajectoryStepResults > steps
Definition: types.h:591
tesseract_collision::ContactResult::link_names
std::array< std::string, 2 > link_names
The two links that are in contact.
Definition: types.h:92
tesseract_collision::ContactResult
Definition: types.h:81
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300
tesseract_collision::ContactTrajectorySubstepResults::state0
Eigen::VectorXd state0
Definition: types.h:515
eigen_serialization.h
tesseract_collision::ContactTrajectoryStepResults::state1
Eigen::VectorXd state1
Definition: types.h:554
tesseract_collision::ContactResult::cc_type
std::array< ContinuousCollisionType, 2 > cc_type
The type of continuous contact.
Definition: types.h:113
tesseract_collision::ContactManagerConfig::acm_override_type
ACMOverrideType acm_override_type
Specifies how to combine the ContactAllowedValidator from acm with the one preset in the contact mana...
Definition: types.h:436
tesseract_collision::ContactRequest::calculate_penetration
bool calculate_penetration
This enables the calculation of penetration contact data if two objects are in collision.
Definition: types.h:306
tesseract_collision::CollisionCheckConfig::longest_valid_segment_length
double longest_valid_segment_length
Longest valid segment to use if type supports lvs. Default: 0.005.
Definition: types.h:483


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52