20 namespace std_ph = std::placeholders;
23 : carma_ros2_utils::CarmaLifecycleNode(options)
44 auto error = update_params<std::string>({{
"url",
config_.
url},
51 rcl_interfaces::msg::SetParametersResult result;
53 result.successful = !error;
60 RCLCPP_DEBUG_STREAM(this->get_logger(),
"CarmaCloudClient trying to configure");
64 get_parameter<std::string>(
"url",
config_.
url);
77 tcr_sub_ = create_subscription<carma_v2x_msgs::msg::TrafficControlRequest>(
"outgoing_geofence_request", 10,
79 tcm_pub_ = create_publisher<j2735_v2x_msgs::msg::TrafficControlMessage>(
"incoming_j2735_geofence_control", 1);
83 return CallbackReturn::SUCCESS;
88 carma_v2x_msgs::msg::TrafficControlRequest request_msg(*msg.get());
96 RCLCPP_DEBUG_STREAM( get_logger(),
"tcr_sub_ callback called ");
101 j2735_v2x_msgs::msg::TrafficControlRequest j2735_tcr;
105 RCLCPP_DEBUG_STREAM( get_logger(),
"converted: ");
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++)
111 sprintf(reqid+(
i*hexlen),
"%.2X", j2735_tcr.tcr_v01.reqid.id[
i]);
114 RCLCPP_DEBUG_STREAM( get_logger(),
"reqid: " << reqid);
116 long int reqseq = j2735_tcr.tcr_v01.reqseq;
117 RCLCPP_DEBUG_STREAM( get_logger(),
"reqseq: " << reqseq);
119 long int scale = j2735_tcr.tcr_v01.scale;
120 RCLCPP_DEBUG_STREAM( get_logger(),
"scale: " << scale);
122 int totBounds = j2735_tcr.tcr_v01.bounds.size();
124 char bounds_str[5000];
125 strcpy(bounds_str,
"");
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;
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;
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);
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);
157 RCLCPP_DEBUG_STREAM( get_logger(),
"xml_str: " << xml_str);
161 int CarmaCloudClient::CloudSend(
const std::string &local_msg,
const std::string& local_url,
const std::string& local_base,
const std::string& local_method)
165 std::string urlfull = local_url +
config_.
port + local_base;
166 RCLCPP_DEBUG_STREAM( get_logger(),
"full url: " << urlfull);
167 req = curl_easy_init();
169 curl_easy_setopt(req, CURLOPT_URL, urlfull.c_str());
171 if(strcmp(local_method.c_str(),
"POST")==0)
173 curl_easy_setopt(req, CURLOPT_POSTFIELDS, local_msg.c_str());
174 curl_easy_setopt(req, CURLOPT_TIMEOUT_MS, 1000L);
175 res = curl_easy_perform(req);
178 RCLCPP_ERROR_STREAM( get_logger(),
"curl send failed: " << curl_easy_strerror(res));
182 curl_easy_cleanup(req);
190 std::thread t([
this, &local_msg, &local_url, &local_base, &local_method](){
191 CloudSend(local_msg, local_url, local_base, local_method);
199 strm.zalloc =
nullptr;
200 strm.zfree =
nullptr;
201 strm.opaque =
nullptr;
202 strm.avail_in = compressedBytes.size();
203 strm.next_in = (Byte *)compressedBytes.data();
205 auto err = inflateInit2(&strm, MAX_WBITS + 16);
208 const int BUFFER_SIZE = 4092;
215 char buffer[BUFFER_SIZE] = {0};
216 strm.avail_out = BUFFER_SIZE;
217 strm.next_out = (Byte *)buffer;
219 isDone = inflate(&strm, Z_FINISH);
220 outBuf.append(buffer);
221 }
while (Z_STREAM_END != isDone);
225 RCLCPP_DEBUG_STREAM( get_logger(),
"Error initalize stream. Err code = " << err);
235 while(socket->bytesAvailable()>0)
237 auto readBytes = socket->readAll();
245 st.append(readBytes);
249 QByteArray array = st.toLocal8Bit();
251 char* _cloudUpdate = array.data();
254 std::string tcm_string = _cloudUpdate;
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)
260 RCLCPP_DEBUG_STREAM( get_logger(),
"Received TCM length is zero, and skipped.");
264 boost::property_tree::ptree list_tree;
265 std :: stringstream ss;
267 read_xml(ss, list_tree);
270 auto child_tcm_list = list_tree.get_child_optional(
"TrafficControlMessageList");
274 auto child_tree = list_tree.get_child(
"TrafficControlMessage");
275 j2735_v2x_msgs::msg::TrafficControlMessage parsed_tcm =
parseTCMXML(child_tree);
280 auto tcm_list = child_tcm_list.get();
282 BOOST_FOREACH(
auto &node, list_tree.get_child(
"TrafficControlMessageList"))
284 j2735_v2x_msgs::msg::TrafficControlMessage parsed_tcm =
parseTCMXML(node.second);
295 j2735_v2x_msgs::msg::TrafficControlMessage tcm;
297 auto child_tcmv01 =
tree.get_child_optional(
"tcmV01");
300 tcm.choice = j2735_v2x_msgs::msg::TrafficControlMessage::RESERVED;
303 else tcm.choice = j2735_v2x_msgs::msg::TrafficControlMessage::TCMV01;
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)
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");
316 std::string id_string =
tree.get<std::string>(
"tcmV01.id");
317 for (std::size_t
i = 0;
i != id_string.size() / 2; ++
i)
322 tcm.tcm_v01.updated =
tree.get<uint64_t>(
"tcmV01.updated");
324 auto tree_package =
tree.get_child_optional(
"tcmV01.package");
327 tcm.tcm_v01.package_exists =
false;
331 tcm.tcm_v01.package_exists =
true;
335 auto tree_params =
tree.get_child_optional(
"tcmV01.params");
338 tcm.tcm_v01.params_exists =
false;
342 tcm.tcm_v01.params_exists =
true;
346 auto tree_geometry =
tree.get_child_optional(
"tcmV01.geometry");
349 tcm.tcm_v01.geometry_exists =
false;
353 tcm.tcm_v01.geometry_exists =
true;
365 char *placeholderX[1]={0};
367 QCoreApplication a(placeholderC,placeholderX);
369 QHostAddress address = QHostAddress(QString::fromStdString (
config_.
webip));
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();
377 QObject::connect(handler.data(), &OpenAPI::OAIApiRequestHandler::requestReceived, [&](QHttpEngine::Socket *socket) {
381 QObject::connect(handler.data(), &OpenAPI::OAIApiRequestHandler::requestReceived, [&](QHttpEngine::Socket *socket) {
382 router->processRequest(socket);
384 QHttpEngine::Server server(handler.data());
386 if (!server.listen(address, port)) {
387 qCritical(
"Unable to listen on the specified port.");
391 RCLCPP_DEBUG_STREAM(this->get_logger(),
"CarmaCloudClient :: Started web service");
398 j2735_v2x_msgs::msg::TrafficControlPackage tcm_pkg;
400 auto tree_label =
tree.get_child_optional(
"label");
403 tcm_pkg.label_exists =
false;
407 tcm_pkg.label_exists =
true;
408 tcm_pkg.label =
tree.get<std::string>(
"label");
411 std::string tcids_string =
tree.get<std::string>(
"tcids");
419 j2735_v2x_msgs::msg::TrafficControlSchedule tcm_schedule;
420 tcm_schedule.start =
tree.get<uint64_t>(
"schedule.start");
422 auto child_end =
tree.get_child_optional(
"schedule.end");
425 tcm_schedule.end_exists =
false;
429 tcm_schedule.end_exists =
true;
430 tcm_schedule.end =
tree.get<uint64_t>(
"schedule.end");
433 auto child_dow =
tree.get_child_optional(
"schedule.dow");
436 tcm_schedule.dow_exists =
false;
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++)
444 tcm_schedule.dow.dow[
i] = dow_string[
i] -
'0';
447 auto child_between =
tree.get_child_optional(
"schedule.between");
450 tcm_schedule.between_exists =
false;
454 tcm_schedule.between_exists =
true;
455 auto child_tree = child_between.get();
457 for (
auto& item :
tree.get_child(
"schedule.between"))
459 j2735_v2x_msgs::msg::DailySchedule daily;
460 for (
auto& which : item.second)
462 if (which.first ==
"begin")
464 daily.begin = which.second.get_value<uint16_t>();
466 else if (which.first ==
"duration")
468 daily.duration = which.second.get_value<uint16_t>();
471 tcm_schedule.between.push_back(daily);
474 auto child_repeat =
tree.get_child_optional(
"schedule.repeat");
478 tcm_schedule.repeat_exists =
false;
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");
493 j2735_v2x_msgs::msg::TrafficControlDetail tcm_detail;
495 auto detail_tree =
tree.get_child(
"detail");
498 auto closed_tree = detail_tree.get_child_optional(
"closed" );
501 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::CLOSED_CHOICE;
503 auto open = closed_tree.get().get_child_optional(
"open");
506 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPEN;
509 auto notopen = closed_tree.get().get_child_optional(
"notopen");
512 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::CLOSED;
515 auto taperleft = closed_tree.get().get_child_optional(
"taperleft");
518 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::TAPERLEFT;
521 auto taperright = closed_tree.get().get_child_optional(
"taperright");
524 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::TAPERRIGHT;
527 auto openleft = closed_tree.get().get_child_optional(
"openleft");
530 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPENLEFT;
533 auto openright = closed_tree.get().get_child_optional(
"openright");
536 tcm_detail.closed = j2735_v2x_msgs::msg::TrafficControlDetail::OPENRIGHT;
541 auto child_dir= detail_tree.get_child_optional(
"direction" );
544 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::DIRECTION_CHOICE;
546 auto direction = child_dir.get().get_child_optional(
"reverse");
549 tcm_detail.direction = j2735_v2x_msgs::msg::TrafficControlDetail::REVERSE;
551 else tcm_detail.direction = j2735_v2x_msgs::msg::TrafficControlDetail::FORWARD;
555 auto child_chains = detail_tree.get_child_optional(
"chains" );
558 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::CHAINS_CHOICE;
559 auto no = child_chains.get().get_child_optional(
"no");
562 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::NO;
564 auto permitted = child_chains.get().get_child_optional(
"permitted");
567 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::PERMITTED;
569 auto required = child_chains.get().get_child_optional(
"required");
572 tcm_detail.chains = j2735_v2x_msgs::msg::TrafficControlDetail::REQUIRED;
576 auto child_mins =
tree.get_child_optional(
"detail.minspeed" );
579 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINSPEED_CHOICE;
580 tcm_detail.minspeed =
tree.get<
float>(
"detail.minspeed");
583 auto child_maxs =
tree.get_child_optional(
"detail.maxspeed");
586 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXSPEED_CHOICE;
587 tcm_detail.maxspeed =
tree.get<uint16_t>(
"detail.maxspeed");
590 auto child_minhdwy =
tree.get_child_optional(
"detail.minhdwy");
593 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINHDWY_CHOICE;
594 tcm_detail.minhdwy =
tree.get<uint16_t>(
"detail.minhdwy");
597 auto child_maxvehmass =
tree.get_child_optional(
"detail.maxvehmass");
598 if( child_maxvehmass )
600 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHMASS_CHOICE;
601 tcm_detail.maxvehmass =
tree.get<uint16_t>(
"detail.maxvehmass");
604 auto child_maxvehheight =
tree.get_child_optional(
"detail.maxvehheight");
605 if( child_maxvehheight )
607 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHHEIGHT_CHOICE;
608 tcm_detail.maxvehheight =
tree.get<uint8_t>(
"detail.maxvehheight");
611 auto child_maxvehwidth =
tree.get_child_optional(
"detail.maxvehwidth");
612 if( child_maxvehwidth )
614 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHWIDTH_CHOICE;
615 tcm_detail.maxvehwidth =
tree.get<uint8_t>(
"detail.maxvehwidth");
618 auto child_maxvehlength =
tree.get_child_optional(
"detail.maxvehlength");
619 if( child_maxvehlength )
621 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHLENGTH_CHOICE;
622 tcm_detail.maxvehlength =
tree.get<uint16_t>(
"detail.maxvehlength");
625 auto child_maxvehaxles =
tree.get_child_optional(
"detail.maxvehaxles");
626 if( child_maxvehaxles)
628 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXVEHAXLES_CHOICE;
629 tcm_detail.maxvehaxles =
tree.get<uint8_t>(
"detail.maxvehaxles");
632 auto child_minvehocc =
tree.get_child_optional(
"detail.minvehocc");
635 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINVEHOCC_CHOICE;
636 tcm_detail.minvehocc =
tree.get<uint8_t>(
"detail.minvehocc");
639 auto child_maxplatoonsize =
tree.get_child_optional(
"detail.maxplatoonsize");
640 if( child_maxplatoonsize)
642 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MAXPLATOONSIZE_CHOICE;
643 tcm_detail.maxplatoonsize =
tree.get<uint8_t>(
"detail.maxplatoonsize");
646 auto child_minplatoonhdwy =
tree.get_child_optional(
"detail.minplatoonhdwy");
647 if( child_minplatoonhdwy)
649 tcm_detail.choice = j2735_v2x_msgs::msg::TrafficControlDetail::MINPLATOONHDWY_CHOICE;
650 tcm_detail.minplatoonhdwy =
tree.get<uint16_t>(
"detail.minplatoonhdwy");
658 j2735_v2x_msgs::msg::TrafficControlParams tcm_params;
659 for (
auto& item :
tree.get_child(
"vclasses"))
661 j2735_v2x_msgs::msg::TrafficControlVehClass vclass;
662 if (item.first ==
"any")
664 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::ANY;
666 else if (item.first ==
"pedestrian")
668 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::PEDESTRIAN;
670 else if (item.first ==
"bicycle")
672 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::BICYCLE;
674 else if (
tree.count(
"micromobile") != 0)
676 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::MICROMOBILE;
678 else if (item.first ==
"motorcycle")
680 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::MOTORCYCLE;
682 else if (item.first ==
"passenger-car")
684 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::PASSENGER_CAR;
686 else if (item.first ==
"light-truck-van")
688 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::LIGHT_TRUCK_VAN;
690 else if (item.first ==
"bus")
692 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::BUS;
694 else if (item.first ==
"two-axle-six-tire-single-unit-truck")
696 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::TWO_AXLE_SIX_TIRE_SINGLE_UNIT_TRUCK;
698 else if (item.first ==
"three-axle-single-unit-truck")
700 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::THREE_AXLE_SINGLE_UNIT_TRUCK;
702 else if (item.first ==
"four-or-more-axle-single-unit-truck")
704 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FOUR_OR_MORE_AXLE_SINGLE_UNIT_TRUCK;
706 else if (item.first ==
"four-or-fewer-axle-single-trailer-truck")
708 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FOUR_OR_FEWER_AXLE_SINGLE_TRAILER_TRUCK;
710 else if (item.first ==
"five-axle-single-trailer-truck")
712 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FIVE_AXLE_SINGLE_TRAILER_TRUCK;
714 else if (item.first ==
"six-or-more-axle-single-trailer-truck")
716 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SIX_OR_MORE_AXLE_SINGLE_TRAILER_TRUCK;
718 else if (item.first ==
"five-or-fewer-axle-multi-trailer-truck")
720 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::FIVE_OR_FEWER_AXLE_MULTI_TRAILER_TRUCK;
722 else if (item.first ==
"six-axle-multi-trailer-truck")
724 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SIX_AXLE_MULTI_TRAILER_TRUCK;
726 else if (item.first ==
"seven-or-more-axle-multi-trailer-truck")
728 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::SEVEN_OR_MORE_AXLE_MULTI_TRAILER_TRUCK;
730 else if (item.first ==
"rail")
732 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::RAIL;
734 else if (item.first ==
"unclassified")
736 vclass.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::UNCLASSIFIED;
738 tcm_params.vclasses.push_back(vclass);
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;
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");
758 tcm_geometry.reftime =
tree.get<uint64_t>(
"reftime");
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");
765 for (
auto& item :
tree.get_child(
"nodes"))
767 j2735_v2x_msgs::msg::PathNode pathnode;
768 for (
auto& which : item.second)
770 if (which.first ==
"x")
772 std::string x_val = which.second.get_value<std::string>();
773 pathnode.x = std::stoll(x_val);
776 else if (which.first ==
"y")
778 std::string y_val = which.second.get_value<std::string>();
779 pathnode.y = std::stoll(y_val);
781 else if (which.first ==
"z")
783 pathnode.z_exists =
true;
784 std::string z_val = which.second.get_value<std::string>();
785 pathnode.z = std::stoll(z_val);
787 else if (which.first ==
"width")
789 pathnode.width_exists =
true;
790 std::string w_val = which.second.get_value<std::string>();
791 pathnode.width = std::stoll(w_val);
796 tcm_geometry.nodes.push_back(pathnode);
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;
815#include "rclcpp_components/register_node_macro.hpp"
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)
const char * CONTENT_ENCODING_KEY
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.
const char * CONTENT_ENCODING_VALUE
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_
int StartWebService()
Starts web service.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
callback for dynamic parameter updates
auto to_string(const UtmZone &zone) -> std::string
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.