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.
carma_cloud_client_node.hpp
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 */
16
17
18#pragma once
19
20#define CURL_STATICLIB
21
22#include <rclcpp/rclcpp.hpp>
23#include <functional>
24#include <std_msgs/msg/string.hpp>
25#include <std_srvs/srv/empty.hpp>
26#include <curl/curl.h>
27#include <curl/easy.h>
28#include <j2735_convertor/control_request_convertor.hpp>
29#include <stdio.h>
30#include <cstdio>
31#include <iostream>
32#include <zlib.h>
33
34#include <QCoreApplication>
35#include <QHostAddress>
36#include <QVariantMap>
37
38#include <qhttpengine/handler.h>
39#include <qhttpengine/localauthmiddleware.h>
40#include <qhttpengine/qobjecthandler.h>
41#include <qhttpengine/server.h>
42#include <qhttpengine/socket.h>
43
44#include <carma_ros2_utils/carma_lifecycle_node.hpp>
46#include <j2735_v2x_msgs/msg/traffic_control_request.hpp>
47#include <carma_v2x_msgs/msg/traffic_control_request.hpp>
48#include <j2735_v2x_msgs/msg/traffic_control_message.hpp>
49#include <boost/property_tree/ptree.hpp>
50#include <boost/property_tree/xml_parser.hpp>
51#include <boost/foreach.hpp>
52
53#include <v2xhubWebAPI/OAIApiRouter.h>
54
55// using namespace OpenAPI;
56
57namespace carma_cloud_client
58{
59
64 class CarmaCloudClient : public carma_ros2_utils::CarmaLifecycleNode
65 {
66
67 private:
68 // TCR Subscriber
69 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::TrafficControlRequest> tcr_sub_;
70 carma_ros2_utils::PubPtr<j2735_v2x_msgs::msg::TrafficControlMessage> tcm_pub_;
71
72 // Node configuration
74
75 const char *CONTENT_ENCODING_KEY = "Content-Encoding";
76 const char *CONTENT_ENCODING_VALUE = "gzip";
77
78 public:
82 explicit CarmaCloudClient(const rclcpp::NodeOptions &);
83
88 rcl_interfaces::msg::SetParametersResult
89 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
90
91
96 void tcr_callback(carma_v2x_msgs::msg::TrafficControlRequest::UniquePtr msg);
97
103 void XMLconversion(char* xml_str, carma_v2x_msgs::msg::TrafficControlRequest request_msg);
104
112 int CloudSend(const std::string &local_msg, const std::string& local_url, const std::string& local_base, const std::string& local_method);
113
121 void CloudSendAsync(const std::string& local_msg,const std::string& local_url, const std::string& local_base, const std::string& local_method);
122
127 void TCMHandler(QHttpEngine::Socket *socket);
128
132 int StartWebService();
133
139 j2735_v2x_msgs::msg::TrafficControlMessage parseTCMXML(boost::property_tree::ptree& tree);
140
145 unsigned char parse_hex(char c);
146
152 j2735_v2x_msgs::msg::TrafficControlPackage parse_package(boost::property_tree::ptree& tree);
153
159 j2735_v2x_msgs::msg::TrafficControlParams parse_params(boost::property_tree::ptree& tree);
160
166 j2735_v2x_msgs::msg::TrafficControlGeometry parse_geometry(boost::property_tree::ptree& tree);
167
173 j2735_v2x_msgs::msg::TrafficControlSchedule parse_schedule(boost::property_tree::ptree& tree);
174
180 j2735_v2x_msgs::msg::TrafficControlDetail parse_detail(boost::property_tree::ptree& tree);
181
187 QByteArray UncompressBytes(const QByteArray compressedBytes) const;
188
189
191 // Overrides
193 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state);
194
195 };
196
197} // carma_cloud_client
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
Stuct containing the algorithm configuration values for carma_cloud_client.