Carma-platform v4.10.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.
carma_cloud_client_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17
18namespace carma_cloud_client
19{
20 namespace std_ph = std::placeholders;
21
22 CarmaCloudClient::CarmaCloudClient(const rclcpp::NodeOptions &options)
23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25 // Create initial config
26 config_ = Config();
27
28 // Declare parameters
29 config_.url = declare_parameter<std::string>("url", config_.url);
30 config_.base_req = declare_parameter<std::string>("base_req", config_.base_req);
31 config_.base_ack = declare_parameter<std::string>("base_ack", config_.base_ack);
32 config_.port = declare_parameter<std::string>("port", config_.port);
33 config_.list = declare_parameter<std::string>("list", config_.list);
34 config_.method = declare_parameter<std::string>("method", config_.method);
35 config_.fetchtime = declare_parameter<int>("fetchtime", config_.fetchtime);
36 config_.webport = declare_parameter<uint16_t>("webport", config_.webport);
37 config_.webip = declare_parameter<std::string>("webip", config_.webip);
38
39 }
40
41 rcl_interfaces::msg::SetParametersResult CarmaCloudClient::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
42 {
43
44 auto error = update_params<std::string>({{"url", config_.url},
45 {"base_req", config_.base_req},
46 {"base_ack", config_.base_ack},
47 {"port", config_.port},
48 {"list", config_.list},
49 {"method", config_.method}} , parameters);
50
51 rcl_interfaces::msg::SetParametersResult result;
52
53 result.successful = !error;
54
55 return result;
56 }
57
58 carma_ros2_utils::CallbackReturn CarmaCloudClient::handle_on_configure(const rclcpp_lifecycle::State &)
59 {
60 RCLCPP_DEBUG_STREAM(this->get_logger(), "CarmaCloudClient trying to configure");
61 // Reset config
62 config_ = Config();
63 // Load parameters
64 get_parameter<std::string>("url", config_.url);
65 get_parameter<std::string>("base_req", config_.base_req);
66 get_parameter<std::string>("base_ack", config_.base_ack);
67 get_parameter<std::string>("port", config_.port);
68 get_parameter<std::string>("list", config_.list);
69 get_parameter<std::string>("method", config_.method);
70 get_parameter<int>("fetchtime", config_.fetchtime);
71 get_parameter<std::string>("webip", config_.webip);
72 get_parameter<uint16_t>("webport", config_.webport);
73
74 // Register runtime parameter update callback
75 add_on_set_parameters_callback(std::bind(&CarmaCloudClient::parameter_update_callback, this, std_ph::_1));
76 // Setup subscribers
77 tcr_sub_ = create_subscription<carma_v2x_msgs::msg::TrafficControlRequest>("outgoing_geofence_request", 10,
78 std::bind(&CarmaCloudClient::tcr_callback, this, std_ph::_1));
79 tcm_pub_ = create_publisher<j2735_v2x_msgs::msg::TrafficControlMessage>("incoming_j2735_geofence_control", 1);
80 std::thread webthread(&CarmaCloudClient::StartWebService,this);
81 webthread.detach(); // wait for the thread to finish
82 // Return success if everything initialized successfully
83 return CallbackReturn::SUCCESS;
84 }
85
86 void CarmaCloudClient::tcr_callback(carma_v2x_msgs::msg::TrafficControlRequest::UniquePtr msg)
87 {
88 carma_v2x_msgs::msg::TrafficControlRequest request_msg(*msg.get());
89
90 char xml_str[10000];
91
92 XMLconversion(xml_str, request_msg);
93
95
96 RCLCPP_DEBUG_STREAM( get_logger(), "tcr_sub_ callback called ");
97 }
98
99 void CarmaCloudClient::XMLconversion(char* xml_str, carma_v2x_msgs::msg::TrafficControlRequest request_msg)
100 {
101 j2735_v2x_msgs::msg::TrafficControlRequest j2735_tcr;
102
103 j2735_convertor::geofence_request::convert(request_msg, j2735_tcr);
104
105 RCLCPP_DEBUG_STREAM( get_logger(), "converted: ");
106
107 size_t hexlen = 2; //size of each hex representation with a leading 0
108 char reqid[j2735_tcr.tcr_v01.reqid.id.size() * hexlen + 1];
109 for (int i = 0; i < j2735_tcr.tcr_v01.reqid.id.size(); i++)
110 {
111 sprintf(reqid+(i*hexlen), "%.2X", j2735_tcr.tcr_v01.reqid.id[i]);
112 }
113
114 RCLCPP_DEBUG_STREAM( get_logger(), "reqid: " << reqid);
115
116 long int reqseq = j2735_tcr.tcr_v01.reqseq;
117 RCLCPP_DEBUG_STREAM( get_logger(), "reqseq: " << reqseq);
118
119 long int scale = j2735_tcr.tcr_v01.scale;
120 RCLCPP_DEBUG_STREAM( get_logger(), "scale: " << scale);
121
122 int totBounds = j2735_tcr.tcr_v01.bounds.size();
123 int cnt=0;
124 char bounds_str[5000];
125 strcpy(bounds_str,"");
126
127 // get current time
128 std::time_t tm = this->now().seconds()/60 - config_.fetchtime*24*60; // T minus fetchtime*24 hours in min
129
130 while(cnt<totBounds)
131 {
132
133 uint32_t oldest = tm;
134 long lat = j2735_tcr.tcr_v01.bounds[cnt].reflat;
135 long longg = j2735_tcr.tcr_v01.bounds[cnt].reflon;
136
137
138 long dtx0 = j2735_tcr.tcr_v01.bounds[cnt].offsets[0].deltax;
139 long dty0 = j2735_tcr.tcr_v01.bounds[cnt].offsets[0].deltay;
140 long dtx1 = j2735_tcr.tcr_v01.bounds[cnt].offsets[1].deltax;
141 long dty1 = j2735_tcr.tcr_v01.bounds[cnt].offsets[1].deltay;
142 long dtx2 = j2735_tcr.tcr_v01.bounds[cnt].offsets[2].deltax;
143 long dty2 = j2735_tcr.tcr_v01.bounds[cnt].offsets[2].deltay;
144
145 int x = std::sprintf(bounds_str+strlen(bounds_str),"<bounds><TrafficControlBounds><oldest>%ld</oldest><reflon>%ld</reflon><reflat>%ld</reflat><offsets><OffsetPoint><deltax>%ld</deltax><deltay>%ld</deltay></OffsetPoint><OffsetPoint><deltax>%ld</deltax><deltay>%ld</deltay></OffsetPoint><OffsetPoint><deltax>%ld</deltax><deltay>%ld</deltay></OffsetPoint></offsets></TrafficControlBounds></bounds>",oldest,longg,lat,dtx0,dty0,dtx1,dty1,dtx2,dty2);
146
147 cnt++;
148
149 }
150
151 char list[config_.list.size() + 1];
152 strcpy(list, config_.list.c_str());
153
154 // with port and list
155 sprintf(xml_str,"<?xml version=\"1.0\" encoding=\"UTF-8\"?><TrafficControlRequest port=\"%s\" list=\"%s\"><reqid>%s</reqid><reqseq>%ld</reqseq><scale>%ld</scale>%s</TrafficControlRequest>", std::to_string(config_.webport).c_str(), list, reqid, reqseq,scale,bounds_str);
156
157 RCLCPP_DEBUG_STREAM( get_logger(), "xml_str: " << xml_str);
158
159 }
160
161 int CarmaCloudClient::CloudSend(const std::string &local_msg, const std::string& local_url, const std::string& local_base, const std::string& local_method)
162 {
163 CURL *req;
164 CURLcode res;
165 std::string urlfull = local_url + config_.port + local_base;
166 RCLCPP_DEBUG_STREAM( get_logger(), "full url: " << urlfull);
167 req = curl_easy_init();
168 if(req) {
169 curl_easy_setopt(req, CURLOPT_URL, urlfull.c_str());
170
171 if(strcmp(local_method.c_str(),"POST")==0)
172 {
173 curl_easy_setopt(req, CURLOPT_POSTFIELDS, local_msg.c_str());
174 curl_easy_setopt(req, CURLOPT_TIMEOUT_MS, 1000L); // Request operation complete within max millisecond timeout
175 res = curl_easy_perform(req);
176 if(res != CURLE_OK)
177 {
178 RCLCPP_ERROR_STREAM( get_logger(), "curl send failed: " << curl_easy_strerror(res));
179 return 1;
180 }
181 }
182 curl_easy_cleanup(req);
183 }
184
185 return 0;
186 }
187
188 void CarmaCloudClient::CloudSendAsync(const std::string& local_msg,const std::string& local_url, const std::string& local_base, const std::string& local_method)
189 {
190 std::thread t([this, &local_msg, &local_url, &local_base, &local_method](){
191 CloudSend(local_msg, local_url, local_base, local_method);
192 });
193 t.detach();
194 }
195
196 QByteArray CarmaCloudClient::UncompressBytes(const QByteArray compressedBytes) const
197 {
198 z_stream strm;
199 strm.zalloc = nullptr;//Refer to zlib docs (https://zlib.net/zlib_how.html)
200 strm.zfree = nullptr;
201 strm.opaque = nullptr;
202 strm.avail_in = compressedBytes.size();
203 strm.next_in = (Byte *)compressedBytes.data();
204 //checking input z_stream to see if there is any error, eg: invalid data etc.
205 auto err = inflateInit2(&strm, MAX_WBITS + 16); // gzip input
206 QByteArray outBuf;
207 //MAX numbers of bytes stored in a buffer
208 const int BUFFER_SIZE = 4092;
209 //There is successful, starting to decompress data
210 if (err == Z_OK)
211 {
212 int isDone = 0;
213 do
214 {
215 char buffer[BUFFER_SIZE] = {0};
216 strm.avail_out = BUFFER_SIZE;
217 strm.next_out = (Byte *)buffer;
218 //Uncompress finished
219 isDone = inflate(&strm, Z_FINISH);
220 outBuf.append(buffer);
221 } while (Z_STREAM_END != isDone); //Reach the end of stream to be uncompressed
222 }
223 else
224 {
225 RCLCPP_DEBUG_STREAM( get_logger(), "Error initalize stream. Err code = " << err);
226 }
227 //Finished decompress data stream
228 inflateEnd(&strm);
229 return outBuf;
230 }
231
232 void CarmaCloudClient::TCMHandler(QHttpEngine::Socket *socket)
233 {
234 QString st;
235 while(socket->bytesAvailable()>0)
236 {
237 auto readBytes = socket->readAll();
238 if (socket->headers().keys().contains(CONTENT_ENCODING_KEY) && std::string(socket->headers().constFind(CONTENT_ENCODING_KEY).value().data()) == CONTENT_ENCODING_VALUE)
239 {
240 //readBytes is compressed in gzip format
241 st.append(UncompressBytes(readBytes));
242 }
243 else
244 {
245 st.append(readBytes);
246 }
247
248 }
249 QByteArray array = st.toLocal8Bit();
250
251 char* _cloudUpdate = array.data(); // would be the cloud update packet, needs parsing
252
253
254 std::string tcm_string = _cloudUpdate;
255
256 RCLCPP_DEBUG_STREAM( get_logger(), "Received TCM from cloud");
257 RCLCPP_DEBUG_STREAM( get_logger(), "TCM in XML format: " << tcm_string);
258 if(tcm_string.length() == 0)
259 {
260 RCLCPP_DEBUG_STREAM( get_logger(), "Received TCM length is zero, and skipped.");
261 return;
262 }
263
264 boost::property_tree::ptree list_tree;
265 std :: stringstream ss;
266 ss << tcm_string;
267 read_xml(ss, list_tree);
268
269
270 auto child_tcm_list = list_tree.get_child_optional("TrafficControlMessageList");
271
272 if (!child_tcm_list)
273 {
274 auto child_tree = list_tree.get_child("TrafficControlMessage");
275 j2735_v2x_msgs::msg::TrafficControlMessage parsed_tcm = parseTCMXML(child_tree);
276 tcm_pub_->publish(parsed_tcm);
277 }
278 else
279 {
280 auto tcm_list = child_tcm_list.get();
281
282 BOOST_FOREACH(auto &node, list_tree.get_child("TrafficControlMessageList"))
283 {
284 j2735_v2x_msgs::msg::TrafficControlMessage parsed_tcm = parseTCMXML(node.second);
285 tcm_pub_->publish(parsed_tcm);
286 }
287
288 }
289
290
291 }
292
293 j2735_v2x_msgs::msg::TrafficControlMessage CarmaCloudClient::parseTCMXML(boost::property_tree::ptree& tree)
294 {
295 j2735_v2x_msgs::msg::TrafficControlMessage tcm;
296
297 auto child_tcmv01 = tree.get_child_optional("tcmV01");
298 if (!child_tcmv01)
299 {
300 tcm.choice = j2735_v2x_msgs::msg::TrafficControlMessage::RESERVED;
301 return tcm;
302 }
303 else tcm.choice = j2735_v2x_msgs::msg::TrafficControlMessage::TCMV01;
304
305 std::string reqid_string = tree.get<std::string>("tcmV01.reqid");
306 j2735_v2x_msgs::msg::Id64b output;
307 for (std::size_t i = 0; i != reqid_string.size() / 2; ++i)
308 {
309 tcm.tcm_v01.reqid.id[i] = 16 * parse_hex(reqid_string[2 * i]) + parse_hex(reqid_string[2 * i + 1]);
310 }
311
312 tcm.tcm_v01.reqseq = tree.get<uint8_t>("tcmV01.reqseq");
313 tcm.tcm_v01.msgtot = tree.get<uint16_t>("tcmV01.msgtot");
314 tcm.tcm_v01.msgnum = tree.get<uint16_t>("tcmV01.msgnum");
315
316 std::string id_string = tree.get<std::string>("tcmV01.id");
317 for (std::size_t i = 0; i != id_string.size() / 2; ++i)
318 {
319 tcm.tcm_v01.id.id[i] = 16 * parse_hex(id_string[2 * i]) + parse_hex(id_string[2 * i + 1]);
320 }
321
322 tcm.tcm_v01.updated = tree.get<uint64_t>("tcmV01.updated");
323
324 auto tree_package = tree.get_child_optional("tcmV01.package");
325 if (!tree_package)
326 {
327 tcm.tcm_v01.package_exists = false;
328 }
329 else
330 {
331 tcm.tcm_v01.package_exists = true;
332 tcm.tcm_v01.package = parse_package(tree_package.get());
333 }
334
335 auto tree_params = tree.get_child_optional("tcmV01.params");
336 if (!tree_params)
337 {
338 tcm.tcm_v01.params_exists = false;
339 }
340 else
341 {
342 tcm.tcm_v01.params_exists = true;
343 tcm.tcm_v01.params = parse_params(tree_params.get());
344 }
345
346 auto tree_geometry = tree.get_child_optional("tcmV01.geometry");
347 if (!tree_geometry)
348 {
349 tcm.tcm_v01.geometry_exists = false;
350 }
351 else
352 {
353 tcm.tcm_v01.geometry_exists = true;
354 tcm.tcm_v01.geometry = parse_geometry(tree_geometry.get());
355 }
356
357
358 return tcm;
359 }
360
361
363 {
364 //Web services
365 char *placeholderX[1]={0};
366 int placeholderC=1;
367 QCoreApplication a(placeholderC,placeholderX);
368
369 QHostAddress address = QHostAddress(QString::fromStdString (config_.webip));
370 quint16 port = static_cast<quint16>(config_.webport);
371
372 QSharedPointer<OpenAPI::OAIApiRequestHandler> handler(new OpenAPI::OAIApiRequestHandler());
373 handler = QSharedPointer<OpenAPI::OAIApiRequestHandler> (new OpenAPI::OAIApiRequestHandler());
374 auto router = QSharedPointer<OpenAPI::OAIApiRouter>::create();
375 router->setUpRoutes();
376
377 QObject::connect(handler.data(), &OpenAPI::OAIApiRequestHandler::requestReceived, [&](QHttpEngine::Socket *socket) {
378 TCMHandler(socket);
379 });
380
381 QObject::connect(handler.data(), &OpenAPI::OAIApiRequestHandler::requestReceived, [&](QHttpEngine::Socket *socket) {
382 router->processRequest(socket);
383 });
384 QHttpEngine::Server server(handler.data());
385
386 if (!server.listen(address, port)) {
387 qCritical("Unable to listen on the specified port.");
388 return 1;
389 }
390
391 RCLCPP_DEBUG_STREAM(this->get_logger(), "CarmaCloudClient :: Started web service");
392 return a.exec();
393
394 }
395
396 j2735_v2x_msgs::msg::TrafficControlPackage CarmaCloudClient::parse_package(boost::property_tree::ptree& tree)
397 {
398 j2735_v2x_msgs::msg::TrafficControlPackage tcm_pkg;
399
400 auto tree_label = tree.get_child_optional("label");
401 if( !tree_label )
402 {
403 tcm_pkg.label_exists = false;
404 }
405 else
406 {
407 tcm_pkg.label_exists = true;
408 tcm_pkg.label = tree.get<std::string>("label");
409 }
410
411 std::string tcids_string = tree.get<std::string>("tcids");
412
413 return tcm_pkg;
414
415 }
416
417 j2735_v2x_msgs::msg::TrafficControlSchedule CarmaCloudClient::parse_schedule(boost::property_tree::ptree& tree)
418 {
419 j2735_v2x_msgs::msg::TrafficControlSchedule tcm_schedule;
420 tcm_schedule.start = tree.get<uint64_t>("schedule.start");
421
422 auto child_end = tree.get_child_optional("schedule.end");
423 if (!child_end)
424 {
425 tcm_schedule.end_exists = false;
426 }
427 else
428 {
429 tcm_schedule.end_exists = true;
430 tcm_schedule.end = tree.get<uint64_t>("schedule.end");
431 }
432
433 auto child_dow = tree.get_child_optional("schedule.dow");
434 if (!child_dow)
435 {
436 tcm_schedule.dow_exists = false;
437 }
438 else
439 {
440 tcm_schedule.dow_exists = true;
441 std::string dow_string = tree.get<std::string>("schedule.dow");
442 for (size_t i=0; i<dow_string.size(); i++)
443 {
444 tcm_schedule.dow.dow[i] = dow_string[i] - '0';
445 }
446 }
447 auto child_between = tree.get_child_optional("schedule.between");
448 if( !child_between )
449 {
450 tcm_schedule.between_exists = false;
451 }
452 else
453 {
454 tcm_schedule.between_exists = true;
455 auto child_tree = child_between.get();
456
457 for (auto& item : tree.get_child("schedule.between"))
458 {
459 j2735_v2x_msgs::msg::DailySchedule daily;
460 for (auto& which : item.second)
461 {
462 if (which.first == "begin")
463 {
464 daily.begin = which.second.get_value<uint16_t>();
465 }
466 else if (which.first == "duration")
467 {
468 daily.duration = which.second.get_value<uint16_t>();
469 }
470 }
471 tcm_schedule.between.push_back(daily);
472 }
473 }
474 auto child_repeat = tree.get_child_optional("schedule.repeat");
475
476 if(!child_repeat)
477 {
478 tcm_schedule.repeat_exists = false;
479 }
480 else
481 {
482 tcm_schedule.repeat_exists = true;
483 tcm_schedule.repeat.offset = child_repeat.get().get<uint16_t>("offset");
484 tcm_schedule.repeat.period = child_repeat.get().get<uint16_t>("period");
485 tcm_schedule.repeat.span = child_repeat.get().get<uint16_t>("span");
486 }
487
488 return tcm_schedule;
489 }
490
491 j2735_v2x_msgs::msg::TrafficControlDetail CarmaCloudClient::parse_detail(boost::property_tree::ptree& tree)
492 {
493 j2735_v2x_msgs::msg::TrafficControlDetail tcm_detail;
494
495 auto detail_tree = tree.get_child("detail");
496
497
498 auto closed_tree = detail_tree.get_child_optional( "closed" );
499 if (closed_tree)
500 {
501 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::CLOSED_CHOICE;
502
503 auto open = closed_tree.get().get_child_optional("open");
504 if (open)
505 {
506 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPEN;
507 }
508
509 auto notopen = closed_tree.get().get_child_optional("notopen");
510 if (notopen)
511 {
512 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::CLOSED;
513 }
514
515 auto taperleft = closed_tree.get().get_child_optional("taperleft");
516 if (taperleft)
517 {
518 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::TAPERLEFT;
519 }
520
521 auto taperright = closed_tree.get().get_child_optional("taperright");
522 if (taperright)
523 {
524 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::TAPERRIGHT;
525 }
526
527 auto openleft = closed_tree.get().get_child_optional("openleft");
528 if (openleft)
529 {
530 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPENLEFT;
531 }
532
533 auto openright = closed_tree.get().get_child_optional("openright");
534 if (openright)
535 {
536 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPENRIGHT;
537 }
538
539 }
540
541 auto child_dir= detail_tree.get_child_optional( "direction" );
542 if (child_dir)
543 {
544 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::DIRECTION_CHOICE;
545
546 auto direction = child_dir.get().get_child_optional("reverse");
547 if (direction)
548 {
549 tcm_detail.direction = j2735_v2x_msgs::msg::TrafficControlDetail::REVERSE;
550 }
551 else tcm_detail.direction = j2735_v2x_msgs::msg::TrafficControlDetail::FORWARD;
552
553 }
554
555 auto child_chains = detail_tree.get_child_optional( "chains" );
556 if( child_chains )
557 {
558 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::CHAINS_CHOICE;
559 auto no = child_chains.get().get_child_optional("no");
560 if (no)
561 {
562 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::NO;
563 }
564 auto permitted = child_chains.get().get_child_optional("permitted");
565 if (permitted)
566 {
567 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::PERMITTED;
568 }
569 auto required = child_chains.get().get_child_optional("required");
570 if (required)
571 {
572 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::REQUIRED;
573 }
574 }
575
576 auto child_mins = tree.get_child_optional( "detail.minspeed" );
577 if( child_mins )
578 {
579 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINSPEED_CHOICE;
580 tcm_detail.minspeed = tree.get<float>("detail.minspeed");
581 }
582
583 auto child_maxs = tree.get_child_optional("detail.maxspeed");
584 if( child_maxs )
585 {
586 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXSPEED_CHOICE;
587 tcm_detail.maxspeed = tree.get<uint16_t>("detail.maxspeed");
588 }
589
590 auto child_minhdwy = tree.get_child_optional("detail.minhdwy");
591 if( child_minhdwy )
592 {
593 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINHDWY_CHOICE;
594 tcm_detail.minhdwy = tree.get<uint16_t>("detail.minhdwy");
595 }
596
597 auto child_maxvehmass = tree.get_child_optional("detail.maxvehmass");
598 if( child_maxvehmass )
599 {
600 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHMASS_CHOICE;
601 tcm_detail.maxvehmass = tree.get<uint16_t>("detail.maxvehmass");
602 }
603
604 auto child_maxvehheight = tree.get_child_optional("detail.maxvehheight");
605 if( child_maxvehheight )
606 {
607 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHHEIGHT_CHOICE;
608 tcm_detail.maxvehheight = tree.get<uint8_t>("detail.maxvehheight");
609 }
610
611 auto child_maxvehwidth = tree.get_child_optional("detail.maxvehwidth");
612 if( child_maxvehwidth )
613 {
614 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHWIDTH_CHOICE;
615 tcm_detail.maxvehwidth = tree.get<uint8_t>("detail.maxvehwidth");
616 }
617
618 auto child_maxvehlength = tree.get_child_optional("detail.maxvehlength");
619 if( child_maxvehlength )
620 {
621 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHLENGTH_CHOICE;
622 tcm_detail.maxvehlength = tree.get<uint16_t>("detail.maxvehlength");
623 }
624
625 auto child_maxvehaxles = tree.get_child_optional("detail.maxvehaxles");
626 if( child_maxvehaxles)
627 {
628 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHAXLES_CHOICE;
629 tcm_detail.maxvehaxles = tree.get<uint8_t>("detail.maxvehaxles");
630 }
631
632 auto child_minvehocc = tree.get_child_optional("detail.minvehocc");
633 if( child_minvehocc)
634 {
635 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINVEHOCC_CHOICE;
636 tcm_detail.minvehocc = tree.get<uint8_t>("detail.minvehocc");
637 }
638
639 auto child_maxplatoonsize = tree.get_child_optional("detail.maxplatoonsize");
640 if( child_maxplatoonsize)
641 {
642 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXPLATOONSIZE_CHOICE;
643 tcm_detail.maxplatoonsize = tree.get<uint8_t>("detail.maxplatoonsize");
644 }
645
646 auto child_minplatoonhdwy = tree.get_child_optional("detail.minplatoonhdwy");
647 if( child_minplatoonhdwy)
648 {
649 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINPLATOONHDWY_CHOICE;
650 tcm_detail.minplatoonhdwy = tree.get<uint16_t>("detail.minplatoonhdwy");
651 }
652
653 return tcm_detail;
654 }
655
656 j2735_v2x_msgs::msg::TrafficControlParams CarmaCloudClient::parse_params(boost::property_tree::ptree& tree)
657 {
658 j2735_v2x_msgs::msg::TrafficControlParams tcm_params;
659 for (auto& item : tree.get_child("vclasses"))
660 {
661 j2735_v2x_msgs::msg::TrafficControlVehClass vclass;
662 if (item.first == "any")
663 {
664 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::ANY;
665 }
666 else if (item.first == "pedestrian")
667 {
668 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::PEDESTRIAN;
669 }
670 else if (item.first == "bicycle")
671 {
672 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::BICYCLE;
673 }
674 else if (tree.count("micromobile") != 0)
675 {
676 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::MICROMOBILE;
677 }
678 else if (item.first == "motorcycle")
679 {
680 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::MOTORCYCLE;
681 }
682 else if (item.first == "passenger-car")
683 {
684 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::PASSENGER_CAR;
685 }
686 else if (item.first == "light-truck-van")
687 {
688 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::LIGHT_TRUCK_VAN;
689 }
690 else if (item.first == "bus")
691 {
692 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::BUS;
693 }
694 else if (item.first == "two-axle-six-tire-single-unit-truck")
695 {
696 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::TWO_AXLE_SIX_TIRE_SINGLE_UNIT_TRUCK;
697 }
698 else if (item.first == "three-axle-single-unit-truck")
699 {
700 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::THREE_AXLE_SINGLE_UNIT_TRUCK;
701 }
702 else if (item.first == "four-or-more-axle-single-unit-truck")
703 {
704 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FOUR_OR_MORE_AXLE_SINGLE_UNIT_TRUCK;
705 }
706 else if (item.first == "four-or-fewer-axle-single-trailer-truck")
707 {
708 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FOUR_OR_FEWER_AXLE_SINGLE_TRAILER_TRUCK;
709 }
710 else if (item.first == "five-axle-single-trailer-truck")
711 {
712 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FIVE_AXLE_SINGLE_TRAILER_TRUCK;
713 }
714 else if (item.first == "six-or-more-axle-single-trailer-truck")
715 {
716 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SIX_OR_MORE_AXLE_SINGLE_TRAILER_TRUCK;
717 }
718 else if (item.first == "five-or-fewer-axle-multi-trailer-truck")
719 {
720 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FIVE_OR_FEWER_AXLE_MULTI_TRAILER_TRUCK;
721 }
722 else if (item.first =="six-axle-multi-trailer-truck")
723 {
724 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SIX_AXLE_MULTI_TRAILER_TRUCK;
725 }
726 else if (item.first =="seven-or-more-axle-multi-trailer-truck")
727 {
728 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SEVEN_OR_MORE_AXLE_MULTI_TRAILER_TRUCK;
729 }
730 else if (item.first =="rail")
731 {
732 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::RAIL;
733 }
734 else if (item.first == "unclassified")
735 {
736 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::UNCLASSIFIED;
737 }
738 tcm_params.vclasses.push_back(vclass);
739 }
740 tcm_params.schedule = parse_schedule(tree);
741
742 std::string bool_str = tree.get_value<std::string>("regulatory");
743 if (bool_str == "false") tcm_params.regulatory = false;
744 else tcm_params.regulatory = true;
745
746 tcm_params.detail = parse_detail(tree);
747
748 return tcm_params;
749
750 }
751
752 j2735_v2x_msgs::msg::TrafficControlGeometry CarmaCloudClient::parse_geometry(boost::property_tree::ptree& tree)
753 {
754 j2735_v2x_msgs::msg::TrafficControlGeometry tcm_geometry;
755 tcm_geometry.proj = tree.get<std::string>("proj");
756 tcm_geometry.datum = tree.get<std::string>("datum");
757
758 tcm_geometry.reftime = tree.get<uint64_t>("reftime");
759
760 tcm_geometry.reflon = tree.get<int32_t>("reflon");
761 tcm_geometry.reflat = tree.get<int32_t>("reflat");
762 tcm_geometry.refelv = tree.get<int32_t>("refelv");
763 tcm_geometry.heading = tree.get<int16_t>("heading");
764
765 for (auto& item : tree.get_child("nodes"))
766 {
767 j2735_v2x_msgs::msg::PathNode pathnode;
768 for (auto& which : item.second)
769 {
770 if (which.first == "x")
771 {
772 std::string x_val = which.second.get_value<std::string>();
773 pathnode.x = std::stoll(x_val);
774 }
775
776 else if (which.first == "y")
777 {
778 std::string y_val = which.second.get_value<std::string>();
779 pathnode.y = std::stoll(y_val);
780 }
781 else if (which.first == "z")
782 {
783 pathnode.z_exists = true;
784 std::string z_val = which.second.get_value<std::string>();
785 pathnode.z = std::stoll(z_val);
786 }
787 else if (which.first == "width")
788 {
789 pathnode.width_exists = true;
790 std::string w_val = which.second.get_value<std::string>();
791 pathnode.width = std::stoll(w_val);
792
793 }
794
795 }
796 tcm_geometry.nodes.push_back(pathnode);
797 }
798
799 return tcm_geometry;
800
801 }
802
803 unsigned char CarmaCloudClient::parse_hex(char c)
804 {
805 if ('0' <= c && c <= '9') return c - '0';
806 if ('A' <= c && c <= 'F') return c - 'A' + 10;
807 if ('a' <= c && c <= 'f') return c - 'a' + 10;
808 std::abort();
809 }
810
811
812
813} // carma_cloud_client
814
815#include "rclcpp_components/register_node_macro.hpp"
816
817// Register the component with class_loader
818RCLCPP_COMPONENTS_REGISTER_NODE(carma_cloud_client::CarmaCloudClient)
TODO for USER: Add class description.
j2735_v2x_msgs::msg::TrafficControlGeometry parse_geometry(boost::property_tree::ptree &tree)
Parse xml geometry subtree of tcm msg.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
void tcr_callback(carma_v2x_msgs::msg::TrafficControlRequest::UniquePtr msg)
TCR subscription callback.
j2735_v2x_msgs::msg::TrafficControlParams parse_params(boost::property_tree::ptree &tree)
Parse xml params subtree of tcm msg.
j2735_v2x_msgs::msg::TrafficControlSchedule parse_schedule(boost::property_tree::ptree &tree)
Parse xml schedule subtree of tcm msg.
void CloudSendAsync(const std::string &local_msg, const std::string &local_url, const std::string &local_base, const std::string &local_method)
Send async http request to carma cloud.
carma_ros2_utils::PubPtr< j2735_v2x_msgs::msg::TrafficControlMessage > tcm_pub_
unsigned char parse_hex(char c)
Convert Hex char to unsigned char.
j2735_v2x_msgs::msg::TrafficControlMessage parseTCMXML(boost::property_tree::ptree &tree)
Parse xml package of tcm msg using boost property tree xml parser.
void TCMHandler(QHttpEngine::Socket *socket)
Handles the TCM received from CARMA Cloud.
void XMLconversion(char *xml_str, carma_v2x_msgs::msg::TrafficControlRequest request_msg)
Funtion to Convert the TCR into XML format.
int CloudSend(const std::string &local_msg, const std::string &local_url, const std::string &local_base, const std::string &local_method)
Send http request to carma cloud.
QByteArray UncompressBytes(const QByteArray compressedBytes) const
Uncompress bytes using zlib library.
CarmaCloudClient(const rclcpp::NodeOptions &)
Node constructor.
j2735_v2x_msgs::msg::TrafficControlDetail parse_detail(boost::property_tree::ptree &tree)
Parse xml detail subtree of tcm msg.
j2735_v2x_msgs::msg::TrafficControlPackage parse_package(boost::property_tree::ptree &tree)
Parse xml package subtree of tcm msg.
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::TrafficControlRequest > tcr_sub_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
callback for dynamic parameter updates
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
void convert(const carma_v2x_msgs::msg::PSM &in_msg, carma_perception_msgs::msg::ExternalObject &out_msg, const std::string &map_frame_id, double pred_period, double pred_step_size, const lanelet::projection::LocalFrameProjector &map_projector, const tf2::Quaternion &ned_in_map_rotation, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock)
Stuct containing the algorithm configuration values for carma_cloud_client.