22#include <rclcpp/rclcpp.hpp>
24#include <std_msgs/msg/string.hpp>
25#include <std_srvs/srv/empty.hpp>
28#include <j2735_convertor/control_request_convertor.hpp>
34#include <QCoreApplication>
35#include <QHostAddress>
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>
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>
53#include <v2xhubWebAPI/OAIApiRouter.h>
69 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::TrafficControlRequest>
tcr_sub_;
70 carma_ros2_utils::PubPtr<j2735_v2x_msgs::msg::TrafficControlMessage>
tcm_pub_;
88 rcl_interfaces::msg::SetParametersResult
96 void tcr_callback(carma_v2x_msgs::msg::TrafficControlRequest::UniquePtr msg);
103 void XMLconversion(
char* xml_str, carma_v2x_msgs::msg::TrafficControlRequest request_msg);
112 int CloudSend(
const std::string &local_msg,
const std::string& local_url,
const std::string& local_base,
const std::string& local_method);
121 void CloudSendAsync(
const std::string& local_msg,
const std::string& local_url,
const std::string& local_base,
const std::string& local_method);
139 j2735_v2x_msgs::msg::TrafficControlMessage
parseTCMXML(boost::property_tree::ptree& tree);
152 j2735_v2x_msgs::msg::TrafficControlPackage
parse_package(boost::property_tree::ptree& tree);
159 j2735_v2x_msgs::msg::TrafficControlParams
parse_params(boost::property_tree::ptree& tree);
166 j2735_v2x_msgs::msg::TrafficControlGeometry
parse_geometry(boost::property_tree::ptree& tree);
173 j2735_v2x_msgs::msg::TrafficControlSchedule
parse_schedule(boost::property_tree::ptree& tree);
180 j2735_v2x_msgs::msg::TrafficControlDetail
parse_detail(boost::property_tree::ptree& tree);
193 carma_ros2_utils::CallbackReturn
handle_on_configure(
const rclcpp_lifecycle::State &prev_state);
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
Stuct containing the algorithm configuration values for carma_cloud_client.