Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
boost::serialization Namespace Reference

Functions

template<class Archive >
void save (Archive &ar, const carma_wm::TrafficControl &gf, unsigned int)
 
template<class Archive >
void load (Archive &ar, carma_wm::TrafficControl &gf, unsigned int)
 
template<class Archive >
void save (Archive &ar, const carma_wm::SignalizedIntersectionManager &sim, unsigned int)
 
template<class Archive >
void load (Archive &ar, carma_wm::SignalizedIntersectionManager &sim, unsigned int)
 
template<typename Archive >
void serialize (Archive &ar, std::pair< lanelet::Id, lanelet::RegulatoryElementPtr > &p, unsigned int)
 
template<typename Archive >
void serialize (Archive &ar, std::pair< uint8_t, lanelet::Id > &p, unsigned int)
 
template<typename Archive >
void serialize (Archive &ar, std::pair< uint16_t, lanelet::Id > &p, unsigned int)
 
template<typename Archive >
void serialize (Archive &ar, std::pair< uint32_t, lanelet::Id > &p, unsigned int)
 

Function Documentation

◆ load() [1/2]

template<class Archive >
void boost::serialization::load ( Archive &  ar,
carma_wm::SignalizedIntersectionManager sim,
unsigned int   
)
inline

Definition at line 242 of file TrafficControl.hpp.

243{
244 // save traffic light id lookup
245 size_t intersection_id_to_regem_id_size;
246 ar >> intersection_id_to_regem_id_size;
247 for (size_t i = 0; i < intersection_id_to_regem_id_size; i ++)
248 {
249 std::pair<uint16_t, lanelet::Id> pair;
250 ar >> pair;
251 sim.intersection_id_to_regem_id_.emplace(pair);
252 }
253
254 // save traffic light id lookup
255 size_t signal_group_to_traffic_light_id_size;
256 ar >> signal_group_to_traffic_light_id_size;
257 for (size_t i = 0; i < signal_group_to_traffic_light_id_size; i ++)
258 {
259 std::pair<uint8_t, lanelet::Id> pair;
260 ar >> pair;
261 sim.signal_group_to_traffic_light_id_.emplace(pair);
262 }
263
264 size_t signal_group_to_exit_lanelet_ids_size;
265 ar >> signal_group_to_exit_lanelet_ids_size;
266 for (size_t i = 0; i < signal_group_to_exit_lanelet_ids_size; i ++)
267 {
268 size_t set_size;
269 ar >> set_size;
270 uint8_t signal_grp;
271 ar >> signal_grp;
272 for (size_t j = 0; j <set_size; j++)
273 {
274 lanelet::Id id;
275 ar >>id;
276 sim.signal_group_to_exit_lanelet_ids_[signal_grp].insert(id);
277 }
278 }
279
280 size_t signal_group_to_entry_lanelet_ids_size;
281 ar >> signal_group_to_entry_lanelet_ids_size;
282 for (size_t i = 0; i < signal_group_to_entry_lanelet_ids_size; i ++)
283 {
284 size_t set_size;
285 ar >> set_size;
286 uint8_t signal_grp;
287 ar >> signal_grp;
288 for (size_t j = 0; j <set_size; j++)
289 {
290 lanelet::Id id;
291 ar >>id;
292 sim.signal_group_to_entry_lanelet_ids_[signal_grp].insert(id);
293 }
294 }
295
296}
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_entry_lanelet_ids_
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_exit_lanelet_ids_
std::unordered_map< uint8_t, lanelet::Id > signal_group_to_traffic_light_id_

References process_bag::i, carma_wm::SignalizedIntersectionManager::intersection_id_to_regem_id_, carma_wm::SignalizedIntersectionManager::signal_group_to_entry_lanelet_ids_, carma_wm::SignalizedIntersectionManager::signal_group_to_exit_lanelet_ids_, and carma_wm::SignalizedIntersectionManager::signal_group_to_traffic_light_id_.

◆ load() [2/2]

template<class Archive >
void boost::serialization::load ( Archive &  ar,
carma_wm::TrafficControl gf,
unsigned int   
)
inline

Definition at line 140 of file TrafficControl.hpp.

141{
142 boost::uuids::string_generator gen;
143 std::string id;
144 ar >> id;
145 gf.id_ = gen(id);
146
147 // save llts to add
148 size_t lanelet_additions_size;
149 ar >> lanelet_additions_size;
150 for (auto i = 0u; i < lanelet_additions_size; ++i)
151 {
152 lanelet::Lanelet llt;
153 ar >> llt;
154 gf.lanelet_additions_.push_back(llt);
155 }
156
157 // save regems to remove
158 size_t remove_list_size;
159 ar >> remove_list_size;
160 for (auto i = 0u; i < remove_list_size; ++i)
161 {
162 std::pair<lanelet::Id, lanelet::RegulatoryElementPtr> remove_item;
163 ar >> remove_item;
164 gf.remove_list_.push_back(remove_item);
165 }
166
167 // save parts that need to be updated
168 size_t update_list_size;
169 ar >> update_list_size;
170
171 for (auto i = 0u; i < update_list_size; ++i)
172 {
173 std::pair<lanelet::Id, lanelet::RegulatoryElementPtr> update_item;
174 ar >> update_item;
175 gf.update_list_.push_back(update_item);
176 }
177
178 // save ids
179 size_t traffic_light_id_lookup_size;
180 ar >> traffic_light_id_lookup_size;
181 for (auto i = 0u; i < traffic_light_id_lookup_size; ++i)
182 {
183 std::pair<uint32_t, lanelet::Id> traffic_light_id_pair;
184 ar >> traffic_light_id_pair;
185 gf.traffic_light_id_lookup_.push_back(traffic_light_id_pair);
186 }
187
188 // save signalized intersection manager
189 ar >> gf.sim_;
190}
std::vector< std::pair< lanelet::Id, lanelet::RegulatoryElementPtr > > update_list_
carma_wm::SignalizedIntersectionManager sim_
std::vector< std::pair< lanelet::Id, lanelet::RegulatoryElementPtr > > remove_list_
boost::uuids::uuid id_
std::vector< lanelet::Lanelet > lanelet_additions_
std::vector< std::pair< uint32_t, lanelet::Id > > traffic_light_id_lookup_

References process_bag::i, carma_wm::TrafficControl::id_, carma_wm::TrafficControl::lanelet_additions_, carma_wm::TrafficControl::remove_list_, carma_wm::TrafficControl::sim_, carma_wm::TrafficControl::traffic_light_id_lookup_, and carma_wm::TrafficControl::update_list_.

◆ save() [1/2]

template<class Archive >
void boost::serialization::save ( Archive &  ar,
const carma_wm::SignalizedIntersectionManager sim,
unsigned int   
)
inline

Definition at line 195 of file TrafficControl.hpp.

196{
197 // convert traffic light id lookup
198 size_t intersection_id_to_regem_id_size = sim.intersection_id_to_regem_id_.size();
199 ar << intersection_id_to_regem_id_size;
200 for (auto pair : sim.intersection_id_to_regem_id_)
201 {
202 ar << pair;
203 }
204
205 // convert traffic light id lookup
206 size_t signal_group_to_traffic_light_id_size = sim.signal_group_to_traffic_light_id_.size();
207 ar << signal_group_to_traffic_light_id_size;
208 for (auto pair : sim.signal_group_to_traffic_light_id_)
209 {
210 ar << pair;
211 }
212
213 size_t signal_group_to_exit_lanelet_ids_size = sim.signal_group_to_exit_lanelet_ids_.size();
214 ar << signal_group_to_exit_lanelet_ids_size;
215 for (auto pair : sim.signal_group_to_exit_lanelet_ids_)
216 {
217 size_t set_size = pair.second.size();
218 ar << set_size;
219 ar << pair.first;
220 for (auto iter = pair.second.begin(); iter != pair.second.end(); iter++)
221 {
222 ar << *iter;
223 }
224 }
225
226 size_t signal_group_to_entry_lanelet_ids_size = sim.signal_group_to_entry_lanelet_ids_.size();
227 ar << signal_group_to_entry_lanelet_ids_size;
228 for (auto pair : sim.signal_group_to_entry_lanelet_ids_)
229 {
230 size_t set_size = pair.second.size();
231 ar << set_size;
232 ar << pair.first;
233 for (auto iter = pair.second.begin(); iter != pair.second.end(); iter++)
234 {
235 ar << *iter;
236 }
237 }
238}

References carma_wm::SignalizedIntersectionManager::intersection_id_to_regem_id_, carma_wm::SignalizedIntersectionManager::signal_group_to_entry_lanelet_ids_, carma_wm::SignalizedIntersectionManager::signal_group_to_exit_lanelet_ids_, and carma_wm::SignalizedIntersectionManager::signal_group_to_traffic_light_id_.

◆ save() [2/2]

template<class Archive >
void boost::serialization::save ( Archive &  ar,
const carma_wm::TrafficControl gf,
unsigned int   
)
inline

Definition at line 109 of file TrafficControl.hpp.

110{
111 std::string string_id = boost::uuids::to_string(gf.id_);
112 ar << string_id;
113
114 // convert the lanelet that need to be added
115 size_t lanelet_additions_size = gf.lanelet_additions_.size();
116 ar << lanelet_additions_size;
117 for (auto llt : gf.lanelet_additions_) ar << llt;
118
119 // convert the regems that need to be removed
120 size_t remove_list_size = gf.remove_list_.size();
121 ar << remove_list_size;
122 for (auto pair : gf.remove_list_) ar << pair;
123
124 // convert id, regem pairs that need to be updated
125 size_t update_list_size = gf.update_list_.size();
126 ar << update_list_size;
127 for (auto pair : gf.update_list_) ar << pair;
128
129 // convert traffic light id lookup
130 size_t traffic_light_id_lookup_size = gf.traffic_light_id_lookup_.size();
131 ar << traffic_light_id_lookup_size;
132 for (auto pair : gf.traffic_light_id_lookup_) ar << pair;
133
134 // convert signalized intersection manager
135 ar << gf.sim_;
136}
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

References carma_wm::TrafficControl::id_, carma_wm::TrafficControl::lanelet_additions_, carma_wm::TrafficControl::remove_list_, carma_wm::TrafficControl::sim_, carma_cooperative_perception::to_string(), carma_wm::TrafficControl::traffic_light_id_lookup_, and carma_wm::TrafficControl::update_list_.

Here is the call graph for this function:

◆ serialize() [1/4]

template<typename Archive >
void boost::serialization::serialize ( Archive &  ar,
std::pair< lanelet::Id, lanelet::RegulatoryElementPtr > &  p,
unsigned int   
)

Definition at line 299 of file TrafficControl.hpp.

300{
301 ar& p.first;
302 ar& p.second;
303}

◆ serialize() [2/4]

template<typename Archive >
void boost::serialization::serialize ( Archive &  ar,
std::pair< uint16_t, lanelet::Id > &  p,
unsigned int   
)

Definition at line 313 of file TrafficControl.hpp.

314{
315 ar& p.first;
316 ar& p.second;
317}

◆ serialize() [3/4]

template<typename Archive >
void boost::serialization::serialize ( Archive &  ar,
std::pair< uint32_t, lanelet::Id > &  p,
unsigned int   
)

Definition at line 320 of file TrafficControl.hpp.

321{
322 ar& p.first;
323 ar& p.second;
324}

◆ serialize() [4/4]

template<typename Archive >
void boost::serialization::serialize ( Archive &  ar,
std::pair< uint8_t, lanelet::Id > &  p,
unsigned int   
)

Definition at line 306 of file TrafficControl.hpp.

307{
308 ar& p.first;
309 ar& p.second;
310}