From ad167f2978326edc4b4b62b0d0bfe9c51e3ecc20 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 01:38:48 +0900 Subject: [PATCH 01/75] WIP: add likelihood filed based car tracker --- .../detection_by_tracker/CMakeLists.txt | 1 + .../likelihood_field_tracker.hpp | 231 ++++++ .../src/likelihood_field_tracker.cpp | 769 ++++++++++++++++++ 3 files changed, 1001 insertions(+) create mode 100644 perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp create mode 100644 perception/detection_by_tracker/src/likelihood_field_tracker.cpp diff --git a/perception/detection_by_tracker/CMakeLists.txt b/perception/detection_by_tracker/CMakeLists.txt index 236268438f852..034f83a852e88 100644 --- a/perception/detection_by_tracker/CMakeLists.txt +++ b/perception/detection_by_tracker/CMakeLists.txt @@ -27,6 +27,7 @@ include_directories( # Generate exe file set(DETECTION_BY_TRACKER_SRC src/detection_by_tracker_core.cpp + src/likelihood_field_tracker.cpp ) ament_auto_add_library(detection_by_tracker_node SHARED diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp new file mode 100644 index 0000000000000..d226fa3ee0209 --- /dev/null +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -0,0 +1,231 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DETECTION_BY_TRACKER__LIKELIHOOD_FIELD_TRACKER_CORE_HPP_ +#define DETECTION_BY_TRACKER__LIKELIHOOD_FIELD_TRACKER_CORE_HPP_ + +#include "detection_by_tracker/debugger.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + + +#include +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +//using autoware::common::types::float64_t; // convert double to float64_t later + + +/** + * @brief rectangle zone calc function + * + */ +class RectangleZone +{ +private: + double xmin_, xmax_, ymin_, ymax_; + +public: + RectangleZone();/// default constructor + RectangleZone(const double xmin, const double xmax, const double ymin, const double ymax); + void setZone(const double xmin, const double xmax, const double ymin, const double ymax); + bool contains(const Eigen::Vector2d point); /// if input coordinates is inside the rectangle zone, geometry_msgs::msg::Point +}; + +/** + * @brief Express Car Likelihood Field used in coarse fitting + * + * @details likelihood is calc as following equations: + * exp(-c/2/sigma/sigma) + * ,while c is cost parameter and sigma is measurement noise covariance + */ +class CoarseCarLikelihoodField +{ + private: + double measurement_covariance_ = 0.1; + /// cost value of {contour, outside} + std::vector costs_ = {0.01, 0.1}; + std::array contour_zones_; + const std::vector> indexes_ = {{0,1},{1,2},{2,3},{3,0}}; + + + public: + explicit CoarseCarLikelihoodField(const double width, const double length, + const double outside_margin, const double inside_margin); + void setContourZones(const double width, const double length, const double outside_margin, const double inside_margin); + void setMeasurementCovariance(const double cov); + void setCostParameters(const std::vector & costs); + double calcLikelihoods(std::vector localized_measurements, std::uint8_t index_num); +}; + + +/** + * @brief Express Car Likelihood Field used in fine fitting + * + */ +class FineCarLikelihoodField +{ + private: + /// cost value represent {penalty, contour, inside, outside} + std::vector costs_ = {0.1, 0.01, 0.03, 0.06}; + double measurement_covariance_ = 0.1; + RectangleZone car_contour_; /// Rectangle Area + std::array penalty_zones_; + std::array contour_zones_; + const std::vector> indexes_ = {{0,1},{1,2},{2,3},{3,0}}; + + public: + explicit FineCarLikelihoodField(const double width, const double length, + const double outside_margin, const double inside_margin); + void setContourZones(const double width, const double length, const double outside_margin, const double inside_margin); + void setPenaltyZones(const double width, const double length, const double outside_margin, const double inside_margin); + void setMeasurementCovariance(const double cov); + void setCostParameters(const std::vector & costs); + double calcLikelihoods(std::vector localized_measurements, std::uint8_t index_num); +}; + + +/** + * @brief Manage Each Vehicle Particle + * + */ +class VehicleParticle +{ +private: + double inside_margin_ = 0.25; + double outside_margin_ = 1.0; + double measurement_noise_ = 0.1; + std::unique_ptr fine_likelihood_; // maybe it's ok to use std::optional instead + std::unique_ptr coarse_likelihood_; + std::array corner_points_; + + + +public: + Eigen::Vector2d center_; + double orientation_; + explicit VehicleParticle(const Eigen::Vector2d center, const double width, const double length, const double orientation); + void setCornerPoints(const Eigen::Vector2d center, const double width, const double length, const double orientation); + std::uint8_t getNearestCornerIndex(const Eigen::Vector2d & origin = Eigen::Vector2d(0.0,0.0)); /// ego origin is set 0,0 by default + std::vector toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation); + double calcCoarseLikelihood(const std::vector & measurements); + double calcFineLikelihood(const std::vector & measurements); +}; + + +class SingleLFTracker +{ + private: + std::vector vehicle_particle_; + std::uint32_t particle_num_; + Eigen::Vector2d position_; + double orientation_; + double width_; + double length_; + Eigen::Matrix3d covariance_; + + public: + SingleLFTracker(const autoware_auto_perception_msgs::msg::TrackedObject & object); + void createVehiclePositionParticle(const std::uint32_t particle_num); + void createVehicleShapeParticle(); + void estimateState(const std::vector & scan); +}; + + + +// class TrackerHandler +// { +// private: +// std::deque objects_buffer_; + +// public: +// TrackerHandler() = default; +// void onTrackedObjects( +// const autoware_auto_perception_msgs::msg::TrackedObjects::ConstSharedPtr input_objects_msg); +// bool estimateTrackedObjects( +// const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObjects & output); +// }; + +// class LikelihoodFieldTracker : public rclcpp::Node +// { +// public: +// explicit LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options); + +// private: +// rclcpp::Publisher::SharedPtr objects_pub_; +// rclcpp::Subscription::SharedPtr trackers_sub_; +// rclcpp::Subscription::SharedPtr +// initial_objects_sub_; + +// tf2_ros::Buffer tf_buffer_; +// tf2_ros::TransformListener tf_listener_; + +// TrackerHandler tracker_handler_; +// std::shared_ptr shape_estimator_; +// std::shared_ptr cluster_; +// std::shared_ptr debugger_; + +// bool ignore_unknown_tracker_; + +// void onObjects( +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg); + +// void divideUnderSegmentedObjects( +// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, +// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, +// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); + +// float optimizeUnderSegmentedObject( +// const autoware_auto_perception_msgs::msg::DetectedObject & target_object, +// const sensor_msgs::msg::PointCloud2 & under_segmented_cluster, +// tier4_perception_msgs::msg::DetectedObjectWithFeature & output); + +// void mergeOverSegmentedObjects( +// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, +// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, +// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); +// }; + +#endif // DETECTION_BY_TRACKER__LIKELIHOOD_FIELD_TRACKER_CORE_HPP_ diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp new file mode 100644 index 0000000000000..0db667a483166 --- /dev/null +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -0,0 +1,769 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "detection_by_tracker/likelihood_field_tracker.hpp" +#include "detection_by_tracker/detection_by_tracker_core.hpp" + +#include "perception_utils/perception_utils.hpp" + +#include +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; +static std::random_device seed_gen; + +namespace +{ + +// void setClusterInObjectWithFeature( +// const std_msgs::msg::Header & header, const pcl::PointCloud & cluster, +// tier4_perception_msgs::msg::DetectedObjectWithFeature & feature_object) +// { +// sensor_msgs::msg::PointCloud2 ros_pointcloud; +// pcl::toROSMsg(cluster, ros_pointcloud); +// ros_pointcloud.header = header; +// feature_object.feature.cluster = ros_pointcloud; +// } +// autoware_auto_perception_msgs::msg::Shape extendShape( +// const autoware_auto_perception_msgs::msg::Shape & shape, const float scale) +// { +// autoware_auto_perception_msgs::msg::Shape output = shape; +// output.dimensions.x *= scale; +// output.dimensions.y *= scale; +// output.dimensions.z *= scale; +// for (auto & point : output.footprint.points) { +// point.x *= scale; +// point.y *= scale; +// point.z *= scale; +// } +// return output; +// } + +// boost::optional getReferenceYawInfo(const uint8_t label, const float yaw) +// { +// const bool is_vehicle = +// Label::CAR == label || Label::TRUCK == label || Label::BUS == label || Label::TRAILER == label; +// if (is_vehicle) { +// return ReferenceYawInfo{yaw, tier4_autoware_utils::deg2rad(30)}; +// } else { +// return boost::none; +// } +// } + + +Eigen::Matrix3d extractXYYawCovariance(const std::array covariance) +{ + Eigen::Matrix3d cov(3,3); + cov(0,0) = covariance[0]; cov(0,1) = covariance[1]; cov(0,2) = covariance[5]; + cov(1,0) = covariance[6]; cov(1,1) = covariance[7]; cov(1,2) = covariance[11]; + cov(2,0) = covariance[30]; cov(2,1) = covariance[31]; cov(2,2) = covariance[35]; + return cov; +} + +/// sum of cost to calc likelihood +double sumOfCostToLikelihood(double cost_sum, double sigma) +{ + return std::exp(-cost_sum/2.0/sigma/sigma); +} + +} // namespace + + +RectangleZone::RectangleZone() +{ + xmin_ = -1; xmax_ = 1; + ymin_ = -1; ymax_ = 1; +} + +RectangleZone::RectangleZone(const double xmin, const double xmax, const double ymin, const double ymax) +{ + xmin_ = xmin; xmax_ = xmax; + ymin_ = ymin; ymax_ = ymax; +} + +void RectangleZone::setZone(const double xmin, const double xmax, const double ymin, const double ymax) +{ + xmin_ = xmin; xmax_ = xmax; + ymin_ = ymin; ymax_ = ymax; +} + +bool RectangleZone::contains(const Eigen::Vector2d p) +{ + if(p.x() >= xmin_ && p.x() <= xmax_ && p.y() >= ymin_ && p.y() <= ymax_){ + return true; + }else{ + return false; + } +} + + +CoarseCarLikelihoodField::CoarseCarLikelihoodField( + const double width, const double length, const double outside_margin, const double inside_margin) +{ + setContourZones(width, length, outside_margin, inside_margin); +} + +void CoarseCarLikelihoodField::setContourZones(const double width, const double length, const double outside_margin, const double inside_margin) +{ + auto W2 = width/2.0; auto L2 = length/2.0; + contour_zones_[0].setZone(-L2-outside_margin, L2+outside_margin, -W2-outside_margin, -W2 + inside_margin); + contour_zones_[1].setZone(-L2-outside_margin, -L2+inside_margin, -W2-outside_margin, W2 + outside_margin); + contour_zones_[2].setZone(-L2-outside_margin, L2+outside_margin, W2-inside_margin, W2 + outside_margin); + contour_zones_[3].setZone(L2-inside_margin, L2+outside_margin, -W2-outside_margin, W2 + outside_margin); +} + +void CoarseCarLikelihoodField::setMeasurementCovariance(const double cov) +{ + measurement_covariance_ = cov; +} + +void CoarseCarLikelihoodField::setCostParameters(const std::vector & costs) +{ + costs_ = costs; // {inside, outside} +} + +/// calc likelihood of localized measurements +double CoarseCarLikelihoodField::calcLikelihoods(const std::vector localized_measurements,std::uint8_t index_num) +{ + double cost_sum = 0; + // for each 2d measurements + for(std::size_t i = 0; i < localized_measurements.size(); ++i) { + auto part = indexes_[index_num]; // Zone indexes + if(contour_zones_[part[0]].contains(localized_measurements[i]) || contour_zones_[part[1]].contains(localized_measurements[i])){ + // inside contour zones + cost_sum += costs_[0]; + }else{ + // outside contour zones + cost_sum += costs_[1]; + } + } + + double likelihood = sumOfCostToLikelihood(cost_sum, measurement_covariance_); + return likelihood; +} + + + + +FineCarLikelihoodField::FineCarLikelihoodField( + const double width, const double length, const double outside_margin, const double inside_margin) +{ + // set likelihood field zones + setContourZones(width, length, outside_margin, inside_margin); + setPenaltyZones(width, length, outside_margin, inside_margin); + car_contour_.setZone(-length/2.0, length/2.0, width/2.0, width/2.0); +} + + + +void FineCarLikelihoodField::setContourZones(const double width, const double length, const double outside_margin, const double inside_margin) +{ + auto W2 = width/2.0; auto L2 = length/2.0; + contour_zones_[0].setZone(-L2, L2, -W2, -W2+inside_margin); + contour_zones_[1].setZone(-L2, -L2+inside_margin, -W2, W2); + contour_zones_[2].setZone(-L2, L2, W2-inside_margin, W2); + contour_zones_[3].setZone(L2-inside_margin, L2, -W2, W2); + (void)outside_margin; // currently unused +} + +void FineCarLikelihoodField::setPenaltyZones(const double width, const double length, const double outside_margin, const double inside_margin) +{ + auto W2 = width/2.0; auto L2 = length/2.0; + penalty_zones_[0].setZone(-L2-outside_margin, L2+outside_margin, -W2-outside_margin, -W2); + penalty_zones_[1].setZone(-L2-outside_margin, -L2, -W2-outside_margin, W2+outside_margin); + penalty_zones_[2].setZone(-L2-outside_margin, L2+outside_margin, W2, W2+outside_margin); + penalty_zones_[3].setZone(L2, L2+outside_margin, -W2-outside_margin, W2+outside_margin); + (void)inside_margin; // currently unused +} + +void FineCarLikelihoodField::setMeasurementCovariance(const double cov) +{ + measurement_covariance_ = cov; +} + +void FineCarLikelihoodField::setCostParameters(const std::vector & costs) +{ + costs_ = costs; // {penalty, contour, inside, outside} +} + +/// calc likelihood of localized measurements +double FineCarLikelihoodField::calcLikelihoods(const std::vector localized_measurements,std::uint8_t index_num) +{ + double cost_sum = 0; + // for each 2d measurements + for(std::size_t i = 0; i < localized_measurements.size(); ++i) { + auto part = indexes_[index_num]; // Zone indexes + + if(penalty_zones_[part[0]].contains(localized_measurements[i]) || penalty_zones_[part[1]].contains(localized_measurements[i])){ + // inside penalty zones + cost_sum += costs_[0]; + }else if(contour_zones_[part[0]].contains(localized_measurements[i]) || contour_zones_[part[1]].contains(localized_measurements[i])){ + // inside contour zones + cost_sum += costs_[1]; + }else if(car_contour_.contains(localized_measurements[i])){ + // inside car + cost_sum += costs_[2]; + }else{ + // outside the car + cost_sum += costs_[3]; + } + } + + double likelihood = sumOfCostToLikelihood(cost_sum, measurement_covariance_); + return likelihood; +} + + +VehicleParticle::VehicleParticle(const Eigen::Vector2d center, const double width, const double length, const double orientation) +{ + // init likelihood + fine_likelihood_.reset(new FineCarLikelihoodField(width, length, outside_margin_, inside_margin_)); + coarse_likelihood_.reset(new CoarseCarLikelihoodField(width, length, outside_margin_, inside_margin_)); + // calc corner points + setCornerPoints(center, width, length, orientation); + // set geometry + center_ = center; + orientation_ = orientation; +} + +void VehicleParticle::setCornerPoints(const Eigen::Vector2d center, const double width, const double length, const double orientation) +{ + Eigen::Rotation2Dd rotate(orientation); /// rotation + auto R = rotate.toRotationMatrix(); /// Rotation matrix R^T + // corners in local coordinate + p0 = Eigen::Vector2d(length/2.0,-width/2.0); p1 = Eigen::Vector2d(-length/2.0,-width/2.0); + p2 = Eigen::Vector2d(-length/2.0,+width/2.0); p3 = Eigen::Vector2d(length/2.0,width/2.0); + // set corner points coordinates + corner_points_[0] = R*p0 + center; + corner_points_[1] = R*p1 + center; + corner_points_[2] = R*p2 + center; + corner_points_[3] = R*p3 + center; +} + +std::uint8_t VehicleParticle::getNearestCornerIndex(const Eigen::Vector2d & center) +{ + std::uint8_t closest_index = 0; + double max_dist = 100; // distance[m] + double buff = 0; + for(std::uint8_t i=0; i<4; i++){ + buff = (corner_points_[i] - center).norm(); + if(buff VehicleParticle::toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation) +{ + auto point_num = measurements.size(); + std::vector localized(point_num); + + Eigen::Rotation2Dd rotate(orientation); /// rotation + auto Rt = rotate.toRotationMatrix().transpose(); /// Rotation matrix R^T + + for(std::size_t i=0;i & measurements) +{ + auto corner_index = getNearestCornerIndex(); + auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); + auto likelihood = coarse_likelihood_->calcLikelihoods(local_measurements, corner_index); + return likelihood; +} + +/** + * @brief + * + * @param measurements : 2d measurement Points + * @return double likelihood + */ +double VehicleParticle::calcFineLikelihood(const std::vector & measurements) +{ + auto corner_index = getNearestCornerIndex(); + auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); + auto likelihood = fine_likelihood_->calcLikelihoods(local_measurements, corner_index); + return likelihood; + +} + + +SingleLFTracker::SingleLFTracker(const autoware_auto_perception_msgs::msg::TrackedObject & object) +{ + // set private variable + position_ = Eigen::Vector2d(object.kinematics.pose_with_covariance.pose.position.x, object.kinematics.pose_with_covariance.pose.position.y); + orientation_ = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + length_ = object.shape.dimensions.x; + width_ = object.shape.dimensions.y; + covariance_ = extractXYYawCovariance(object.kinematics.pose_with_covariance.covariance); +} + + +void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle_num) +{ + // Strictly, we should use multivariate normal distribution + // Relaxed Results + std::default_random_engine engine(seed_gen()); + std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance_(0, 0))); + std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance_(1, 1))); + std::normal_distribution<> yaw_distribution(0.0, std::sqrt(covariance_(2, 2))); + + // generate random vehicle particles + for(std::uint32_t i =0; i calcMeanAndCovFromParticles(std::vector & likelihoods, std::vector vectors) +{ + + auto loop = likelihoods.size(); + Eigen::Vector3d mean; + Eigen::Matrix3d cov; + double w2 = 0; + + for(std::size_t i; i < loop; i++){ + mean += vectors[i] * likelihoods[i]; + w2 += likelihoods[i]*likelihoods[i]; + } + + for(std::size_t i; i < loop; i++){ + cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i]/(1-w2); + } + + return std::make_tuple(mean,cov); +} + +void SingleLFTracker::estimateState(const std::vector & scan) +{ + // temporary + createVehiclePositionParticle(particle_num_); + + std::vector likelihoods; + std::vector states; + + for(std::uint32_t i=0; i < particle_num_; i++){ + double likelihood = vehicle_particle_[i].calcCoarseLikelihood(scan); + likelihoods.push_back(likelihood); + Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); + states.push_back(state); + } + + auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + + auto mstate = std::get<0>(mean_cov); + covariance_ = std::get<1>(mean_cov); + position_ = Eigen::Vector2d(mstate.x(),mstate.y()); + orientation_ = mstate.z(); + + // fine tracking + createVehiclePositionParticle(particle_num_); + + likelihoods.clear(); + states.clear(); + + for(std::uint32_t i=0; i < particle_num_; i++){ + double likelihood = vehicle_particle_[i].calcFineLikelihood(scan); + likelihoods.push_back(likelihood); + Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); + states.push_back(state); + } + + + auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + + auto mstate = std::get<0>(mean_cov); + covariance_ = std::get<1>(mean_cov); + position_ = Eigen::Vector2d(mstate.x(),mstate.y()); + orientation_ = mstate.z(); + + +} + + + + +// void TrackerHandler::onTrackedObjects( +// const autoware_auto_perception_msgs::msg::TrackedObjects::ConstSharedPtr msg) +// { +// constexpr size_t max_buffer_size = 10; + +// // Add tracked objects to buffer +// objects_buffer_.push_front(*msg); + +// // Remove old data +// while (max_buffer_size < objects_buffer_.size()) { +// objects_buffer_.pop_back(); +// } +// } + +// bool TrackerHandler::estimateTrackedObjects( +// const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObjects & output) +// { +// if (objects_buffer_.empty()) { +// return false; +// } + +// // Get the objects closest to the target time. +// const auto target_objects_iter = std::min_element( +// objects_buffer_.cbegin(), objects_buffer_.cend(), +// [&time]( +// autoware_auto_perception_msgs::msg::TrackedObjects first, +// autoware_auto_perception_msgs::msg::TrackedObjects second) { +// return std::fabs((time - first.header.stamp).seconds()) < +// std::fabs((time - second.header.stamp).seconds()); +// }); + +// // Estimate the pose of the object at the target time +// const auto dt = time - target_objects_iter->header.stamp; +// output.header.frame_id = target_objects_iter->header.frame_id; +// output.header.stamp = time; +// for (const auto & object : target_objects_iter->objects) { +// const auto & pose_with_covariance = object.kinematics.pose_with_covariance; +// const auto & x = pose_with_covariance.pose.position.x; +// const auto & y = pose_with_covariance.pose.position.y; +// const auto & z = pose_with_covariance.pose.position.z; +// const float yaw = tf2::getYaw(pose_with_covariance.pose.orientation); +// const auto & twist = object.kinematics.twist_with_covariance.twist; +// const float & vx = twist.linear.x; +// const float & wz = twist.angular.z; + +// // build output +// autoware_auto_perception_msgs::msg::TrackedObject estimated_object; +// estimated_object.object_id = object.object_id; +// estimated_object.existence_probability = object.existence_probability; +// estimated_object.classification = object.classification; +// estimated_object.shape = object.shape; +// estimated_object.kinematics.pose_with_covariance.pose.position.x = +// x + vx * std::cos(yaw) * dt.seconds(); +// estimated_object.kinematics.pose_with_covariance.pose.position.y = +// y + vx * std::sin(yaw) * dt.seconds(); +// estimated_object.kinematics.pose_with_covariance.pose.position.z = z; +// const float yaw_hat = tier4_autoware_utils::normalizeRadian(yaw + wz * dt.seconds()); +// estimated_object.kinematics.pose_with_covariance.pose.orientation = +// tier4_autoware_utils::createQuaternionFromYaw(yaw_hat); +// output.objects.push_back(estimated_object); +// } +// return true; +// } + +// LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options) +// : rclcpp::Node("likelihood_field_tracker", node_options), +// tf_buffer_(this->get_clock()), +// tf_listener_(tf_buffer_) +// { +// // Create publishers and subscribers +// trackers_sub_ = create_subscription( +// "~/input/tracked_objects", rclcpp::QoS{1}, +// std::bind(&TrackerHandler::onTrackedObjects, &tracker_handler_, std::placeholders::_1)); +// initial_objects_sub_ = +// create_subscription( +// "~/input/initial_objects", rclcpp::QoS{1}, +// std::bind(&LikelihoodFieldTracker::onObjects, this, std::placeholders::_1)); +// objects_pub_ = create_publisher( +// "~/output", rclcpp::QoS{1}); + +// ignore_unknown_tracker_ = declare_parameter("ignore_unknown_tracker", true); + +// shape_estimator_ = std::make_shared(true, true); +// cluster_ = std::make_shared( +// false, 10, 10000, 0.7, 0.3, 0); +// debugger_ = std::make_shared(this); +// } + +// void LikelihoodFieldTracker::onObjects( +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg) +// { +// autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; +// detected_objects.header = input_msg->header; + +// // get objects from tracking module +// autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects; +// { +// autoware_auto_perception_msgs::msg::TrackedObjects objects, transformed_objects; +// const bool available_trackers = +// tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); +// if ( +// !available_trackers || +// !perception_utils::transformObjects( +// objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) { +// objects_pub_->publish(detected_objects); +// return; +// } +// // to simplify post processes, convert tracked_objects to DetectedObjects message. +// tracked_objects = perception_utils::toDetectedObjects(transformed_objects); +// } +// debugger_->publishInitialObjects(*input_msg); +// debugger_->publishTrackedObjects(tracked_objects); + +// // merge over segmented objects +// tier4_perception_msgs::msg::DetectedObjectsWithFeature merged_objects; +// autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects; +// mergeOverSegmentedObjects(tracked_objects, *input_msg, no_found_tracked_objects, merged_objects); +// debugger_->publishMergedObjects(merged_objects); + +// // divide under segmented objects +// tier4_perception_msgs::msg::DetectedObjectsWithFeature divided_objects; +// autoware_auto_perception_msgs::msg::DetectedObjects temp_no_found_tracked_objects; +// divideUnderSegmentedObjects( +// no_found_tracked_objects, *input_msg, temp_no_found_tracked_objects, divided_objects); +// debugger_->publishDividedObjects(divided_objects); + +// // merge under/over segmented objects to build output objects +// for (const auto & merged_object : merged_objects.feature_objects) { +// detected_objects.objects.push_back(merged_object.object); +// } +// for (const auto & divided_object : divided_objects.feature_objects) { +// detected_objects.objects.push_back(divided_object.object); +// } + +// objects_pub_->publish(detected_objects); +// } + +// void LikelihoodFieldTracker::divideUnderSegmentedObjects( +// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_cluster_objects, +// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, +// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects) +// { +// constexpr float recall_min_threshold = 0.4; +// constexpr float precision_max_threshold = 0.5; +// constexpr float max_search_range = 6.0; +// constexpr float min_score_threshold = 0.4; + +// out_objects.header = in_cluster_objects.header; +// out_no_found_tracked_objects.header = tracked_objects.header; + +// for (const auto & tracked_object : tracked_objects.objects) { +// const auto & label = tracked_object.classification.front().label; +// if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + +// std::optional +// highest_score_divided_object = std::nullopt; +// float highest_score = 0.0; + +// for (const auto & initial_object : in_cluster_objects.feature_objects) { +// // search near object +// const float distance = tier4_autoware_utils::calcDistance2d( +// tracked_object.kinematics.pose_with_covariance.pose, +// initial_object.object.kinematics.pose_with_covariance.pose); +// if (max_search_range < distance) { +// continue; +// } +// // detect under segmented cluster +// const float recall = perception_utils::get2dRecall(initial_object.object, tracked_object); +// const float precision = +// perception_utils::get2dPrecision(initial_object.object, tracked_object); +// const bool is_under_segmented = +// (recall_min_threshold < recall && precision < precision_max_threshold); +// if (!is_under_segmented) { +// continue; +// } +// // optimize clustering +// tier4_perception_msgs::msg::DetectedObjectWithFeature divided_object; +// float score = optimizeUnderSegmentedObject( +// tracked_object, initial_object.feature.cluster, divided_object); +// if (score < min_score_threshold) { +// continue; +// } + +// if (highest_score < score) { +// highest_score = score; +// highest_score_divided_object = divided_object; +// } +// } +// if (highest_score_divided_object) { // found +// out_objects.feature_objects.push_back(highest_score_divided_object.value()); +// } else { // not found +// out_no_found_tracked_objects.objects.push_back(tracked_object); +// } +// } +// } + +// float LikelihoodFieldTracker::optimizeUnderSegmentedObject( +// const autoware_auto_perception_msgs::msg::DetectedObject & target_object, +// const sensor_msgs::msg::PointCloud2 & under_segmented_cluster, +// tier4_perception_msgs::msg::DetectedObjectWithFeature & output) +// { +// constexpr float iter_rate = 0.8; +// constexpr int iter_max_count = 5; +// constexpr float initial_cluster_range = 0.7; +// float cluster_range = initial_cluster_range; +// constexpr float initial_voxel_size = initial_cluster_range / 2.0f; +// float voxel_size = initial_voxel_size; + +// const auto & label = target_object.classification.front().label; + +// // initialize clustering parameters +// euclidean_cluster::VoxelGridBasedEuclideanCluster cluster( +// false, 4, 10000, initial_cluster_range, initial_voxel_size, 0); + +// // convert to pcl +// pcl::PointCloud::Ptr pcl_cluster(new pcl::PointCloud); +// pcl::fromROSMsg(under_segmented_cluster, *pcl_cluster); + +// // iterate to find best fit divided object +// float highest_iou = 0.0; +// tier4_perception_msgs::msg::DetectedObjectWithFeature highest_iou_object; +// for (int iter_count = 0; iter_count < iter_max_count; +// ++iter_count, cluster_range *= iter_rate, voxel_size *= iter_rate) { +// // divide under segmented cluster +// std::vector> divided_clusters; +// cluster.setTolerance(cluster_range); +// cluster.setVoxelLeafSize(voxel_size); +// cluster.cluster(pcl_cluster, divided_clusters); + +// // find highest iou object in divided clusters +// float highest_iou_in_current_iter = 0.0f; +// tier4_perception_msgs::msg::DetectedObjectWithFeature highest_iou_object_in_current_iter; +// highest_iou_object_in_current_iter.object.classification = target_object.classification; +// for (const auto & divided_cluster : divided_clusters) { +// bool is_shape_estimated = shape_estimator_->estimateShapeAndPose( +// label, divided_cluster, +// getReferenceYawInfo( +// label, tf2::getYaw(target_object.kinematics.pose_with_covariance.pose.orientation)), +// highest_iou_object_in_current_iter.object.shape, +// highest_iou_object_in_current_iter.object.kinematics.pose_with_covariance.pose); +// if (!is_shape_estimated) { +// continue; +// } +// const float iou = +// perception_utils::get2dIoU(highest_iou_object_in_current_iter.object, target_object); +// if (highest_iou_in_current_iter < iou) { +// highest_iou_in_current_iter = iou; +// setClusterInObjectWithFeature( +// under_segmented_cluster.header, divided_cluster, highest_iou_object_in_current_iter); +// } +// } + +// // finish iteration when current score is under previous score +// if (highest_iou_in_current_iter < highest_iou) { +// break; +// } + +// // copy for next iteration +// highest_iou = highest_iou_in_current_iter; +// highest_iou_object = highest_iou_object_in_current_iter; +// } + +// // build output +// highest_iou_object.object.classification = target_object.classification; +// highest_iou_object.object.existence_probability = +// perception_utils::get2dIoU(target_object, highest_iou_object.object); + +// output = highest_iou_object; +// return highest_iou; +// } + +// void LikelihoodFieldTracker::mergeOverSegmentedObjects( +// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, +// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_cluster_objects, +// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, +// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects) +// { +// constexpr float precision_threshold = 0.5; +// constexpr float max_search_range = 5.0; +// out_objects.header = in_cluster_objects.header; +// out_no_found_tracked_objects.header = tracked_objects.header; + +// for (const auto & tracked_object : tracked_objects.objects) { +// const auto & label = tracked_object.classification.front().label; +// if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + +// // extend shape +// autoware_auto_perception_msgs::msg::DetectedObject extended_tracked_object = tracked_object; +// extended_tracked_object.shape = extendShape(tracked_object.shape, /*scale*/ 1.1); + +// pcl::PointCloud pcl_merged_cluster; +// for (const auto & initial_object : in_cluster_objects.feature_objects) { +// const float distance = tier4_autoware_utils::calcDistance2d( +// tracked_object.kinematics.pose_with_covariance.pose, +// initial_object.object.kinematics.pose_with_covariance.pose); + +// if (max_search_range < distance) { +// continue; +// } + +// // If there is an initial object in the tracker, it will be merged. +// const float precision = +// perception_utils::get2dPrecision(initial_object.object, extended_tracked_object); +// if (precision < precision_threshold) { +// continue; +// } +// pcl::PointCloud pcl_cluster; +// pcl::fromROSMsg(initial_object.feature.cluster, pcl_cluster); +// pcl_merged_cluster += pcl_cluster; +// } + +// if (pcl_merged_cluster.points.empty()) { // if clusters aren't found +// out_no_found_tracked_objects.objects.push_back(tracked_object); +// continue; +// } + +// // build output clusters +// tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object; +// feature_object.object.classification = tracked_object.classification; + +// bool is_shape_estimated = shape_estimator_->estimateShapeAndPose( +// label, pcl_merged_cluster, +// getReferenceYawInfo( +// label, tf2::getYaw(tracked_object.kinematics.pose_with_covariance.pose.orientation)), +// feature_object.object.shape, feature_object.object.kinematics.pose_with_covariance.pose); +// if (!is_shape_estimated) { +// out_no_found_tracked_objects.objects.push_back(tracked_object); +// continue; +// } + +// feature_object.object.existence_probability = +// perception_utils::get2dIoU(tracked_object, feature_object.object); +// setClusterInObjectWithFeature(in_cluster_objects.header, pcl_merged_cluster, feature_object); +// out_objects.feature_objects.push_back(feature_object); +// } +// } + +//#include +//RCLCPP_COMPONENTS_REGISTER_NODE(LikelihoodFieldTracker) From 8478fa68fd721653c7289933e8dcb02412fc0f77 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 02:02:31 +0900 Subject: [PATCH 02/75] fixed pointer exception and some other error --- .../likelihood_field_tracker.hpp | 4 +-- .../src/likelihood_field_tracker.cpp | 28 +++++++++---------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index d226fa3ee0209..716f76e240ab0 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -135,8 +135,8 @@ class VehicleParticle double inside_margin_ = 0.25; double outside_margin_ = 1.0; double measurement_noise_ = 0.1; - std::unique_ptr fine_likelihood_; // maybe it's ok to use std::optional instead - std::unique_ptr coarse_likelihood_; + std::shared_ptr fine_likelihood_; // maybe it's ok to use std::optional instead + std::shared_ptr coarse_likelihood_; std::array corner_points_; diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 0db667a483166..a366b17e01ce1 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -249,8 +249,8 @@ void VehicleParticle::setCornerPoints(const Eigen::Vector2d center, const double Eigen::Rotation2Dd rotate(orientation); /// rotation auto R = rotate.toRotationMatrix(); /// Rotation matrix R^T // corners in local coordinate - p0 = Eigen::Vector2d(length/2.0,-width/2.0); p1 = Eigen::Vector2d(-length/2.0,-width/2.0); - p2 = Eigen::Vector2d(-length/2.0,+width/2.0); p3 = Eigen::Vector2d(length/2.0,width/2.0); + auto p0 = Eigen::Vector2d(length/2.0,-width/2.0); auto p1 = Eigen::Vector2d(-length/2.0,-width/2.0); + auto p2 = Eigen::Vector2d(-length/2.0,+width/2.0); auto p3 = Eigen::Vector2d(length/2.0,width/2.0); // set corner points coordinates corner_points_[0] = R*p0 + center; corner_points_[1] = R*p1 + center; @@ -366,12 +366,12 @@ std::tuple calcMeanAndCovFromParticles(std::ve Eigen::Matrix3d cov; double w2 = 0; - for(std::size_t i; i < loop; i++){ + for(std::size_t i=0; i < loop; i++){ mean += vectors[i] * likelihoods[i]; w2 += likelihoods[i]*likelihoods[i]; } - for(std::size_t i; i < loop; i++){ + for(std::size_t i=0; i < loop; i++){ cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i]/(1-w2); } @@ -402,24 +402,24 @@ void SingleLFTracker::estimateState(const std::vector & scan) // fine tracking createVehiclePositionParticle(particle_num_); - - likelihoods.clear(); - states.clear(); + // tmp + std::vector likelihoods2; + std::vector states2; for(std::uint32_t i=0; i < particle_num_; i++){ double likelihood = vehicle_particle_[i].calcFineLikelihood(scan); - likelihoods.push_back(likelihood); + likelihoods2.push_back(likelihood); Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); - states.push_back(state); + states2.push_back(state); } - auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods2, states2); - auto mstate = std::get<0>(mean_cov); - covariance_ = std::get<1>(mean_cov); - position_ = Eigen::Vector2d(mstate.x(),mstate.y()); - orientation_ = mstate.z(); + auto mstate_ = std::get<0>(mean_cov_); + covariance_ = std::get<1>(mean_cov_); + position_ = Eigen::Vector2d(mstate_.x(),mstate_.y()); + orientation_ = mstate_.z(); } From 12133cd4c8762ebedd4bc3f0a637e4e2036b105f Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 11:48:40 +0900 Subject: [PATCH 03/75] add likelihood filed tracker --- .../likelihood_field_tracker.hpp | 101 ++++----- .../src/likelihood_field_tracker.cpp | 212 +++++++----------- 2 files changed, 123 insertions(+), 190 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 716f76e240ab0..eaec918d54dd8 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -28,6 +28,7 @@ #include #include #include +#include #include @@ -52,7 +53,7 @@ #include #include - +#include "detection_by_tracker/detection_by_tracker_core.hpp" //using autoware::common::types::float64_t; // convert double to float64_t later @@ -167,65 +168,53 @@ class SingleLFTracker public: SingleLFTracker(const autoware_auto_perception_msgs::msg::TrackedObject & object); void createVehiclePositionParticle(const std::uint32_t particle_num); - void createVehicleShapeParticle(); + //void createVehicleShapeParticle(); void estimateState(const std::vector & scan); }; -// class TrackerHandler -// { -// private: -// std::deque objects_buffer_; - -// public: -// TrackerHandler() = default; -// void onTrackedObjects( -// const autoware_auto_perception_msgs::msg::TrackedObjects::ConstSharedPtr input_objects_msg); -// bool estimateTrackedObjects( -// const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObjects & output); -// }; - -// class LikelihoodFieldTracker : public rclcpp::Node -// { -// public: -// explicit LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options); - -// private: -// rclcpp::Publisher::SharedPtr objects_pub_; -// rclcpp::Subscription::SharedPtr trackers_sub_; -// rclcpp::Subscription::SharedPtr -// initial_objects_sub_; - -// tf2_ros::Buffer tf_buffer_; -// tf2_ros::TransformListener tf_listener_; - -// TrackerHandler tracker_handler_; -// std::shared_ptr shape_estimator_; -// std::shared_ptr cluster_; -// std::shared_ptr debugger_; - -// bool ignore_unknown_tracker_; - -// void onObjects( -// const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg); - -// void divideUnderSegmentedObjects( -// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, -// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, -// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, -// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); - -// float optimizeUnderSegmentedObject( -// const autoware_auto_perception_msgs::msg::DetectedObject & target_object, -// const sensor_msgs::msg::PointCloud2 & under_segmented_cluster, -// tier4_perception_msgs::msg::DetectedObjectWithFeature & output); - -// void mergeOverSegmentedObjects( -// const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, -// const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, -// autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, -// tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); -// }; +class LikelihoodFieldTracker : public rclcpp::Node +{ +public: + explicit LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options); + +private: + rclcpp::Publisher::SharedPtr objects_pub_; + rclcpp::Subscription::SharedPtr trackers_sub_; + rclcpp::Subscription::SharedPtr scans_sub_; + rclcpp::Subscription::SharedPtr + initial_objects_sub_; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + TrackerHandler tracker_handler_; + std::shared_ptr shape_estimator_; + std::shared_ptr cluster_; + std::shared_ptr debugger_; + + bool ignore_unknown_tracker_; + + void onObjects( + const sensor_msgs::msg::LaserScan::ConstSharedPtr input_msg); + + // void divideUnderSegmentedObjects( + // const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, + // const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, + // autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, + // tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); + + // float optimizeUnderSegmentedObject( + // const autoware_auto_perception_msgs::msg::DetectedObject & target_object, + // const sensor_msgs::msg::PointCloud2 & under_segmented_cluster, + // tier4_perception_msgs::msg::DetectedObjectWithFeature & output); + + // void mergeOverSegmentedObjects( + // const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, + // const tier4_perception_msgs::msg::DetectedObjectsWithFeature & in_objects, + // autoware_auto_perception_msgs::msg::DetectedObjects & out_no_found_tracked_objects, + // tier4_perception_msgs::msg::DetectedObjectsWithFeature & out_objects); +}; #endif // DETECTION_BY_TRACKER__LIKELIHOOD_FIELD_TRACKER_CORE_HPP_ diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index a366b17e01ce1..bc729bd8a68e1 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "detection_by_tracker/likelihood_field_tracker.hpp" -#include "detection_by_tracker/detection_by_tracker_core.hpp" + #include "perception_utils/perception_utils.hpp" @@ -421,148 +421,92 @@ void SingleLFTracker::estimateState(const std::vector & scan) position_ = Eigen::Vector2d(mstate_.x(),mstate_.y()); orientation_ = mstate_.z(); - } - - - -// void TrackerHandler::onTrackedObjects( -// const autoware_auto_perception_msgs::msg::TrackedObjects::ConstSharedPtr msg) +/// PointCloud2 to eigen vector +// std::vector PoinCloud2ToScan(sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud) // { -// constexpr size_t max_buffer_size = 10; - -// // Add tracked objects to buffer -// objects_buffer_.push_front(*msg); - -// // Remove old data -// while (max_buffer_size < objects_buffer_.size()) { -// objects_buffer_.pop_back(); -// } +// cloud->data. // } -// bool TrackerHandler::estimateTrackedObjects( -// const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObjects & output) -// { -// if (objects_buffer_.empty()) { -// return false; -// } -// // Get the objects closest to the target time. -// const auto target_objects_iter = std::min_element( -// objects_buffer_.cbegin(), objects_buffer_.cend(), -// [&time]( -// autoware_auto_perception_msgs::msg::TrackedObjects first, -// autoware_auto_perception_msgs::msg::TrackedObjects second) { -// return std::fabs((time - first.header.stamp).seconds()) < -// std::fabs((time - second.header.stamp).seconds()); -// }); - -// // Estimate the pose of the object at the target time -// const auto dt = time - target_objects_iter->header.stamp; -// output.header.frame_id = target_objects_iter->header.frame_id; -// output.header.stamp = time; -// for (const auto & object : target_objects_iter->objects) { -// const auto & pose_with_covariance = object.kinematics.pose_with_covariance; -// const auto & x = pose_with_covariance.pose.position.x; -// const auto & y = pose_with_covariance.pose.position.y; -// const auto & z = pose_with_covariance.pose.position.z; -// const float yaw = tf2::getYaw(pose_with_covariance.pose.orientation); -// const auto & twist = object.kinematics.twist_with_covariance.twist; -// const float & vx = twist.linear.x; -// const float & wz = twist.angular.z; - -// // build output -// autoware_auto_perception_msgs::msg::TrackedObject estimated_object; -// estimated_object.object_id = object.object_id; -// estimated_object.existence_probability = object.existence_probability; -// estimated_object.classification = object.classification; -// estimated_object.shape = object.shape; -// estimated_object.kinematics.pose_with_covariance.pose.position.x = -// x + vx * std::cos(yaw) * dt.seconds(); -// estimated_object.kinematics.pose_with_covariance.pose.position.y = -// y + vx * std::sin(yaw) * dt.seconds(); -// estimated_object.kinematics.pose_with_covariance.pose.position.z = z; -// const float yaw_hat = tier4_autoware_utils::normalizeRadian(yaw + wz * dt.seconds()); -// estimated_object.kinematics.pose_with_covariance.pose.orientation = -// tier4_autoware_utils::createQuaternionFromYaw(yaw_hat); -// output.objects.push_back(estimated_object); -// } -// return true; -// } -// LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options) -// : rclcpp::Node("likelihood_field_tracker", node_options), -// tf_buffer_(this->get_clock()), -// tf_listener_(tf_buffer_) -// { -// // Create publishers and subscribers -// trackers_sub_ = create_subscription( -// "~/input/tracked_objects", rclcpp::QoS{1}, -// std::bind(&TrackerHandler::onTrackedObjects, &tracker_handler_, std::placeholders::_1)); -// initial_objects_sub_ = -// create_subscription( -// "~/input/initial_objects", rclcpp::QoS{1}, -// std::bind(&LikelihoodFieldTracker::onObjects, this, std::placeholders::_1)); -// objects_pub_ = create_publisher( -// "~/output", rclcpp::QoS{1}); - -// ignore_unknown_tracker_ = declare_parameter("ignore_unknown_tracker", true); - -// shape_estimator_ = std::make_shared(true, true); -// cluster_ = std::make_shared( -// false, 10, 10000, 0.7, 0.3, 0); -// debugger_ = std::make_shared(this); -// } +LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("likelihood_field_tracker", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + // Create publishers and subscribers + trackers_sub_ = create_subscription( + "~/input/tracked_objects", rclcpp::QoS{1}, + std::bind(&TrackerHandler::onTrackedObjects, &tracker_handler_, std::placeholders::_1)); + + scans_sub_ = create_subscription( + "/perception/occupancy_grid_map/virtual_scan/laserscan", rclcpp::QoS{1}, + std::bind(&LikelihoodFieldTracker::onObjects, this, std::placeholders::_1) ); + + // initial_objects_sub_ = + // create_subscription( + // "~/input/initial_objects", rclcpp::QoS{1}, + // std::bind(&LikelihoodFieldTracker::onObjects, this, std::placeholders::_1)); + objects_pub_ = create_publisher( + "/perception/lftracker", rclcpp::QoS{1}); + + //ignore_unknown_tracker_ = declare_parameter("ignore_unknown_tracker", true); + + /// ??? + // shape_estimator_ = std::make_shared(true, true); + // cluster_ = std::make_shared( + // false, 10, 10000, 0.7, 0.3, 0); + // debugger_ = std::make_shared(this); +} -// void LikelihoodFieldTracker::onObjects( -// const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg) -// { -// autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; -// detected_objects.header = input_msg->header; - -// // get objects from tracking module -// autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects; -// { -// autoware_auto_perception_msgs::msg::TrackedObjects objects, transformed_objects; -// const bool available_trackers = -// tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); -// if ( -// !available_trackers || -// !perception_utils::transformObjects( -// objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) { -// objects_pub_->publish(detected_objects); -// return; -// } -// // to simplify post processes, convert tracked_objects to DetectedObjects message. -// tracked_objects = perception_utils::toDetectedObjects(transformed_objects); -// } -// debugger_->publishInitialObjects(*input_msg); -// debugger_->publishTrackedObjects(tracked_objects); - -// // merge over segmented objects -// tier4_perception_msgs::msg::DetectedObjectsWithFeature merged_objects; -// autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects; -// mergeOverSegmentedObjects(tracked_objects, *input_msg, no_found_tracked_objects, merged_objects); -// debugger_->publishMergedObjects(merged_objects); - -// // divide under segmented objects -// tier4_perception_msgs::msg::DetectedObjectsWithFeature divided_objects; -// autoware_auto_perception_msgs::msg::DetectedObjects temp_no_found_tracked_objects; -// divideUnderSegmentedObjects( -// no_found_tracked_objects, *input_msg, temp_no_found_tracked_objects, divided_objects); -// debugger_->publishDividedObjects(divided_objects); - -// // merge under/over segmented objects to build output objects -// for (const auto & merged_object : merged_objects.feature_objects) { -// detected_objects.objects.push_back(merged_object.object); -// } -// for (const auto & divided_object : divided_objects.feature_objects) { -// detected_objects.objects.push_back(divided_object.object); -// } +void LikelihoodFieldTracker::onObjects( + const sensor_msgs::msg::LaserScan::ConstSharedPtr input_msg) +{ + autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; + detected_objects.header = input_msg->header; + + // get objects from tracking module + autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects; + { + autoware_auto_perception_msgs::msg::TrackedObjects objects, transformed_objects; + // Do prediction + const bool available_trackers = + tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); + + // Return if none object is tracked + if (!available_trackers) { + objects_pub_->publish(detected_objects); + return; + } + // to simplify post processes, convert tracked_objects to DetectedObjects message. + tracked_objects = perception_utils::toDetectedObjects(transformed_objects); + } -// objects_pub_->publish(detected_objects); -// } + // // merge over segmented objects + // tier4_perception_msgs::msg::DetectedObjectsWithFeature merged_objects; + // autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects; + // mergeOverSegmentedObjects(tracked_objects, *input_msg, no_found_tracked_objects, merged_objects); + // debugger_->publishMergedObjects(merged_objects); + + // // divide under segmented objects + // tier4_perception_msgs::msg::DetectedObjectsWithFeature divided_objects; + // autoware_auto_perception_msgs::msg::DetectedObjects temp_no_found_tracked_objects; + // divideUnderSegmentedObjects( + // no_found_tracked_objects, *input_msg, temp_no_found_tracked_objects, divided_objects); + // debugger_->publishDividedObjects(divided_objects); + + // // merge under/over segmented objects to build output objects + // for (const auto & merged_object : merged_objects.feature_objects) { + // detected_objects.objects.push_back(merged_object.object); + // } + // for (const auto & divided_object : divided_objects.feature_objects) { + // detected_objects.objects.push_back(divided_object.object); + // } + + objects_pub_->publish(detected_objects); +} // void LikelihoodFieldTracker::divideUnderSegmentedObjects( // const autoware_auto_perception_msgs::msg::DetectedObjects & tracked_objects, From aaee0b8cceb3bbde32cbcea3b5b82d659c9a3f51 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 12:02:22 +0900 Subject: [PATCH 04/75] add Laserscan to vector --- .../src/likelihood_field_tracker.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index bc729bd8a68e1..4b0bfe25f619c 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -480,8 +480,18 @@ void LikelihoodFieldTracker::onObjects( objects_pub_->publish(detected_objects); return; } + + // LaserScan to std::vector + std::vector scan_vec; + for(int i=0; input_msg->ranges.size();i++){ + double th = input_msg->angle_min+ (double)i*input_msg->angle_increment; + double range = input_msg->ranges[i]; + Eigen::Vector2d xy{range*cos(th), range*sin(th)}; + scan_vec.push_back(xy); + } + // to simplify post processes, convert tracked_objects to DetectedObjects message. - tracked_objects = perception_utils::toDetectedObjects(transformed_objects); + //tracked_objects = perception_utils::toDetectedObjects(transformed_objects); } // // merge over segmented objects From b2a7365c2b230023cf26ac3c1bdf02ff709a155c Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 12:39:37 +0900 Subject: [PATCH 05/75] test build for likelihood field tracker --- .../likelihood_field_tracker.hpp | 1 + .../src/likelihood_field_tracker.cpp | 39 ++++++++++++++++++- 2 files changed, 38 insertions(+), 2 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index eaec918d54dd8..ca1eacfcd2e8b 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -170,6 +170,7 @@ class SingleLFTracker void createVehiclePositionParticle(const std::uint32_t particle_num); //void createVehicleShapeParticle(); void estimateState(const std::vector & scan); + autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject(autoware_auto_perception_msgs::msg::TrackedObject &object); }; diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 4b0bfe25f619c..cc67b6b95b364 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -423,6 +423,23 @@ void SingleLFTracker::estimateState(const std::vector & scan) } + +autoware_auto_perception_msgs::msg::TrackedObject SingleLFTracker::toTrackedObject(autoware_auto_perception_msgs::msg::TrackedObject &object) +{ + autoware_auto_perception_msgs::msg::TrackedObject estimated_object; + estimated_object.object_id = object.object_id; + estimated_object.existence_probability = object.existence_probability; + estimated_object.classification = object.classification; + estimated_object.shape = object.shape; + estimated_object.kinematics.pose_with_covariance = object.kinematics.pose_with_covariance; + estimated_object.kinematics.pose_with_covariance.pose.position.x = position_.x(); + estimated_object.kinematics.pose_with_covariance.pose.position.y = position_.y(); + const float yaw_hat = tier4_autoware_utils::normalizeRadian(orientation_); + estimated_object.kinematics.pose_with_covariance.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw_hat); + + return estimated_object; +} + /// PointCloud2 to eigen vector // std::vector PoinCloud2ToScan(sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud) // { @@ -470,7 +487,7 @@ void LikelihoodFieldTracker::onObjects( // get objects from tracking module autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects; { - autoware_auto_perception_msgs::msg::TrackedObjects objects, transformed_objects; + autoware_auto_perception_msgs::msg::TrackedObjects objects, estimated_objects; // Do prediction const bool available_trackers = tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); @@ -490,8 +507,26 @@ void LikelihoodFieldTracker::onObjects( scan_vec.push_back(xy); } + + // tmp + // lf fitting for each objects + for(int i=0; objects.objects.size();i++){ + // apply only for vehicle + const auto label = objects.objects[i].classification.front().label; + const bool is_vehicle = Label::CAR == label || Label::TRUCK == label || Label::BUS == label || Label::TRAILER == label; + if(!is_vehicle){ + continue; + } + + // Create Tracker + SingleLFTracker vehicle(objects.objects[i]); + vehicle.estimateState(scan_vec); + estimated_objects.objects.push_back(vehicle.toTrackedObject(objects.objects[i])); + } + + // to simplify post processes, convert tracked_objects to DetectedObjects message. - //tracked_objects = perception_utils::toDetectedObjects(transformed_objects); + detected_objects = perception_utils::toDetectedObjects(estimated_objects); } // // merge over segmented objects From d59d6672e1a913c3224e0851a4c58c662e402bc8 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 12:57:18 +0900 Subject: [PATCH 06/75] add laserscan node to perception launch --- .../launch/perception.launch.xml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index ae6df48a412f2..7d1b4ac175e94 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -66,6 +66,16 @@ + + + + + + + + + + From 891420842e73a3d0032923b35c3e3d1a016d51bc Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 12:59:38 +0900 Subject: [PATCH 07/75] fix inf scan point error --- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index cc67b6b95b364..e3cee73548a46 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -503,6 +503,9 @@ void LikelihoodFieldTracker::onObjects( for(int i=0; input_msg->ranges.size();i++){ double th = input_msg->angle_min+ (double)i*input_msg->angle_increment; double range = input_msg->ranges[i]; + if( range > input_msg->range_max || range < input_msg->range_min){ + continue; + } Eigen::Vector2d xy{range*cos(th), range*sin(th)}; scan_vec.push_back(xy); } From 8737c2d5d2902dddcb9159953ce359a0ce4bdc18 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 28 Sep 2022 14:41:02 +0900 Subject: [PATCH 08/75] fix cmakelist and launch to run new node --- .../launch/perception.launch.xml | 4 ++-- perception/detection_by_tracker/CMakeLists.txt | 14 ++++++++++++++ .../launch/detection_by_tracker.launch.xml | 7 +++++++ .../src/likelihood_field_tracker.cpp | 4 ++-- 4 files changed, 25 insertions(+), 4 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 7d1b4ac175e94..b82399721a374 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -66,8 +66,9 @@ + - + @@ -76,7 +77,6 @@ - diff --git a/perception/detection_by_tracker/CMakeLists.txt b/perception/detection_by_tracker/CMakeLists.txt index 034f83a852e88..0f63e35d42e48 100644 --- a/perception/detection_by_tracker/CMakeLists.txt +++ b/perception/detection_by_tracker/CMakeLists.txt @@ -44,6 +44,20 @@ rclcpp_components_register_node(detection_by_tracker_node EXECUTABLE detection_by_tracker ) +ament_auto_add_library(likelihood_field_tracker_node SHARED + ${DETECTION_BY_TRACKER_SRC} +) + +target_link_libraries(likelihood_field_tracker_node + Eigen3::Eigen + ${PCL_LIBRARIES} +) + +rclcpp_components_register_node(likelihood_field_tracker_node + PLUGIN "LikelihoodFieldTracker" + EXECUTABLE likelihood_field_tracker +) + ament_auto_package(INSTALL_TO_SHARE launch ) diff --git a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml index 79e1b642cc53c..2b2ebf8e0bb1c 100644 --- a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml +++ b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml @@ -9,4 +9,11 @@ + + + + + + + diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index e3cee73548a46..1b0a61c6b7980 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -757,5 +757,5 @@ void LikelihoodFieldTracker::onObjects( // } // } -//#include -//RCLCPP_COMPONENTS_REGISTER_NODE(LikelihoodFieldTracker) +#include +RCLCPP_COMPONENTS_REGISTER_NODE(LikelihoodFieldTracker) From cc6a9dd7843ae2187f0baa885d4e477f8188da43 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 30 Sep 2022 17:39:34 +0900 Subject: [PATCH 09/75] Fixed QoS setting and typo in for loop --- .../src/likelihood_field_tracker.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 1b0a61c6b7980..8ce638a42bfdb 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -459,7 +459,7 @@ LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_ std::bind(&TrackerHandler::onTrackedObjects, &tracker_handler_, std::placeholders::_1)); scans_sub_ = create_subscription( - "/perception/occupancy_grid_map/virtual_scan/laserscan", rclcpp::QoS{1}, + "/perception/occupancy_grid_map/virtual_scan/laserscan", rclcpp::QoS{1}.best_effort(), std::bind(&LikelihoodFieldTracker::onObjects, this, std::placeholders::_1) ); // initial_objects_sub_ = @@ -476,11 +476,15 @@ LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_ // cluster_ = std::make_shared( // false, 10, 10000, 0.7, 0.3, 0); // debugger_ = std::make_shared(this); + + } void LikelihoodFieldTracker::onObjects( const sensor_msgs::msg::LaserScan::ConstSharedPtr input_msg) { + + autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; detected_objects.header = input_msg->header; @@ -500,7 +504,9 @@ void LikelihoodFieldTracker::onObjects( // LaserScan to std::vector std::vector scan_vec; - for(int i=0; input_msg->ranges.size();i++){ + for(long unsigned int i=0; i < input_msg->ranges.size();i++){ + + //std::cout<angle_min+ (double)i*input_msg->angle_increment; double range = input_msg->ranges[i]; if( range > input_msg->range_max || range < input_msg->range_min){ @@ -510,10 +516,13 @@ void LikelihoodFieldTracker::onObjects( scan_vec.push_back(xy); } + RCLCPP_WARN( + rclcpp::get_logger("LFTracker"), + "SubsCribed Scan"); // tmp // lf fitting for each objects - for(int i=0; objects.objects.size();i++){ + for(long unsigned int i=0; i < objects.objects.size();i++){ // apply only for vehicle const auto label = objects.objects[i].classification.front().label; const bool is_vehicle = Label::CAR == label || Label::TRUCK == label || Label::BUS == label || Label::TRAILER == label; From 8726a610b0703f7676086ffd63db56ab760f8337 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 30 Sep 2022 22:07:28 +0900 Subject: [PATCH 10/75] fix output and likelihood normalization part --- .../src/likelihood_field_tracker.cpp | 36 ++++++++++++------- 1 file changed, 23 insertions(+), 13 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 8ce638a42bfdb..895c9a64937ac 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -78,6 +78,13 @@ Eigen::Matrix3d extractXYYawCovariance(const std::array covariance) return cov; } +void eigenMatrixToROS2Covariance(const Eigen::Matrix3d covariance, std::array & cov) +{ + cov[0] = covariance(0,0); cov[1] = covariance(0,1); cov[5] = covariance(0,2); + cov[6] = covariance(1,0); cov[7] = covariance(1,1); cov[11] = covariance(1,2); + cov[30] = covariance(2,0); cov[31] = covariance(2,1); cov[35] = covariance(2,2); +} + /// sum of cost to calc likelihood double sumOfCostToLikelihood(double cost_sum, double sigma) { @@ -365,14 +372,20 @@ std::tuple calcMeanAndCovFromParticles(std::ve Eigen::Vector3d mean; Eigen::Matrix3d cov; double w2 = 0; + double sum_likelihoods = 0; + + for(std::size_t i=0; i < loop; i++){ + sum_likelihoods += likelihoods[i]; + } + for(std::size_t i=0; i < loop; i++){ - mean += vectors[i] * likelihoods[i]; - w2 += likelihoods[i]*likelihoods[i]; + mean += vectors[i] * likelihoods[i] / sum_likelihoods; + w2 += likelihoods[i]*likelihoods[i] / sum_likelihoods / sum_likelihoods; } for(std::size_t i=0; i < loop; i++){ - cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i]/(1-w2); + cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i] / sum_likelihoods /(1-w2); } return std::make_tuple(mean,cov); @@ -427,16 +440,17 @@ void SingleLFTracker::estimateState(const std::vector & scan) autoware_auto_perception_msgs::msg::TrackedObject SingleLFTracker::toTrackedObject(autoware_auto_perception_msgs::msg::TrackedObject &object) { autoware_auto_perception_msgs::msg::TrackedObject estimated_object; - estimated_object.object_id = object.object_id; - estimated_object.existence_probability = object.existence_probability; - estimated_object.classification = object.classification; - estimated_object.shape = object.shape; - estimated_object.kinematics.pose_with_covariance = object.kinematics.pose_with_covariance; + estimated_object = object; + // estimated_object.object_id = object.object_id; + // estimated_object.existence_probability = object.existence_probability; + // estimated_object.classification = object.classification; + // estimated_object.shape = object.shape; + // estimated_object.kinematics.pose_with_covariance = object.kinematics.pose_with_covariance; estimated_object.kinematics.pose_with_covariance.pose.position.x = position_.x(); estimated_object.kinematics.pose_with_covariance.pose.position.y = position_.y(); const float yaw_hat = tier4_autoware_utils::normalizeRadian(orientation_); estimated_object.kinematics.pose_with_covariance.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw_hat); - + eigenMatrixToROS2Covariance(covariance_, estimated_object.kinematics.pose_with_covariance.covariance); return estimated_object; } @@ -476,15 +490,11 @@ LikelihoodFieldTracker::LikelihoodFieldTracker(const rclcpp::NodeOptions & node_ // cluster_ = std::make_shared( // false, 10, 10000, 0.7, 0.3, 0); // debugger_ = std::make_shared(this); - - } void LikelihoodFieldTracker::onObjects( const sensor_msgs::msg::LaserScan::ConstSharedPtr input_msg) { - - autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; detected_objects.header = input_msg->header; From ba1e6bdf88c10495b0625d97cbe8dfb2e77581d9 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Sun, 2 Oct 2022 01:18:22 +0900 Subject: [PATCH 11/75] quit using shareptr in VehicleParticle --- .../likelihood_field_tracker.hpp | 8 +++--- .../src/likelihood_field_tracker.cpp | 25 +++++++++++-------- 2 files changed, 19 insertions(+), 14 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index ca1eacfcd2e8b..5b1b0d66fc07e 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -133,11 +133,11 @@ class FineCarLikelihoodField class VehicleParticle { private: - double inside_margin_ = 0.25; - double outside_margin_ = 1.0; + const double inside_margin_ = 0.25; + const double outside_margin_ = 1.0; double measurement_noise_ = 0.1; - std::shared_ptr fine_likelihood_; // maybe it's ok to use std::optional instead - std::shared_ptr coarse_likelihood_; + FineCarLikelihoodField fine_likelihood_; // maybe it's ok to use std::optional instead + CoarseCarLikelihoodField coarse_likelihood_; std::array corner_points_; diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 895c9a64937ac..20ab41a98a705 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -239,11 +239,13 @@ double FineCarLikelihoodField::calcLikelihoods(const std::vector { auto corner_index = getNearestCornerIndex(); auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); - auto likelihood = coarse_likelihood_->calcLikelihoods(local_measurements, corner_index); + auto likelihood = coarse_likelihood_.calcLikelihoods(local_measurements, corner_index); return likelihood; } @@ -318,7 +320,7 @@ double VehicleParticle::calcFineLikelihood(const std::vector & { auto corner_index = getNearestCornerIndex(); auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); - auto likelihood = fine_likelihood_->calcLikelihoods(local_measurements, corner_index); + auto likelihood = fine_likelihood_.calcLikelihoods(local_measurements, corner_index); return likelihood; } @@ -416,18 +418,20 @@ void SingleLFTracker::estimateState(const std::vector & scan) // fine tracking createVehiclePositionParticle(particle_num_); // tmp - std::vector likelihoods2; - std::vector states2; + likelihoods.clear(); + states.clear(); + //std::vector likelihoods2; + //std::vector states2; for(std::uint32_t i=0; i < particle_num_; i++){ double likelihood = vehicle_particle_[i].calcFineLikelihood(scan); - likelihoods2.push_back(likelihood); + likelihoods.push_back(likelihood); Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); - states2.push_back(state); + states.push_back(state); } - auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods2, states2); + auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); auto mstate_ = std::get<0>(mean_cov_); covariance_ = std::get<1>(mean_cov_); @@ -535,6 +539,7 @@ void LikelihoodFieldTracker::onObjects( for(long unsigned int i=0; i < objects.objects.size();i++){ // apply only for vehicle const auto label = objects.objects[i].classification.front().label; + std::cout << label < Date: Tue, 4 Oct 2022 01:28:55 +0900 Subject: [PATCH 12/75] fix invalid index address problem --- .../include/detection_by_tracker/likelihood_field_tracker.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 5b1b0d66fc07e..51567cbf1d5cc 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -87,7 +87,7 @@ class CoarseCarLikelihoodField /// cost value of {contour, outside} std::vector costs_ = {0.01, 0.1}; std::array contour_zones_; - const std::vector> indexes_ = {{0,1},{1,2},{2,3},{3,0}}; + const std::array, 4> indexes_ = {{{0,1},{1,2},{2,3},{3,0}}}; public: @@ -113,7 +113,7 @@ class FineCarLikelihoodField RectangleZone car_contour_; /// Rectangle Area std::array penalty_zones_; std::array contour_zones_; - const std::vector> indexes_ = {{0,1},{1,2},{2,3},{3,0}}; + const std::array, 4> indexes_ = {{{0,1},{1,2},{2,3},{3,0}}}; public: explicit FineCarLikelihoodField(const double width, const double length, From 319a582b94912cccf22f2ec6634b437645a62dbd Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Oct 2022 01:30:14 +0900 Subject: [PATCH 13/75] fix bug in vehicle particle likelihood --- .../src/likelihood_field_tracker.cpp | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 20ab41a98a705..b830c0f63dd66 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -86,11 +86,14 @@ void eigenMatrixToROS2Covariance(const Eigen::Matrix3d covariance, std::array base_link (may be unneccesary) + //geometry_msgs::msg::TransformStamped map_to_baselink = tf_buffer_.lookupTransform(input_msg->header.frame_id, "base_link", input_msg->header.stamp); + // tmp // lf fitting for each objects for(long unsigned int i=0; i < objects.objects.size();i++){ @@ -546,6 +554,9 @@ void LikelihoodFieldTracker::onObjects( } // Create Tracker + + + tf2::doTransform(robot_pose, robot_pose, base_link_to_leap_motion); SingleLFTracker vehicle(objects.objects[i]); vehicle.estimateState(scan_vec); estimated_objects.objects.push_back(vehicle.toTrackedObject(objects.objects[i])); From b1943d467f5daeafbe4d94276dd4495cd670e673 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Oct 2022 05:50:09 +0900 Subject: [PATCH 14/75] changed many settings --- .../src/likelihood_field_tracker.cpp | 56 ++++++++++++++++--- 1 file changed, 48 insertions(+), 8 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index b830c0f63dd66..7fe37d5276d5d 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -88,10 +88,40 @@ void eigenMatrixToROS2Covariance(const Eigen::Matrix3d covariance, std::array +void transformObjectsFromMapToBaselink +(T & object_map, T & object_baselink, + std_msgs::msg::Header header, tf2_ros::Buffer & buffer) +{ + geometry_msgs::msg::PoseWithCovarianceStamped before, after; + before.pose = object_map.kinematics.pose_with_covariance; + before.header = header; + before.header.frame_id = "map"; + after = buffer.transform(before, "base_link"); + object_baselink = object_map; + object_baselink.kinematics.pose_with_covariance = after.pose; + object_baselink.kinematics.pose_with_covariance.pose.position.z = before.pose.pose.position.z; +} + + +template +void transformObjectsFromBaselinkToMap +(T & object_baselink, T & object_map, + std_msgs::msg::Header header, tf2_ros::Buffer & buffer) +{ + geometry_msgs::msg::PoseWithCovarianceStamped before, after; + before.pose = object_baselink.kinematics.pose_with_covariance; + before.header = header; + before.header.frame_id = "base_link"; + after = buffer.transform(before, "map"); + object_map = object_baselink; + object_map.kinematics.pose_with_covariance = after.pose; + object_map.kinematics.pose_with_covariance.pose.position.z = before.pose.pose.position.z; +} } // namespace @@ -166,7 +196,7 @@ double CoarseCarLikelihoodField::calcLikelihoods(const std::vectorheader; // Do prediction const bool available_trackers = tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); @@ -554,12 +591,15 @@ void LikelihoodFieldTracker::onObjects( } // Create Tracker + autoware_auto_perception_msgs::msg::TrackedObject local_object, estimated_local_object, estimated_object; - - tf2::doTransform(robot_pose, robot_pose, base_link_to_leap_motion); - SingleLFTracker vehicle(objects.objects[i]); + transformObjectsFromMapToBaselink(objects.objects[i], local_object, input_msg->header, tf_buffer_); + SingleLFTracker vehicle(local_object); vehicle.estimateState(scan_vec); - estimated_objects.objects.push_back(vehicle.toTrackedObject(objects.objects[i])); + estimated_local_object = vehicle.toTrackedObject(objects.objects[i]); + + transformObjectsFromBaselinkToMap(estimated_local_object, estimated_object, input_msg->header, tf_buffer_); + estimated_objects.objects.push_back(estimated_object); } @@ -569,7 +609,7 @@ void LikelihoodFieldTracker::onObjects( // // merge over segmented objects // tier4_perception_msgs::msg::DetectedObjectsWithFeature merged_objects; - // autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects; + // autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects ; // mergeOverSegmentedObjects(tracked_objects, *input_msg, no_found_tracked_objects, merged_objects); // debugger_->publishMergedObjects(merged_objects); From c4e3d0cdd53518e4fce88e6d3d612397beb95434 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Oct 2022 14:44:27 +0900 Subject: [PATCH 15/75] fixed output frame_id to map --- perception/detection_by_tracker/src/likelihood_field_tracker.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 7fe37d5276d5d..bcd508adcf0a7 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -548,6 +548,7 @@ void LikelihoodFieldTracker::onObjects( { autoware_auto_perception_msgs::msg::TrackedObjects objects, estimated_objects; estimated_objects.header = input_msg->header; + estimated_objects.header.frame_id = "map"; // Do prediction const bool available_trackers = tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); From 35a9e1490d5c04b735a2af409ba58eb90c4fcf4f Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Oct 2022 14:45:00 +0900 Subject: [PATCH 16/75] add launch for debugging --- .../detection_by_tracker/launch/my_debug.launch.xml | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 perception/detection_by_tracker/launch/my_debug.launch.xml diff --git a/perception/detection_by_tracker/launch/my_debug.launch.xml b/perception/detection_by_tracker/launch/my_debug.launch.xml new file mode 100644 index 0000000000000..10fea8cc31790 --- /dev/null +++ b/perception/detection_by_tracker/launch/my_debug.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + From ce869fd3deee9cb6afe25f569aca96bc962d9912 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Oct 2022 14:45:00 +0900 Subject: [PATCH 17/75] add launch for debugging --- .../launch/detection_by_tracker.launch.xml | 6 ------ .../detection_by_tracker/launch/my_debug.launch.xml | 13 +++++++++++++ 2 files changed, 13 insertions(+), 6 deletions(-) create mode 100644 perception/detection_by_tracker/launch/my_debug.launch.xml diff --git a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml index 2b2ebf8e0bb1c..d24611bfabe4c 100644 --- a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml +++ b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml @@ -10,10 +10,4 @@ - - - - - - diff --git a/perception/detection_by_tracker/launch/my_debug.launch.xml b/perception/detection_by_tracker/launch/my_debug.launch.xml new file mode 100644 index 0000000000000..10fea8cc31790 --- /dev/null +++ b/perception/detection_by_tracker/launch/my_debug.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + From 5016f65549e388f8f8b4efd66c38e8bb7af8c2bd Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 01:27:50 +0900 Subject: [PATCH 18/75] Changed cost value and add default index num --- .../detection_by_tracker/likelihood_field_tracker.hpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 51567cbf1d5cc..5718d00e33ad0 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include @@ -85,7 +86,7 @@ class CoarseCarLikelihoodField private: double measurement_covariance_ = 0.1; /// cost value of {contour, outside} - std::vector costs_ = {0.01, 0.1}; + std::vector costs_ = {-0.02, 0}; std::array contour_zones_; const std::array, 4> indexes_ = {{{0,1},{1,2},{2,3},{3,0}}}; @@ -108,7 +109,7 @@ class FineCarLikelihoodField { private: /// cost value represent {penalty, contour, inside, outside} - std::vector costs_ = {0.1, 0.01, 0.03, 0.06}; + std::vector costs_ = {0.02,-0.04, -0.01, 0}; double measurement_covariance_ = 0.1; RectangleZone car_contour_; /// Rectangle Area std::array penalty_zones_; @@ -145,6 +146,7 @@ class VehicleParticle public: Eigen::Vector2d center_; double orientation_; + std::uint8_t corner_index_; explicit VehicleParticle(const Eigen::Vector2d center, const double width, const double length, const double orientation); void setCornerPoints(const Eigen::Vector2d center, const double width, const double length, const double orientation); std::uint8_t getNearestCornerIndex(const Eigen::Vector2d & origin = Eigen::Vector2d(0.0,0.0)); /// ego origin is set 0,0 by default From 714dde1f9efe5d2a0a3bff10e7f8d78be0762f3b Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 01:34:55 +0900 Subject: [PATCH 19/75] Try to use best particle --- .../src/likelihood_field_tracker.cpp | 83 ++++++++++++++++--- 1 file changed, 71 insertions(+), 12 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index bcd508adcf0a7..61c2180b4c3cc 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -88,7 +88,22 @@ void eigenMatrixToROS2Covariance(const Eigen::Matrix3d covariance, std::array +std::vector findMaxIndices(std::vector v){ + std::vector pos; + + auto it = std::max_element(std::begin(v), std::end(v)); + while (it != std::end(v)) + { + pos.push_back(std::distance(std::begin(v), it)); + it = std::find(std::next(it), std::end(v), *it); + } + return pos; } /// convert Pose without Stamped Message to Pose @@ -337,9 +352,9 @@ std::vector VehicleParticle::toLocalCoordinate(const std::vecto */ double VehicleParticle::calcCoarseLikelihood(const std::vector & measurements) { - auto corner_index = getNearestCornerIndex(); + //auto corner_index = getNearestCornerIndex(); auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); - auto likelihood = coarse_likelihood_.calcLikelihoods(local_measurements, corner_index); + auto likelihood = coarse_likelihood_.calcLikelihoods(local_measurements, corner_index_); return likelihood; } @@ -351,9 +366,9 @@ double VehicleParticle::calcCoarseLikelihood(const std::vector */ double VehicleParticle::calcFineLikelihood(const std::vector & measurements) { - auto corner_index = getNearestCornerIndex(); + //auto corner_index = getNearestCornerIndex(); auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); - auto likelihood = fine_likelihood_.calcLikelihoods(local_measurements, corner_index); + auto likelihood = fine_likelihood_.calcLikelihoods(local_measurements, corner_index_); return likelihood; } @@ -366,12 +381,13 @@ SingleLFTracker::SingleLFTracker(const autoware_auto_perception_msgs::msg::Track orientation_ = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); length_ = object.shape.dimensions.x; width_ = object.shape.dimensions.y; + //covariance_ = covariance_ = extractXYYawCovariance(object.kinematics.pose_with_covariance.covariance); // tmp - covariance_(0,0) = 0.1; // 0.3m error - covariance_(1,1) = 0.1; - covariance_(2,2) = DEG2RAD(15.)*DEG2RAD(15.); // 15deg + covariance_(0,0) = 2; // 0.3m error + covariance_(1,1) = 2; + covariance_(2,2) = DEG2RAD(10.)*DEG2RAD(10.); // 10deg // control parameter particle_num_ = 100; @@ -386,6 +402,9 @@ void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance_(0, 0))); std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance_(1, 1))); std::normal_distribution<> yaw_distribution(0.0, std::sqrt(covariance_(2, 2))); + // generate vp + VehicleParticle vp(position_ , width_, length_, orientation_); + std::uint8_t index = vp.getNearestCornerIndex(); // generate random vehicle particles for(std::uint32_t i =0; i calcMeanAndCovFromParticles(std::ve return std::make_tuple(mean,cov); } + +std::tuple calcBestParticles(std::vector & likelihoods, std::vector vectors) +{ + + Eigen::Vector3d mean; + Eigen::Matrix3d cov; + double w2 = 0; + double sum_likelihoods = 0; + + std::vector max_indexes = findMaxIndices(likelihoods); + + + for(std::size_t i: max_indexes){ + sum_likelihoods += likelihoods[i]; + } + + + for(std::size_t i: max_indexes){ + mean += vectors[i] * likelihoods[i] / sum_likelihoods; + w2 += likelihoods[i]*likelihoods[i] / sum_likelihoods / sum_likelihoods; + } + + for(std::size_t i: max_indexes){ + cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i] / sum_likelihoods /(1-w2); + } + cov(0,0) = 0.4; + cov(1,1) = 0.4; + + return std::make_tuple(mean,cov); +} + + + void SingleLFTracker::estimateState(const std::vector & scan) { // temporary @@ -449,10 +502,11 @@ void SingleLFTracker::estimateState(const std::vector & scan) states.push_back(state); } - auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + //auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + auto mean_cov = calcBestParticles(likelihoods, states); auto mstate = std::get<0>(mean_cov); - covariance_ = std::get<1>(mean_cov); + //covariance_ = std::get<1>(mean_cov); position_ = Eigen::Vector2d(mstate.x(),mstate.y()); orientation_ = mstate.z(); @@ -472,8 +526,10 @@ void SingleLFTracker::estimateState(const std::vector & scan) } - auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); - + //auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); + auto mean_cov_ = calcBestParticles(likelihoods, states); + + auto mstate_ = std::get<0>(mean_cov_); covariance_ = std::get<1>(mean_cov_); position_ = Eigen::Vector2d(mstate_.x(),mstate_.y()); @@ -606,6 +662,9 @@ void LikelihoodFieldTracker::onObjects( // to simplify post processes, convert tracked_objects to DetectedObjects message. detected_objects = perception_utils::toDetectedObjects(estimated_objects); + + // clear objects + //tracker_handler_ } // // merge over segmented objects From 8ad8b34836978ec7ab0493b6aff241250a0b58f4 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 01:45:47 +0900 Subject: [PATCH 20/75] fixed typo in nearest corener --- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 61c2180b4c3cc..83bed729dff59 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -318,12 +318,12 @@ void VehicleParticle::setCornerPoints(const Eigen::Vector2d center, const double std::uint8_t VehicleParticle::getNearestCornerIndex(const Eigen::Vector2d & center) { std::uint8_t closest_index = 0; - double max_dist = 100; // distance[m] + double min_dist = 100; // distance[m] double buff = 0; for(std::uint8_t i=0; i<4; i++){ buff = (corner_points_[i] - center).norm(); - if(buff Date: Fri, 7 Oct 2022 01:49:08 +0900 Subject: [PATCH 21/75] fixed zones indices order --- .../include/detection_by_tracker/likelihood_field_tracker.hpp | 4 ++-- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 5718d00e33ad0..582f60fff5d64 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -88,7 +88,7 @@ class CoarseCarLikelihoodField /// cost value of {contour, outside} std::vector costs_ = {-0.02, 0}; std::array contour_zones_; - const std::array, 4> indexes_ = {{{0,1},{1,2},{2,3},{3,0}}}; + const std::array, 4> indexes_ = {{{3,0},{0,1},{1,2},{2,3}}}; public: @@ -114,7 +114,7 @@ class FineCarLikelihoodField RectangleZone car_contour_; /// Rectangle Area std::array penalty_zones_; std::array contour_zones_; - const std::array, 4> indexes_ = {{{0,1},{1,2},{2,3},{3,0}}}; + const std::array, 4> indexes_ = {{{3,0},{1,2},{2,3},{3,0}}}; public: explicit FineCarLikelihoodField(const double width, const double length, diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 83bed729dff59..7389f89ac9b88 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -307,7 +307,7 @@ void VehicleParticle::setCornerPoints(const Eigen::Vector2d center, const double auto R = rotate.toRotationMatrix(); /// Rotation matrix R^T // corners in local coordinate auto p0 = Eigen::Vector2d(length/2.0,-width/2.0); auto p1 = Eigen::Vector2d(-length/2.0,-width/2.0); - auto p2 = Eigen::Vector2d(-length/2.0,+width/2.0); auto p3 = Eigen::Vector2d(length/2.0,width/2.0); + auto p2 = Eigen::Vector2d(-length/2.0,width/2.0); auto p3 = Eigen::Vector2d(length/2.0,width/2.0); // set corner points coordinates corner_points_[0] = R*p0 + center; corner_points_[1] = R*p1 + center; From e7ef477df45d6e149d25f70558fea60053b3bfda Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 02:10:29 +0900 Subject: [PATCH 22/75] fix typo in indexes_ --- .../include/detection_by_tracker/likelihood_field_tracker.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 582f60fff5d64..df1db38a6d568 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -114,7 +114,7 @@ class FineCarLikelihoodField RectangleZone car_contour_; /// Rectangle Area std::array penalty_zones_; std::array contour_zones_; - const std::array, 4> indexes_ = {{{3,0},{1,2},{2,3},{3,0}}}; + const std::array, 4> indexes_ = {{{3,0},{0,1},{1,2},{2,3}}}; public: explicit FineCarLikelihoodField(const double width, const double length, From 1c92f8d3e66b17be88124edb7617a292df01d1e2 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 03:34:02 +0900 Subject: [PATCH 23/75] Disabled orientation pertubation --- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 7389f89ac9b88..b5d36911285dc 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -390,7 +390,7 @@ SingleLFTracker::SingleLFTracker(const autoware_auto_perception_msgs::msg::Track covariance_(2,2) = DEG2RAD(10.)*DEG2RAD(10.); // 10deg // control parameter - particle_num_ = 1000; + particle_num_ = 100; } @@ -410,7 +410,7 @@ void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle for(std::uint32_t i =0; i & scan) } - //auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); - auto mean_cov_ = calcBestParticles(likelihoods, states); +// auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); +auto mean_cov_ = calcBestParticles(likelihoods, states); auto mstate_ = std::get<0>(mean_cov_); From 2de91f902b610573315c44dcb0bf9f6d22cc30c3 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 03:48:06 +0900 Subject: [PATCH 24/75] Try to skip coarse fitting --- .../src/likelihood_field_tracker.cpp | 38 +++++++++---------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index b5d36911285dc..bde9320db912d 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -410,7 +410,7 @@ void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle for(std::uint32_t i =0; i & scan) std::vector likelihoods; std::vector states; - for(std::uint32_t i=0; i < particle_num_; i++){ - double likelihood = vehicle_particle_[i].calcCoarseLikelihood(scan); - likelihoods.push_back(likelihood); - Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); - states.push_back(state); - } + // for(std::uint32_t i=0; i < particle_num_; i++){ + // double likelihood = vehicle_particle_[i].calcCoarseLikelihood(scan); + // likelihoods.push_back(likelihood); + // Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); + // states.push_back(state); + // } - //auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); - auto mean_cov = calcBestParticles(likelihoods, states); + // //auto mean_cov = calcMeanAndCovFromParticles(likelihoods, states); + // auto mean_cov = calcBestParticles(likelihoods, states); - auto mstate = std::get<0>(mean_cov); - //covariance_ = std::get<1>(mean_cov); - position_ = Eigen::Vector2d(mstate.x(),mstate.y()); - orientation_ = mstate.z(); - - // fine tracking - createVehiclePositionParticle(particle_num_); - // tmp - likelihoods.clear(); - states.clear(); + // auto mstate = std::get<0>(mean_cov); + // //covariance_ = std::get<1>(mean_cov); + // position_ = Eigen::Vector2d(mstate.x(),mstate.y()); + // orientation_ = mstate.z(); + + // // fine tracking + // createVehiclePositionParticle(particle_num_); + // // tmp + // likelihoods.clear(); + // states.clear(); //std::vector likelihoods2; //std::vector states2; From 44ff800a43bbc653aa0e6a09a8010e29b4e6644b Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 04:12:58 +0900 Subject: [PATCH 25/75] Tried uniform sampling --- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index bde9320db912d..661bff6dd8d66 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -399,9 +399,9 @@ void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle // Strictly, we should use multivariate normal distribution // Relaxed Results std::default_random_engine engine(seed_gen()); - std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance_(0, 0))); - std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance_(1, 1))); - std::normal_distribution<> yaw_distribution(0.0, std::sqrt(covariance_(2, 2))); + std::uniform_real_distribution<> x_distribution(-covariance_(0, 0), covariance_(0, 0)); //std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance_(0, 0))); + std::uniform_real_distribution<> y_distribution(-covariance_(1, 1), covariance_(1, 1)); //std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance_(1, 1))); + //std::normal_distribution<> yaw_distribution(0.0, std::sqrt(covariance_(2, 2))); // generate vp VehicleParticle vp(position_ , width_, length_, orientation_); std::uint8_t index = vp.getNearestCornerIndex(); From f676fd0e8976d80a4c4d85da8f0afde3e06bb96d Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 14:04:42 +0900 Subject: [PATCH 26/75] Shrink penality zones --- .../detection_by_tracker/src/likelihood_field_tracker.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 661bff6dd8d66..8b92c35ab1b80 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -242,10 +242,10 @@ void FineCarLikelihoodField::setContourZones(const double width, const double le void FineCarLikelihoodField::setPenaltyZones(const double width, const double length, const double outside_margin, const double inside_margin) { auto W2 = width/2.0; auto L2 = length/2.0; - penalty_zones_[0].setZone(-L2-outside_margin, L2+outside_margin, -W2-outside_margin, -W2); - penalty_zones_[1].setZone(-L2-outside_margin, -L2, -W2-outside_margin, W2+outside_margin); - penalty_zones_[2].setZone(-L2-outside_margin, L2+outside_margin, W2, W2+outside_margin); - penalty_zones_[3].setZone(L2, L2+outside_margin, -W2-outside_margin, W2+outside_margin); + penalty_zones_[0].setZone(-L2, L2, -W2-outside_margin, -W2); + penalty_zones_[1].setZone(-L2-outside_margin, -L2, -W2, W2); + penalty_zones_[2].setZone(-L2, L2, W2, W2+outside_margin); + penalty_zones_[3].setZone(L2, L2+outside_margin, -W2, W2); (void)inside_margin; // currently unused } From 808105e9860cd904ba324b7553d2af17249385f2 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 11 Oct 2022 09:42:08 +0900 Subject: [PATCH 27/75] use cov information add grid search --- .../likelihood_field_tracker.hpp | 3 +- .../src/likelihood_field_tracker.cpp | 50 ++++++++++++++++--- 2 files changed, 46 insertions(+), 7 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index df1db38a6d568..c917dc9f9d8a6 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -169,7 +169,8 @@ class SingleLFTracker public: SingleLFTracker(const autoware_auto_perception_msgs::msg::TrackedObject & object); - void createVehiclePositionParticle(const std::uint32_t particle_num); + void createRandomVehiclePositionParticle(const std::uint32_t particle_num); + void createGridVehiclePositionParticle(); //void createVehicleShapeParticle(); void estimateState(const std::vector & scan); autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject(autoware_auto_perception_msgs::msg::TrackedObject &object); diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 8b92c35ab1b80..b963ebd67173e 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -385,16 +385,16 @@ SingleLFTracker::SingleLFTracker(const autoware_auto_perception_msgs::msg::Track covariance_ = extractXYYawCovariance(object.kinematics.pose_with_covariance.covariance); // tmp - covariance_(0,0) = 2; // 0.3m error - covariance_(1,1) = 2; - covariance_(2,2) = DEG2RAD(10.)*DEG2RAD(10.); // 10deg + // covariance_(0,0) = 2; // 0.3m error + // covariance_(1,1) = 2; + // covariance_(2,2) = DEG2RAD(10.)*DEG2RAD(10.); // 10deg // control parameter particle_num_ = 100; } -void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle_num) +void SingleLFTracker::createRandomVehiclePositionParticle(const std::uint32_t particle_num) { // Strictly, we should use multivariate normal distribution // Relaxed Results @@ -419,6 +419,42 @@ void SingleLFTracker::createVehiclePositionParticle(const std::uint32_t particle } +double get_interpV(int i, int len, double wid){ + return ( 2.0*(double)i/(len-1.0) - 1.0 ) * wid; +} + +void SingleLFTracker::createGridVehiclePositionParticle() +{ + // Strictly, we should use multivariate normal distribution + // Relaxed Results + double x_wid, y_wid, yaw_wid; + double max_wid = 2; // 2m is max + int ilen = 10; + + x_wid = std::min(std::sqrt(covariance_(0,0)), max_wid); + y_wid = std::min(std::sqrt(covariance_(1,1)), max_wid); + yaw_wid = DEG2RAD(15.0); + + // generate vp + VehicleParticle vp(position_ , width_, length_, orientation_); + std::uint8_t index = vp.getNearestCornerIndex(); + + for(int i=0;i calcBestParticles(std::vector & scan) { // temporary - createVehiclePositionParticle(particle_num_); + //createRandomVehiclePositionParticle(particle_num_); + createGridVehiclePositionParticle(); + std::vector likelihoods; std::vector states; @@ -511,7 +549,7 @@ void SingleLFTracker::estimateState(const std::vector & scan) // orientation_ = mstate.z(); // // fine tracking - // createVehiclePositionParticle(particle_num_); + // createRandomVehiclePositionParticle(particle_num_); // // tmp // likelihoods.clear(); // states.clear(); From 59b238e75ca8df5d9b319df48578a1e954aa40a5 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 11 Oct 2022 10:30:02 +0900 Subject: [PATCH 28/75] applied longitude search --- .../src/likelihood_field_tracker.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index b963ebd67173e..c36665c974616 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -427,30 +427,30 @@ void SingleLFTracker::createGridVehiclePositionParticle() { // Strictly, we should use multivariate normal distribution // Relaxed Results - double x_wid, y_wid, yaw_wid; + double x_wid, y_wid, yaw_wid, longitude; double max_wid = 2; // 2m is max int ilen = 10; + int llen = 50; - x_wid = std::min(std::sqrt(covariance_(0,0)), max_wid); + x_wid = std::max(std::min(std::sqrt(covariance_(0,0)), max_wid); y_wid = std::min(std::sqrt(covariance_(1,1)), max_wid); yaw_wid = DEG2RAD(15.0); + longitude = 2*std::sqrt(x_wid*x_wid+y_wid*y_wid); // generate vp VehicleParticle vp(position_ , width_, length_, orientation_); std::uint8_t index = vp.getNearestCornerIndex(); - for(int i=0;i Date: Tue, 11 Oct 2022 10:59:29 +0900 Subject: [PATCH 29/75] Fix grid range --- .../src/likelihood_field_tracker.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index c36665c974616..30417b426edff 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -427,16 +427,17 @@ void SingleLFTracker::createGridVehiclePositionParticle() { // Strictly, we should use multivariate normal distribution // Relaxed Results - double x_wid, y_wid, yaw_wid, longitude; - double max_wid = 2; // 2m is max + // double x_wid, y_wid + double yaw_wid, longitude; + //double max_wid = 2; // 2m is max int ilen = 10; int llen = 50; - x_wid = std::max(std::min(std::sqrt(covariance_(0,0)), max_wid); - y_wid = std::min(std::sqrt(covariance_(1,1)), max_wid); + // x_wid = std::min(std::sqrt(covariance_(0,0)), max_wid); + // y_wid = std::min(std::sqrt(covariance_(1,1)), max_wid); yaw_wid = DEG2RAD(15.0); - longitude = 2*std::sqrt(x_wid*x_wid+y_wid*y_wid); + longitude = 3; //1.5m x2 // generate vp VehicleParticle vp(position_ , width_, length_, orientation_); std::uint8_t index = vp.getNearestCornerIndex(); From 0e01823b3c741aa5b1afcd67fa6cb1e1749fe243 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 11 Oct 2022 11:27:20 +0900 Subject: [PATCH 30/75] add default vehicle particle --- .../likelihood_field_tracker.hpp | 4 ++++ .../src/likelihood_field_tracker.cpp | 19 +++++++++++++------ 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index c917dc9f9d8a6..2634f1e92bb88 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -160,11 +160,13 @@ class SingleLFTracker { private: std::vector vehicle_particle_; + VehicleParticle default_vehicle_; std::uint32_t particle_num_; Eigen::Vector2d position_; double orientation_; double width_; double length_; + double default_likelihood_; Eigen::Matrix3d covariance_; public: @@ -172,6 +174,8 @@ class SingleLFTracker void createRandomVehiclePositionParticle(const std::uint32_t particle_num); void createGridVehiclePositionParticle(); //void createVehicleShapeParticle(); + std::tuple calcMeanAndCovFromParticles(std::vector & likelihoods, std::vector vectors); + std::tuple calcBestParticles(std::vector & likelihoods, std::vector vectors); void estimateState(const std::vector & scan); autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject(autoware_auto_perception_msgs::msg::TrackedObject &object); }; diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index 30417b426edff..a2aa97278cf30 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -375,6 +375,7 @@ double VehicleParticle::calcFineLikelihood(const std::vector & SingleLFTracker::SingleLFTracker(const autoware_auto_perception_msgs::msg::TrackedObject & object) +:default_vehicle_(Eigen::Vector2d(object.kinematics.pose_with_covariance.pose.position.x, object.kinematics.pose_with_covariance.pose.position.y), object.shape.dimensions.y, object.shape.dimensions.x, tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)) { // set private variable position_ = Eigen::Vector2d(object.kinematics.pose_with_covariance.pose.position.x, object.kinematics.pose_with_covariance.pose.position.y); @@ -439,8 +440,8 @@ void SingleLFTracker::createGridVehiclePositionParticle() longitude = 3; //1.5m x2 // generate vp - VehicleParticle vp(position_ , width_, length_, orientation_); - std::uint8_t index = vp.getNearestCornerIndex(); + //VehicleParticle vp(position_ , width_, length_, orientation_); + std::uint8_t index = default_vehicle_.getNearestCornerIndex(); for(int i=0;i calcMeanAndCovFromParticles(std::vector & likelihoods, std::vector vectors) +std::tuple SingleLFTracker::calcMeanAndCovFromParticles(std::vector & likelihoods, std::vector vectors) { auto loop = likelihoods.size(); @@ -492,7 +493,7 @@ std::tuple calcMeanAndCovFromParticles(std::ve } -std::tuple calcBestParticles(std::vector & likelihoods, std::vector vectors) +std::tuple SingleLFTracker::calcBestParticles(std::vector & likelihoods, std::vector vectors) { Eigen::Vector3d mean; @@ -504,7 +505,13 @@ std::tuple calcBestParticles(std::vector & scan) Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); states.push_back(state); } - + default_likelihood_ = default_vehicle_.calcFineLikelihood(scan); // auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); auto mean_cov_ = calcBestParticles(likelihoods, states); From d479c8dc37c1e95079cddfd039b0efc4b2b74d31 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 11 Oct 2022 19:59:32 +0900 Subject: [PATCH 31/75] Debug Release build problem --- .../likelihood_field_tracker.hpp | 22 +++++---- .../src/likelihood_field_tracker.cpp | 45 ++++++++++++------- 2 files changed, 42 insertions(+), 25 deletions(-) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp index 2634f1e92bb88..2e800df533195 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/likelihood_field_tracker.hpp @@ -64,7 +64,8 @@ */ class RectangleZone { -private: +//private: +public: double xmin_, xmax_, ymin_, ymax_; public: @@ -108,15 +109,17 @@ class CoarseCarLikelihoodField class FineCarLikelihoodField { private: - /// cost value represent {penalty, contour, inside, outside} - std::vector costs_ = {0.02,-0.04, -0.01, 0}; + double measurement_covariance_ = 0.1; + + public: RectangleZone car_contour_; /// Rectangle Area + /// cost value represent {penalty, contour, inside, outside} + std::vector costs_ = {0.02,-0.04, -0.01, 0}; + const int indexes_[4][2] = {{3,0},{0,1},{1,2},{2,3}}; std::array penalty_zones_; std::array contour_zones_; - const std::array, 4> indexes_ = {{{3,0},{0,1},{1,2},{2,3}}}; - public: explicit FineCarLikelihoodField(const double width, const double length, const double outside_margin, const double inside_margin); void setContourZones(const double width, const double length, const double outside_margin, const double inside_margin); @@ -137,20 +140,21 @@ class VehicleParticle const double inside_margin_ = 0.25; const double outside_margin_ = 1.0; double measurement_noise_ = 0.1; - FineCarLikelihoodField fine_likelihood_; // maybe it's ok to use std::optional instead - CoarseCarLikelihoodField coarse_likelihood_; - std::array corner_points_; public: + FineCarLikelihoodField fine_likelihood_; // maybe it's ok to use std::optional instead + CoarseCarLikelihoodField coarse_likelihood_; + std::array corner_points_; + Eigen::Vector2d center_; double orientation_; std::uint8_t corner_index_; explicit VehicleParticle(const Eigen::Vector2d center, const double width, const double length, const double orientation); void setCornerPoints(const Eigen::Vector2d center, const double width, const double length, const double orientation); std::uint8_t getNearestCornerIndex(const Eigen::Vector2d & origin = Eigen::Vector2d(0.0,0.0)); /// ego origin is set 0,0 by default - std::vector toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation); + void toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation, std::vector& local_measurements); double calcCoarseLikelihood(const std::vector & measurements); double calcFineLikelihood(const std::vector & measurements); }; diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index a2aa97278cf30..f0ad27b22647c 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -282,8 +282,8 @@ double FineCarLikelihoodField::calcLikelihoods(const std::vector VehicleParticle::toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation) +void VehicleParticle::toLocalCoordinate(const std::vector & measurements, const Eigen::Vector2d & center, double orientation, std::vector & localized) { auto point_num = measurements.size(); - std::vector localized(point_num); + //std::vector localized(point_num); - Eigen::Rotation2Dd rotate(orientation); /// rotation - auto Rt = rotate.toRotationMatrix().transpose(); /// Rotation matrix R^T + Eigen::Rotation2Dd rotate(-orientation); /// rotation + auto Rt = rotate.toRotationMatrix(); /// Rotation matrix R^T for(std::size_t i=0;i VehicleParticle::toLocalCoordinate(const std::vecto double VehicleParticle::calcCoarseLikelihood(const std::vector & measurements) { //auto corner_index = getNearestCornerIndex(); - auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); + std::vector local_measurements; + toLocalCoordinate(measurements, center_, orientation_, local_measurements); auto likelihood = coarse_likelihood_.calcLikelihoods(local_measurements, corner_index_); return likelihood; } @@ -367,7 +368,8 @@ double VehicleParticle::calcCoarseLikelihood(const std::vector double VehicleParticle::calcFineLikelihood(const std::vector & measurements) { //auto corner_index = getNearestCornerIndex(); - auto local_measurements = toLocalCoordinate(measurements, center_, orientation_); + std::vector local_measurements; + toLocalCoordinate(measurements, center_, orientation_, local_measurements); auto likelihood = fine_likelihood_.calcLikelihoods(local_measurements, corner_index_); return likelihood; @@ -496,19 +498,23 @@ std::tuple SingleLFTracker::calcMeanAndCovFrom std::tuple SingleLFTracker::calcBestParticles(std::vector & likelihoods, std::vector vectors) { - Eigen::Vector3d mean; - Eigen::Matrix3d cov; + Eigen::Vector3d mean = Eigen::Vector3d::Zero(); + Eigen::Matrix3d cov= Eigen::Matrix3d::Zero(); double w2 = 0; double sum_likelihoods = 0; std::vector max_indexes = findMaxIndices(likelihoods); + //ROS_DEBUG("log:%i", count); + std::cout << "Max num " < SingleLFTracker::calcBestParticles( for(std::size_t i: max_indexes){ - mean += vectors[i] * likelihoods[i] / sum_likelihoods; + mean += vectors[i] ; w2 += likelihoods[i]*likelihoods[i] / sum_likelihoods / sum_likelihoods; } + mean = mean/(double) max_indexes.size(); for(std::size_t i: max_indexes){ cov += (mean-vectors[i]) * (mean-vectors[i]).transpose() * likelihoods[i] / sum_likelihoods /(1-w2); @@ -570,8 +577,13 @@ void SingleLFTracker::estimateState(const std::vector & scan) Eigen::Vector3d state(vehicle_particle_[i].center_.x(), vehicle_particle_[i].center_.y(), vehicle_particle_[i].orientation_); states.push_back(state); } + + default_vehicle_.corner_index_ = default_vehicle_.getNearestCornerIndex(); default_likelihood_ = default_vehicle_.calcFineLikelihood(scan); + std::vector local_scan; + default_vehicle_.toLocalCoordinate(scan, default_vehicle_.center_, default_vehicle_.orientation_, local_scan); + std::cout << local_scan[0].x() << ", " << local_scan[0].y() << std::endl; // auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); auto mean_cov_ = calcBestParticles(likelihoods, states); @@ -674,6 +686,7 @@ void LikelihoodFieldTracker::onObjects( Eigen::Vector2d xy{range*cos(th), range*sin(th)}; scan_vec.push_back(xy); } + std::cout << scan_vec[0].x() << ", " < Date: Mon, 17 Oct 2022 13:44:28 +0900 Subject: [PATCH 32/75] change contour range --- .../src/likelihood_field_tracker.cpp | 38 ++++++++++++------- 1 file changed, 24 insertions(+), 14 deletions(-) diff --git a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp index f0ad27b22647c..8a626502dd3bd 100644 --- a/perception/detection_by_tracker/src/likelihood_field_tracker.cpp +++ b/perception/detection_by_tracker/src/likelihood_field_tracker.cpp @@ -232,21 +232,23 @@ FineCarLikelihoodField::FineCarLikelihoodField( void FineCarLikelihoodField::setContourZones(const double width, const double length, const double outside_margin, const double inside_margin) { auto W2 = width/2.0; auto L2 = length/2.0; - contour_zones_[0].setZone(-L2, L2, -W2, -W2+inside_margin); - contour_zones_[1].setZone(-L2, -L2+inside_margin, -W2, W2); - contour_zones_[2].setZone(-L2, L2, W2-inside_margin, W2); - contour_zones_[3].setZone(L2-inside_margin, L2, -W2, W2); + auto contour_margin = inside_margin/2.0; + contour_zones_[0].setZone(-L2, L2, -W2-contour_margin, -W2+contour_margin); + contour_zones_[1].setZone(-L2-contour_margin, -L2+contour_margin, -W2, W2); + contour_zones_[2].setZone(-L2, L2, W2-contour_margin, W2+contour_margin); + contour_zones_[3].setZone(L2-contour_margin, L2+contour_margin, -W2, W2); (void)outside_margin; // currently unused } void FineCarLikelihoodField::setPenaltyZones(const double width, const double length, const double outside_margin, const double inside_margin) { auto W2 = width/2.0; auto L2 = length/2.0; - penalty_zones_[0].setZone(-L2, L2, -W2-outside_margin, -W2); - penalty_zones_[1].setZone(-L2-outside_margin, -L2, -W2, W2); - penalty_zones_[2].setZone(-L2, L2, W2, W2+outside_margin); - penalty_zones_[3].setZone(L2, L2+outside_margin, -W2, W2); - (void)inside_margin; // currently unused + auto contour_margin = inside_margin/2.0; + penalty_zones_[0].setZone(-L2, L2, -W2-outside_margin, -W2-contour_margin); + penalty_zones_[1].setZone(-L2-outside_margin, -L2-contour_margin, -W2, W2); + penalty_zones_[2].setZone(-L2, L2, W2+contour_margin, W2+outside_margin); + penalty_zones_[3].setZone(L2+contour_margin , L2+outside_margin, -W2, W2); + //(void)inside_margin; // currently unused } void FineCarLikelihoodField::setMeasurementCovariance(const double cov) @@ -506,9 +508,9 @@ std::tuple SingleLFTracker::calcBestParticles( std::vector max_indexes = findMaxIndices(likelihoods); //ROS_DEBUG("log:%i", count); - std::cout << "Max num " < SingleLFTracker::calcBestParticles( cov(0,0) = 0.4; cov(1,1) = 0.4; + // check warping objects + if(( default_vehicle_.center_ - mean.head<2>()).norm()>1.0 || std::abs(orientation_ - mean.z() > DEG2RAD(15))){ + std::cout << "max indexes: " << max_indexes.size() << std::endl; + std::cout << default_likelihood_ << " " << likelihoods[max_indexes[0]] << std::endl; + std::cout << "vp position " << default_vehicle_.center_.x() << ", "<< default_vehicle_.center_.y() << ", " << default_vehicle_.orientation_ < & scan) std::vector local_scan; default_vehicle_.toLocalCoordinate(scan, default_vehicle_.center_, default_vehicle_.orientation_, local_scan); - std::cout << local_scan[0].x() << ", " << local_scan[0].y() << std::endl; +// std::cout << local_scan[0].x() << ", " << local_scan[0].y() << std::endl; // auto mean_cov_ = calcMeanAndCovFromParticles(likelihoods, states); auto mean_cov_ = calcBestParticles(likelihoods, states); @@ -686,7 +696,7 @@ void LikelihoodFieldTracker::onObjects( Eigen::Vector2d xy{range*cos(th), range*sin(th)}; scan_vec.push_back(xy); } - std::cout << scan_vec[0].x() << ", " < Date: Mon, 17 Oct 2022 14:19:58 +0900 Subject: [PATCH 33/75] add debug output of likelihoods --- .../detection_by_tracker/nlohmann_json.hpp | 24640 ++++++++++++++++ .../src/likelihood_field_tracker.cpp | 10 +- 2 files changed, 24649 insertions(+), 1 deletion(-) create mode 100644 perception/detection_by_tracker/include/detection_by_tracker/nlohmann_json.hpp diff --git a/perception/detection_by_tracker/include/detection_by_tracker/nlohmann_json.hpp b/perception/detection_by_tracker/include/detection_by_tracker/nlohmann_json.hpp new file mode 100644 index 0000000000000..805efdd760b70 --- /dev/null +++ b/perception/detection_by_tracker/include/detection_by_tracker/nlohmann_json.hpp @@ -0,0 +1,24640 @@ +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + +/****************************************************************************\ + * Note on documentation: The source files contain links to the online * + * documentation of the public API at https://json.nlohmann.me. This URL * + * contains the most recent documentation and should also be applicable to * + * previous versions; documentation for deprecated functions is not * + * removed, but marked deprecated. See "Generate documentation" section in * + * file docs/README.md. * +\****************************************************************************/ + +#ifndef INCLUDE_NLOHMANN_JSON_HPP_ +#define INCLUDE_NLOHMANN_JSON_HPP_ + +#include // all_of, find, for_each +#include // nullptr_t, ptrdiff_t, size_t +#include // hash, less +#include // initializer_list +#ifndef JSON_NO_IO + #include // istream, ostream +#endif // JSON_NO_IO +#include // random_access_iterator_tag +#include // unique_ptr +#include // string, stoi, to_string +#include // declval, forward, move, pair, swap +#include // vector + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// This file contains all macro definitions affecting or depending on the ABI + +#ifndef JSON_SKIP_LIBRARY_VERSION_CHECK + #if defined(NLOHMANN_JSON_VERSION_MAJOR) && defined(NLOHMANN_JSON_VERSION_MINOR) && defined(NLOHMANN_JSON_VERSION_PATCH) + #if NLOHMANN_JSON_VERSION_MAJOR != 3 || NLOHMANN_JSON_VERSION_MINOR != 11 || NLOHMANN_JSON_VERSION_PATCH != 2 + #warning "Already included a different version of the library!" + #endif + #endif +#endif + +#define NLOHMANN_JSON_VERSION_MAJOR 3 // NOLINT(modernize-macro-to-enum) +#define NLOHMANN_JSON_VERSION_MINOR 11 // NOLINT(modernize-macro-to-enum) +#define NLOHMANN_JSON_VERSION_PATCH 2 // NOLINT(modernize-macro-to-enum) + +#ifndef JSON_DIAGNOSTICS + #define JSON_DIAGNOSTICS 0 +#endif + +#ifndef JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON + #define JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON 0 +#endif + +#if JSON_DIAGNOSTICS + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS _diag +#else + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS +#endif + +#if JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON + #define NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON _ldvcmp +#else + #define NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_NO_VERSION + #define NLOHMANN_JSON_NAMESPACE_NO_VERSION 0 +#endif + +// Construct the namespace ABI tags component +#define NLOHMANN_JSON_ABI_TAGS_CONCAT_EX(a, b) json_abi ## a ## b +#define NLOHMANN_JSON_ABI_TAGS_CONCAT(a, b) \ + NLOHMANN_JSON_ABI_TAGS_CONCAT_EX(a, b) + +#define NLOHMANN_JSON_ABI_TAGS \ + NLOHMANN_JSON_ABI_TAGS_CONCAT( \ + NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS, \ + NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON) + +// Construct the namespace version component +#define NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT_EX(major, minor, patch) \ + _v ## major ## _ ## minor ## _ ## patch +#define NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT(major, minor, patch) \ + NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT_EX(major, minor, patch) + +#if NLOHMANN_JSON_NAMESPACE_NO_VERSION +#define NLOHMANN_JSON_NAMESPACE_VERSION +#else +#define NLOHMANN_JSON_NAMESPACE_VERSION \ + NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT(NLOHMANN_JSON_VERSION_MAJOR, \ + NLOHMANN_JSON_VERSION_MINOR, \ + NLOHMANN_JSON_VERSION_PATCH) +#endif + +// Combine namespace components +#define NLOHMANN_JSON_NAMESPACE_CONCAT_EX(a, b) a ## b +#define NLOHMANN_JSON_NAMESPACE_CONCAT(a, b) \ + NLOHMANN_JSON_NAMESPACE_CONCAT_EX(a, b) + +#ifndef NLOHMANN_JSON_NAMESPACE +#define NLOHMANN_JSON_NAMESPACE \ + nlohmann::NLOHMANN_JSON_NAMESPACE_CONCAT( \ + NLOHMANN_JSON_ABI_TAGS, \ + NLOHMANN_JSON_NAMESPACE_VERSION) +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_BEGIN +#define NLOHMANN_JSON_NAMESPACE_BEGIN \ + namespace nlohmann \ + { \ + inline namespace NLOHMANN_JSON_NAMESPACE_CONCAT( \ + NLOHMANN_JSON_ABI_TAGS, \ + NLOHMANN_JSON_NAMESPACE_VERSION) \ + { +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_END +#define NLOHMANN_JSON_NAMESPACE_END \ + } /* namespace (inline namespace) NOLINT(readability/namespace) */ \ + } // namespace nlohmann +#endif + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // transform +#include // array +#include // forward_list +#include // inserter, front_inserter, end +#include // map +#include // string +#include // tuple, make_tuple +#include // is_arithmetic, is_same, is_enum, underlying_type, is_convertible +#include // unordered_map +#include // pair, declval +#include // valarray + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // nullptr_t +#include // exception +#if JSON_DIAGNOSTICS + #include // accumulate +#endif +#include // runtime_error +#include // to_string +#include // vector + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // array +#include // size_t +#include // uint8_t +#include // string + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // declval, pair +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template struct make_void +{ + using type = void; +}; +template using void_t = typename make_void::type; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +// https://en.cppreference.com/w/cpp/experimental/is_detected +struct nonesuch +{ + nonesuch() = delete; + ~nonesuch() = delete; + nonesuch(nonesuch const&) = delete; + nonesuch(nonesuch const&&) = delete; + void operator=(nonesuch const&) = delete; + void operator=(nonesuch&&) = delete; +}; + +template class Op, + class... Args> +struct detector +{ + using value_t = std::false_type; + using type = Default; +}; + +template class Op, class... Args> +struct detector>, Op, Args...> +{ + using value_t = std::true_type; + using type = Op; +}; + +template class Op, class... Args> +using is_detected = typename detector::value_t; + +template class Op, class... Args> +struct is_detected_lazy : is_detected { }; + +template class Op, class... Args> +using detected_t = typename detector::type; + +template class Op, class... Args> +using detected_or = detector; + +template class Op, class... Args> +using detected_or_t = typename detected_or::type; + +template class Op, class... Args> +using is_detected_exact = std::is_same>; + +template class Op, class... Args> +using is_detected_convertible = + std::is_convertible, To>; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + + +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-FileCopyrightText: 2016-2021 Evan Nemerson +// SPDX-License-Identifier: MIT + +/* Hedley - https://nemequ.github.io/hedley + * Created by Evan Nemerson + */ + +#if !defined(JSON_HEDLEY_VERSION) || (JSON_HEDLEY_VERSION < 15) +#if defined(JSON_HEDLEY_VERSION) + #undef JSON_HEDLEY_VERSION +#endif +#define JSON_HEDLEY_VERSION 15 + +#if defined(JSON_HEDLEY_STRINGIFY_EX) + #undef JSON_HEDLEY_STRINGIFY_EX +#endif +#define JSON_HEDLEY_STRINGIFY_EX(x) #x + +#if defined(JSON_HEDLEY_STRINGIFY) + #undef JSON_HEDLEY_STRINGIFY +#endif +#define JSON_HEDLEY_STRINGIFY(x) JSON_HEDLEY_STRINGIFY_EX(x) + +#if defined(JSON_HEDLEY_CONCAT_EX) + #undef JSON_HEDLEY_CONCAT_EX +#endif +#define JSON_HEDLEY_CONCAT_EX(a,b) a##b + +#if defined(JSON_HEDLEY_CONCAT) + #undef JSON_HEDLEY_CONCAT +#endif +#define JSON_HEDLEY_CONCAT(a,b) JSON_HEDLEY_CONCAT_EX(a,b) + +#if defined(JSON_HEDLEY_CONCAT3_EX) + #undef JSON_HEDLEY_CONCAT3_EX +#endif +#define JSON_HEDLEY_CONCAT3_EX(a,b,c) a##b##c + +#if defined(JSON_HEDLEY_CONCAT3) + #undef JSON_HEDLEY_CONCAT3 +#endif +#define JSON_HEDLEY_CONCAT3(a,b,c) JSON_HEDLEY_CONCAT3_EX(a,b,c) + +#if defined(JSON_HEDLEY_VERSION_ENCODE) + #undef JSON_HEDLEY_VERSION_ENCODE +#endif +#define JSON_HEDLEY_VERSION_ENCODE(major,minor,revision) (((major) * 1000000) + ((minor) * 1000) + (revision)) + +#if defined(JSON_HEDLEY_VERSION_DECODE_MAJOR) + #undef JSON_HEDLEY_VERSION_DECODE_MAJOR +#endif +#define JSON_HEDLEY_VERSION_DECODE_MAJOR(version) ((version) / 1000000) + +#if defined(JSON_HEDLEY_VERSION_DECODE_MINOR) + #undef JSON_HEDLEY_VERSION_DECODE_MINOR +#endif +#define JSON_HEDLEY_VERSION_DECODE_MINOR(version) (((version) % 1000000) / 1000) + +#if defined(JSON_HEDLEY_VERSION_DECODE_REVISION) + #undef JSON_HEDLEY_VERSION_DECODE_REVISION +#endif +#define JSON_HEDLEY_VERSION_DECODE_REVISION(version) ((version) % 1000) + +#if defined(JSON_HEDLEY_GNUC_VERSION) + #undef JSON_HEDLEY_GNUC_VERSION +#endif +#if defined(__GNUC__) && defined(__GNUC_PATCHLEVEL__) + #define JSON_HEDLEY_GNUC_VERSION JSON_HEDLEY_VERSION_ENCODE(__GNUC__, __GNUC_MINOR__, __GNUC_PATCHLEVEL__) +#elif defined(__GNUC__) + #define JSON_HEDLEY_GNUC_VERSION JSON_HEDLEY_VERSION_ENCODE(__GNUC__, __GNUC_MINOR__, 0) +#endif + +#if defined(JSON_HEDLEY_GNUC_VERSION_CHECK) + #undef JSON_HEDLEY_GNUC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_GNUC_VERSION) + #define JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_GNUC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_MSVC_VERSION) + #undef JSON_HEDLEY_MSVC_VERSION +#endif +#if defined(_MSC_FULL_VER) && (_MSC_FULL_VER >= 140000000) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_FULL_VER / 10000000, (_MSC_FULL_VER % 10000000) / 100000, (_MSC_FULL_VER % 100000) / 100) +#elif defined(_MSC_FULL_VER) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_FULL_VER / 1000000, (_MSC_FULL_VER % 1000000) / 10000, (_MSC_FULL_VER % 10000) / 10) +#elif defined(_MSC_VER) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_VER / 100, _MSC_VER % 100, 0) +#endif + +#if defined(JSON_HEDLEY_MSVC_VERSION_CHECK) + #undef JSON_HEDLEY_MSVC_VERSION_CHECK +#endif +#if !defined(JSON_HEDLEY_MSVC_VERSION) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (0) +#elif defined(_MSC_VER) && (_MSC_VER >= 1400) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_FULL_VER >= ((major * 10000000) + (minor * 100000) + (patch))) +#elif defined(_MSC_VER) && (_MSC_VER >= 1200) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_FULL_VER >= ((major * 1000000) + (minor * 10000) + (patch))) +#else + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_VER >= ((major * 100) + (minor))) +#endif + +#if defined(JSON_HEDLEY_INTEL_VERSION) + #undef JSON_HEDLEY_INTEL_VERSION +#endif +#if defined(__INTEL_COMPILER) && defined(__INTEL_COMPILER_UPDATE) && !defined(__ICL) + #define JSON_HEDLEY_INTEL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER / 100, __INTEL_COMPILER % 100, __INTEL_COMPILER_UPDATE) +#elif defined(__INTEL_COMPILER) && !defined(__ICL) + #define JSON_HEDLEY_INTEL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER / 100, __INTEL_COMPILER % 100, 0) +#endif + +#if defined(JSON_HEDLEY_INTEL_VERSION_CHECK) + #undef JSON_HEDLEY_INTEL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_INTEL_VERSION) + #define JSON_HEDLEY_INTEL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_INTEL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_INTEL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_INTEL_CL_VERSION) + #undef JSON_HEDLEY_INTEL_CL_VERSION +#endif +#if defined(__INTEL_COMPILER) && defined(__INTEL_COMPILER_UPDATE) && defined(__ICL) + #define JSON_HEDLEY_INTEL_CL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER, __INTEL_COMPILER_UPDATE, 0) +#endif + +#if defined(JSON_HEDLEY_INTEL_CL_VERSION_CHECK) + #undef JSON_HEDLEY_INTEL_CL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_INTEL_CL_VERSION) + #define JSON_HEDLEY_INTEL_CL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_INTEL_CL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_INTEL_CL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_PGI_VERSION) + #undef JSON_HEDLEY_PGI_VERSION +#endif +#if defined(__PGI) && defined(__PGIC__) && defined(__PGIC_MINOR__) && defined(__PGIC_PATCHLEVEL__) + #define JSON_HEDLEY_PGI_VERSION JSON_HEDLEY_VERSION_ENCODE(__PGIC__, __PGIC_MINOR__, __PGIC_PATCHLEVEL__) +#endif + +#if defined(JSON_HEDLEY_PGI_VERSION_CHECK) + #undef JSON_HEDLEY_PGI_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_PGI_VERSION) + #define JSON_HEDLEY_PGI_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_PGI_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_PGI_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_SUNPRO_VERSION) + #undef JSON_HEDLEY_SUNPRO_VERSION +#endif +#if defined(__SUNPRO_C) && (__SUNPRO_C > 0x1000) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((((__SUNPRO_C >> 16) & 0xf) * 10) + ((__SUNPRO_C >> 12) & 0xf), (((__SUNPRO_C >> 8) & 0xf) * 10) + ((__SUNPRO_C >> 4) & 0xf), (__SUNPRO_C & 0xf) * 10) +#elif defined(__SUNPRO_C) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((__SUNPRO_C >> 8) & 0xf, (__SUNPRO_C >> 4) & 0xf, (__SUNPRO_C) & 0xf) +#elif defined(__SUNPRO_CC) && (__SUNPRO_CC > 0x1000) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((((__SUNPRO_CC >> 16) & 0xf) * 10) + ((__SUNPRO_CC >> 12) & 0xf), (((__SUNPRO_CC >> 8) & 0xf) * 10) + ((__SUNPRO_CC >> 4) & 0xf), (__SUNPRO_CC & 0xf) * 10) +#elif defined(__SUNPRO_CC) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((__SUNPRO_CC >> 8) & 0xf, (__SUNPRO_CC >> 4) & 0xf, (__SUNPRO_CC) & 0xf) +#endif + +#if defined(JSON_HEDLEY_SUNPRO_VERSION_CHECK) + #undef JSON_HEDLEY_SUNPRO_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_SUNPRO_VERSION) + #define JSON_HEDLEY_SUNPRO_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_SUNPRO_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_SUNPRO_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION) + #undef JSON_HEDLEY_EMSCRIPTEN_VERSION +#endif +#if defined(__EMSCRIPTEN__) + #define JSON_HEDLEY_EMSCRIPTEN_VERSION JSON_HEDLEY_VERSION_ENCODE(__EMSCRIPTEN_major__, __EMSCRIPTEN_minor__, __EMSCRIPTEN_tiny__) +#endif + +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK) + #undef JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION) + #define JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_EMSCRIPTEN_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_ARM_VERSION) + #undef JSON_HEDLEY_ARM_VERSION +#endif +#if defined(__CC_ARM) && defined(__ARMCOMPILER_VERSION) + #define JSON_HEDLEY_ARM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ARMCOMPILER_VERSION / 1000000, (__ARMCOMPILER_VERSION % 1000000) / 10000, (__ARMCOMPILER_VERSION % 10000) / 100) +#elif defined(__CC_ARM) && defined(__ARMCC_VERSION) + #define JSON_HEDLEY_ARM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ARMCC_VERSION / 1000000, (__ARMCC_VERSION % 1000000) / 10000, (__ARMCC_VERSION % 10000) / 100) +#endif + +#if defined(JSON_HEDLEY_ARM_VERSION_CHECK) + #undef JSON_HEDLEY_ARM_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_ARM_VERSION) + #define JSON_HEDLEY_ARM_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_ARM_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_ARM_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_IBM_VERSION) + #undef JSON_HEDLEY_IBM_VERSION +#endif +#if defined(__ibmxl__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ibmxl_version__, __ibmxl_release__, __ibmxl_modification__) +#elif defined(__xlC__) && defined(__xlC_ver__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__xlC__ >> 8, __xlC__ & 0xff, (__xlC_ver__ >> 8) & 0xff) +#elif defined(__xlC__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__xlC__ >> 8, __xlC__ & 0xff, 0) +#endif + +#if defined(JSON_HEDLEY_IBM_VERSION_CHECK) + #undef JSON_HEDLEY_IBM_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_IBM_VERSION) + #define JSON_HEDLEY_IBM_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_IBM_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_IBM_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_VERSION) + #undef JSON_HEDLEY_TI_VERSION +#endif +#if \ + defined(__TI_COMPILER_VERSION__) && \ + ( \ + defined(__TMS470__) || defined(__TI_ARM__) || \ + defined(__MSP430__) || \ + defined(__TMS320C2000__) \ + ) +#if (__TI_COMPILER_VERSION__ >= 16000000) + #define JSON_HEDLEY_TI_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif +#endif + +#if defined(JSON_HEDLEY_TI_VERSION_CHECK) + #undef JSON_HEDLEY_TI_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_VERSION) + #define JSON_HEDLEY_TI_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL2000_VERSION) + #undef JSON_HEDLEY_TI_CL2000_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__TMS320C2000__) + #define JSON_HEDLEY_TI_CL2000_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL2000_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL2000_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL2000_VERSION) + #define JSON_HEDLEY_TI_CL2000_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL2000_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL2000_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL430_VERSION) + #undef JSON_HEDLEY_TI_CL430_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__MSP430__) + #define JSON_HEDLEY_TI_CL430_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL430_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL430_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL430_VERSION) + #define JSON_HEDLEY_TI_CL430_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL430_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL430_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION) + #undef JSON_HEDLEY_TI_ARMCL_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && (defined(__TMS470__) || defined(__TI_ARM__)) + #define JSON_HEDLEY_TI_ARMCL_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION_CHECK) + #undef JSON_HEDLEY_TI_ARMCL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION) + #define JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_ARMCL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL6X_VERSION) + #undef JSON_HEDLEY_TI_CL6X_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__TMS320C6X__) + #define JSON_HEDLEY_TI_CL6X_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL6X_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL6X_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL6X_VERSION) + #define JSON_HEDLEY_TI_CL6X_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL6X_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL6X_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL7X_VERSION) + #undef JSON_HEDLEY_TI_CL7X_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__C7000__) + #define JSON_HEDLEY_TI_CL7X_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL7X_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL7X_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL7X_VERSION) + #define JSON_HEDLEY_TI_CL7X_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL7X_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL7X_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION) + #undef JSON_HEDLEY_TI_CLPRU_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__PRU__) + #define JSON_HEDLEY_TI_CLPRU_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CLPRU_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION) + #define JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CLPRU_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_CRAY_VERSION) + #undef JSON_HEDLEY_CRAY_VERSION +#endif +#if defined(_CRAYC) + #if defined(_RELEASE_PATCHLEVEL) + #define JSON_HEDLEY_CRAY_VERSION JSON_HEDLEY_VERSION_ENCODE(_RELEASE_MAJOR, _RELEASE_MINOR, _RELEASE_PATCHLEVEL) + #else + #define JSON_HEDLEY_CRAY_VERSION JSON_HEDLEY_VERSION_ENCODE(_RELEASE_MAJOR, _RELEASE_MINOR, 0) + #endif +#endif + +#if defined(JSON_HEDLEY_CRAY_VERSION_CHECK) + #undef JSON_HEDLEY_CRAY_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_CRAY_VERSION) + #define JSON_HEDLEY_CRAY_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_CRAY_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_CRAY_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_IAR_VERSION) + #undef JSON_HEDLEY_IAR_VERSION +#endif +#if defined(__IAR_SYSTEMS_ICC__) + #if __VER__ > 1000 + #define JSON_HEDLEY_IAR_VERSION JSON_HEDLEY_VERSION_ENCODE((__VER__ / 1000000), ((__VER__ / 1000) % 1000), (__VER__ % 1000)) + #else + #define JSON_HEDLEY_IAR_VERSION JSON_HEDLEY_VERSION_ENCODE(__VER__ / 100, __VER__ % 100, 0) + #endif +#endif + +#if defined(JSON_HEDLEY_IAR_VERSION_CHECK) + #undef JSON_HEDLEY_IAR_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_IAR_VERSION) + #define JSON_HEDLEY_IAR_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_IAR_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_IAR_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TINYC_VERSION) + #undef JSON_HEDLEY_TINYC_VERSION +#endif +#if defined(__TINYC__) + #define JSON_HEDLEY_TINYC_VERSION JSON_HEDLEY_VERSION_ENCODE(__TINYC__ / 1000, (__TINYC__ / 100) % 10, __TINYC__ % 100) +#endif + +#if defined(JSON_HEDLEY_TINYC_VERSION_CHECK) + #undef JSON_HEDLEY_TINYC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TINYC_VERSION) + #define JSON_HEDLEY_TINYC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TINYC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TINYC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_DMC_VERSION) + #undef JSON_HEDLEY_DMC_VERSION +#endif +#if defined(__DMC__) + #define JSON_HEDLEY_DMC_VERSION JSON_HEDLEY_VERSION_ENCODE(__DMC__ >> 8, (__DMC__ >> 4) & 0xf, __DMC__ & 0xf) +#endif + +#if defined(JSON_HEDLEY_DMC_VERSION_CHECK) + #undef JSON_HEDLEY_DMC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_DMC_VERSION) + #define JSON_HEDLEY_DMC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_DMC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_DMC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_COMPCERT_VERSION) + #undef JSON_HEDLEY_COMPCERT_VERSION +#endif +#if defined(__COMPCERT_VERSION__) + #define JSON_HEDLEY_COMPCERT_VERSION JSON_HEDLEY_VERSION_ENCODE(__COMPCERT_VERSION__ / 10000, (__COMPCERT_VERSION__ / 100) % 100, __COMPCERT_VERSION__ % 100) +#endif + +#if defined(JSON_HEDLEY_COMPCERT_VERSION_CHECK) + #undef JSON_HEDLEY_COMPCERT_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_COMPCERT_VERSION) + #define JSON_HEDLEY_COMPCERT_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_COMPCERT_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_COMPCERT_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_PELLES_VERSION) + #undef JSON_HEDLEY_PELLES_VERSION +#endif +#if defined(__POCC__) + #define JSON_HEDLEY_PELLES_VERSION JSON_HEDLEY_VERSION_ENCODE(__POCC__ / 100, __POCC__ % 100, 0) +#endif + +#if defined(JSON_HEDLEY_PELLES_VERSION_CHECK) + #undef JSON_HEDLEY_PELLES_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_PELLES_VERSION) + #define JSON_HEDLEY_PELLES_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_PELLES_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_PELLES_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_MCST_LCC_VERSION) + #undef JSON_HEDLEY_MCST_LCC_VERSION +#endif +#if defined(__LCC__) && defined(__LCC_MINOR__) + #define JSON_HEDLEY_MCST_LCC_VERSION JSON_HEDLEY_VERSION_ENCODE(__LCC__ / 100, __LCC__ % 100, __LCC_MINOR__) +#endif + +#if defined(JSON_HEDLEY_MCST_LCC_VERSION_CHECK) + #undef JSON_HEDLEY_MCST_LCC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_MCST_LCC_VERSION) + #define JSON_HEDLEY_MCST_LCC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_MCST_LCC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_MCST_LCC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_GCC_VERSION) + #undef JSON_HEDLEY_GCC_VERSION +#endif +#if \ + defined(JSON_HEDLEY_GNUC_VERSION) && \ + !defined(__clang__) && \ + !defined(JSON_HEDLEY_INTEL_VERSION) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_ARM_VERSION) && \ + !defined(JSON_HEDLEY_CRAY_VERSION) && \ + !defined(JSON_HEDLEY_TI_VERSION) && \ + !defined(JSON_HEDLEY_TI_ARMCL_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL430_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL2000_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL6X_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL7X_VERSION) && \ + !defined(JSON_HEDLEY_TI_CLPRU_VERSION) && \ + !defined(__COMPCERT__) && \ + !defined(JSON_HEDLEY_MCST_LCC_VERSION) + #define JSON_HEDLEY_GCC_VERSION JSON_HEDLEY_GNUC_VERSION +#endif + +#if defined(JSON_HEDLEY_GCC_VERSION_CHECK) + #undef JSON_HEDLEY_GCC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_GCC_VERSION) + #define JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_GCC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_ATTRIBUTE +#endif +#if \ + defined(__has_attribute) && \ + ( \ + (!defined(JSON_HEDLEY_IAR_VERSION) || JSON_HEDLEY_IAR_VERSION_CHECK(8,5,9)) \ + ) +# define JSON_HEDLEY_HAS_ATTRIBUTE(attribute) __has_attribute(attribute) +#else +# define JSON_HEDLEY_HAS_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_ATTRIBUTE +#endif +#if defined(__has_attribute) + #define JSON_HEDLEY_GNUC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_ATTRIBUTE +#endif +#if defined(__has_attribute) + #define JSON_HEDLEY_GCC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_CPP_ATTRIBUTE +#endif +#if \ + defined(__has_cpp_attribute) && \ + defined(__cplusplus) && \ + (!defined(JSON_HEDLEY_SUNPRO_VERSION) || JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0)) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS) + #undef JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS +#endif +#if !defined(__cplusplus) || !defined(__has_cpp_attribute) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) (0) +#elif \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_IAR_VERSION) && \ + (!defined(JSON_HEDLEY_SUNPRO_VERSION) || JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0)) && \ + (!defined(JSON_HEDLEY_MSVC_VERSION) || JSON_HEDLEY_MSVC_VERSION_CHECK(19,20,0)) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) JSON_HEDLEY_HAS_CPP_ATTRIBUTE(ns::attribute) +#else + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE +#endif +#if defined(__has_cpp_attribute) && defined(__cplusplus) + #define JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE +#endif +#if defined(__has_cpp_attribute) && defined(__cplusplus) + #define JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_BUILTIN) + #undef JSON_HEDLEY_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_HAS_BUILTIN(builtin) __has_builtin(builtin) +#else + #define JSON_HEDLEY_HAS_BUILTIN(builtin) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_BUILTIN) + #undef JSON_HEDLEY_GNUC_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_GNUC_HAS_BUILTIN(builtin,major,minor,patch) __has_builtin(builtin) +#else + #define JSON_HEDLEY_GNUC_HAS_BUILTIN(builtin,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_BUILTIN) + #undef JSON_HEDLEY_GCC_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_GCC_HAS_BUILTIN(builtin,major,minor,patch) __has_builtin(builtin) +#else + #define JSON_HEDLEY_GCC_HAS_BUILTIN(builtin,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_FEATURE) + #undef JSON_HEDLEY_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_HAS_FEATURE(feature) __has_feature(feature) +#else + #define JSON_HEDLEY_HAS_FEATURE(feature) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_FEATURE) + #undef JSON_HEDLEY_GNUC_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_GNUC_HAS_FEATURE(feature,major,minor,patch) __has_feature(feature) +#else + #define JSON_HEDLEY_GNUC_HAS_FEATURE(feature,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_FEATURE) + #undef JSON_HEDLEY_GCC_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_GCC_HAS_FEATURE(feature,major,minor,patch) __has_feature(feature) +#else + #define JSON_HEDLEY_GCC_HAS_FEATURE(feature,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_EXTENSION) + #undef JSON_HEDLEY_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_HAS_EXTENSION(extension) __has_extension(extension) +#else + #define JSON_HEDLEY_HAS_EXTENSION(extension) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_EXTENSION) + #undef JSON_HEDLEY_GNUC_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_GNUC_HAS_EXTENSION(extension,major,minor,patch) __has_extension(extension) +#else + #define JSON_HEDLEY_GNUC_HAS_EXTENSION(extension,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_EXTENSION) + #undef JSON_HEDLEY_GCC_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_GCC_HAS_EXTENSION(extension,major,minor,patch) __has_extension(extension) +#else + #define JSON_HEDLEY_GCC_HAS_EXTENSION(extension,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_WARNING) + #undef JSON_HEDLEY_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_HAS_WARNING(warning) __has_warning(warning) +#else + #define JSON_HEDLEY_HAS_WARNING(warning) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_WARNING) + #undef JSON_HEDLEY_GNUC_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_GNUC_HAS_WARNING(warning,major,minor,patch) __has_warning(warning) +#else + #define JSON_HEDLEY_GNUC_HAS_WARNING(warning,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_WARNING) + #undef JSON_HEDLEY_GCC_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_GCC_HAS_WARNING(warning,major,minor,patch) __has_warning(warning) +#else + #define JSON_HEDLEY_GCC_HAS_WARNING(warning,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L)) || \ + defined(__clang__) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,4,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,7,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(2,0,1) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(5,0,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,17) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(8,0,0) || \ + (JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) && defined(__C99_PRAGMA_OPERATOR)) + #define JSON_HEDLEY_PRAGMA(value) _Pragma(#value) +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_PRAGMA(value) __pragma(value) +#else + #define JSON_HEDLEY_PRAGMA(value) +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_PUSH) + #undef JSON_HEDLEY_DIAGNOSTIC_PUSH +#endif +#if defined(JSON_HEDLEY_DIAGNOSTIC_POP) + #undef JSON_HEDLEY_DIAGNOSTIC_POP +#endif +#if defined(__clang__) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("clang diagnostic push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("clang diagnostic pop") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("warning(push)") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("warning(pop)") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("GCC diagnostic push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("GCC diagnostic pop") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH __pragma(warning(push)) + #define JSON_HEDLEY_DIAGNOSTIC_POP __pragma(warning(pop)) +#elif JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("pop") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,4,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("diag_push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("diag_pop") +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,90,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("warning(push)") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("warning(pop)") +#else + #define JSON_HEDLEY_DIAGNOSTIC_PUSH + #define JSON_HEDLEY_DIAGNOSTIC_POP +#endif + +/* JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_ is for + HEDLEY INTERNAL USE ONLY. API subject to change without notice. */ +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_ +#endif +#if defined(__cplusplus) +# if JSON_HEDLEY_HAS_WARNING("-Wc++98-compat") +# if JSON_HEDLEY_HAS_WARNING("-Wc++17-extensions") +# if JSON_HEDLEY_HAS_WARNING("-Wc++1z-extensions") +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + _Pragma("clang diagnostic ignored \"-Wc++17-extensions\"") \ + _Pragma("clang diagnostic ignored \"-Wc++1z-extensions\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + _Pragma("clang diagnostic ignored \"-Wc++17-extensions\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# endif +# else +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# endif +# endif +#endif +#if !defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(x) x +#endif + +#if defined(JSON_HEDLEY_CONST_CAST) + #undef JSON_HEDLEY_CONST_CAST +#endif +#if defined(__cplusplus) +# define JSON_HEDLEY_CONST_CAST(T, expr) (const_cast(expr)) +#elif \ + JSON_HEDLEY_HAS_WARNING("-Wcast-qual") || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_CONST_CAST(T, expr) (__extension__ ({ \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL \ + ((T) (expr)); \ + JSON_HEDLEY_DIAGNOSTIC_POP \ + })) +#else +# define JSON_HEDLEY_CONST_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_REINTERPRET_CAST) + #undef JSON_HEDLEY_REINTERPRET_CAST +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_REINTERPRET_CAST(T, expr) (reinterpret_cast(expr)) +#else + #define JSON_HEDLEY_REINTERPRET_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_STATIC_CAST) + #undef JSON_HEDLEY_STATIC_CAST +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_STATIC_CAST(T, expr) (static_cast(expr)) +#else + #define JSON_HEDLEY_STATIC_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_CPP_CAST) + #undef JSON_HEDLEY_CPP_CAST +#endif +#if defined(__cplusplus) +# if JSON_HEDLEY_HAS_WARNING("-Wold-style-cast") +# define JSON_HEDLEY_CPP_CAST(T, expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wold-style-cast\"") \ + ((T) (expr)) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# elif JSON_HEDLEY_IAR_VERSION_CHECK(8,3,0) +# define JSON_HEDLEY_CPP_CAST(T, expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("diag_suppress=Pe137") \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_CPP_CAST(T, expr) ((T) (expr)) +# endif +#else +# define JSON_HEDLEY_CPP_CAST(T, expr) (expr) +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wdeprecated-declarations") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("clang diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("warning(disable:1478 1786)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED __pragma(warning(disable:1478 1786)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(20,7,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1216,1444,1445") +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1444") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED __pragma(warning(disable:4996)) +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1444") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1291,1718") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) && !defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("error_messages(off,E_DEPRECATED_ATT,E_DEPRECATED_ATT_MESS)") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) && defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("error_messages(off,symdeprecated,symdeprecated2)") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress=Pe1444,Pe1215") +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,90,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("warn(disable:2241)") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("clang diagnostic ignored \"-Wunknown-pragmas\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("warning(disable:161)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS __pragma(warning(disable:161)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 1675") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("GCC diagnostic ignored \"-Wunknown-pragmas\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS __pragma(warning(disable:4068)) +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(16,9,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 163") +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 163") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress=Pe161") +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 161") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-attributes") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("clang diagnostic ignored \"-Wunknown-attributes\"") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(17,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("warning(disable:1292)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES __pragma(warning(disable:1292)) +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(19,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES __pragma(warning(disable:5030)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(20,7,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097,1098") +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,14,0) && defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("error_messages(off,attrskipunsup)") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,3,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1173") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress=Pe1097") +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wcast-qual") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("clang diagnostic ignored \"-Wcast-qual\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("warning(disable:2203 2331)") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("GCC diagnostic ignored \"-Wcast-qual\"") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunused-function") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("clang diagnostic ignored \"-Wunused-function\"") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("GCC diagnostic ignored \"-Wunused-function\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(1,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION __pragma(warning(disable:4505)) +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("diag_suppress 3142") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION +#endif + +#if defined(JSON_HEDLEY_DEPRECATED) + #undef JSON_HEDLEY_DEPRECATED +#endif +#if defined(JSON_HEDLEY_DEPRECATED_FOR) + #undef JSON_HEDLEY_DEPRECATED_FOR +#endif +#if \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DEPRECATED(since) __declspec(deprecated("Since " # since)) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __declspec(deprecated("Since " #since "; use " #replacement)) +#elif \ + (JSON_HEDLEY_HAS_EXTENSION(attribute_deprecated_with_message) && !defined(JSON_HEDLEY_IAR_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,5,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,3,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,3,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DEPRECATED(since) __attribute__((__deprecated__("Since " #since))) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __attribute__((__deprecated__("Since " #since "; use " #replacement))) +#elif defined(__cplusplus) && (__cplusplus >= 201402L) + #define JSON_HEDLEY_DEPRECATED(since) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[deprecated("Since " #since)]]) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[deprecated("Since " #since "; use " #replacement)]]) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(deprecated) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_DEPRECATED(since) __attribute__((__deprecated__)) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __attribute__((__deprecated__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_PELLES_VERSION_CHECK(6,50,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DEPRECATED(since) __declspec(deprecated) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __declspec(deprecated) +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DEPRECATED(since) _Pragma("deprecated") + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) _Pragma("deprecated") +#else + #define JSON_HEDLEY_DEPRECATED(since) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) +#endif + +#if defined(JSON_HEDLEY_UNAVAILABLE) + #undef JSON_HEDLEY_UNAVAILABLE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(warning) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_UNAVAILABLE(available_since) __attribute__((__warning__("Not available until " #available_since))) +#else + #define JSON_HEDLEY_UNAVAILABLE(available_since) +#endif + +#if defined(JSON_HEDLEY_WARN_UNUSED_RESULT) + #undef JSON_HEDLEY_WARN_UNUSED_RESULT +#endif +#if defined(JSON_HEDLEY_WARN_UNUSED_RESULT_MSG) + #undef JSON_HEDLEY_WARN_UNUSED_RESULT_MSG +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(warn_unused_result) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_WARN_UNUSED_RESULT __attribute__((__warn_unused_result__)) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) __attribute__((__warn_unused_result__)) +#elif (JSON_HEDLEY_HAS_CPP_ATTRIBUTE(nodiscard) >= 201907L) + #define JSON_HEDLEY_WARN_UNUSED_RESULT JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard(msg)]]) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE(nodiscard) + #define JSON_HEDLEY_WARN_UNUSED_RESULT JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) +#elif defined(_Check_return_) /* SAL */ + #define JSON_HEDLEY_WARN_UNUSED_RESULT _Check_return_ + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) _Check_return_ +#else + #define JSON_HEDLEY_WARN_UNUSED_RESULT + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) +#endif + +#if defined(JSON_HEDLEY_SENTINEL) + #undef JSON_HEDLEY_SENTINEL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(sentinel) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,4,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_SENTINEL(position) __attribute__((__sentinel__(position))) +#else + #define JSON_HEDLEY_SENTINEL(position) +#endif + +#if defined(JSON_HEDLEY_NO_RETURN) + #undef JSON_HEDLEY_NO_RETURN +#endif +#if JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_NO_RETURN __noreturn +#elif \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_NO_RETURN __attribute__((__noreturn__)) +#elif defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201112L + #define JSON_HEDLEY_NO_RETURN _Noreturn +#elif defined(__cplusplus) && (__cplusplus >= 201103L) + #define JSON_HEDLEY_NO_RETURN JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[noreturn]]) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(noreturn) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,2,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_NO_RETURN __attribute__((__noreturn__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_NO_RETURN _Pragma("does_not_return") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_NO_RETURN __declspec(noreturn) +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,0,0) && defined(__cplusplus) + #define JSON_HEDLEY_NO_RETURN _Pragma("FUNC_NEVER_RETURNS;") +#elif JSON_HEDLEY_COMPCERT_VERSION_CHECK(3,2,0) + #define JSON_HEDLEY_NO_RETURN __attribute((noreturn)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(9,0,0) + #define JSON_HEDLEY_NO_RETURN __declspec(noreturn) +#else + #define JSON_HEDLEY_NO_RETURN +#endif + +#if defined(JSON_HEDLEY_NO_ESCAPE) + #undef JSON_HEDLEY_NO_ESCAPE +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(noescape) + #define JSON_HEDLEY_NO_ESCAPE __attribute__((__noescape__)) +#else + #define JSON_HEDLEY_NO_ESCAPE +#endif + +#if defined(JSON_HEDLEY_UNREACHABLE) + #undef JSON_HEDLEY_UNREACHABLE +#endif +#if defined(JSON_HEDLEY_UNREACHABLE_RETURN) + #undef JSON_HEDLEY_UNREACHABLE_RETURN +#endif +#if defined(JSON_HEDLEY_ASSUME) + #undef JSON_HEDLEY_ASSUME +#endif +#if \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_ASSUME(expr) __assume(expr) +#elif JSON_HEDLEY_HAS_BUILTIN(__builtin_assume) + #define JSON_HEDLEY_ASSUME(expr) __builtin_assume(expr) +#elif \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) + #if defined(__cplusplus) + #define JSON_HEDLEY_ASSUME(expr) std::_nassert(expr) + #else + #define JSON_HEDLEY_ASSUME(expr) _nassert(expr) + #endif +#endif +#if \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_unreachable) && (!defined(JSON_HEDLEY_ARM_VERSION))) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,5,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,10,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,5) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(10,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_UNREACHABLE() __builtin_unreachable() +#elif defined(JSON_HEDLEY_ASSUME) + #define JSON_HEDLEY_UNREACHABLE() JSON_HEDLEY_ASSUME(0) +#endif +#if !defined(JSON_HEDLEY_ASSUME) + #if defined(JSON_HEDLEY_UNREACHABLE) + #define JSON_HEDLEY_ASSUME(expr) JSON_HEDLEY_STATIC_CAST(void, ((expr) ? 1 : (JSON_HEDLEY_UNREACHABLE(), 1))) + #else + #define JSON_HEDLEY_ASSUME(expr) JSON_HEDLEY_STATIC_CAST(void, expr) + #endif +#endif +#if defined(JSON_HEDLEY_UNREACHABLE) + #if \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) return (JSON_HEDLEY_STATIC_CAST(void, JSON_HEDLEY_ASSUME(0)), (value)) + #else + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) JSON_HEDLEY_UNREACHABLE() + #endif +#else + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) return (value) +#endif +#if !defined(JSON_HEDLEY_UNREACHABLE) + #define JSON_HEDLEY_UNREACHABLE() JSON_HEDLEY_ASSUME(0) +#endif + +JSON_HEDLEY_DIAGNOSTIC_PUSH +#if JSON_HEDLEY_HAS_WARNING("-Wpedantic") + #pragma clang diagnostic ignored "-Wpedantic" +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wc++98-compat-pedantic") && defined(__cplusplus) + #pragma clang diagnostic ignored "-Wc++98-compat-pedantic" +#endif +#if JSON_HEDLEY_GCC_HAS_WARNING("-Wvariadic-macros",4,0,0) + #if defined(__clang__) + #pragma clang diagnostic ignored "-Wvariadic-macros" + #elif defined(JSON_HEDLEY_GCC_VERSION) + #pragma GCC diagnostic ignored "-Wvariadic-macros" + #endif +#endif +#if defined(JSON_HEDLEY_NON_NULL) + #undef JSON_HEDLEY_NON_NULL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(nonnull) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) + #define JSON_HEDLEY_NON_NULL(...) __attribute__((__nonnull__(__VA_ARGS__))) +#else + #define JSON_HEDLEY_NON_NULL(...) +#endif +JSON_HEDLEY_DIAGNOSTIC_POP + +#if defined(JSON_HEDLEY_PRINTF_FORMAT) + #undef JSON_HEDLEY_PRINTF_FORMAT +#endif +#if defined(__MINGW32__) && JSON_HEDLEY_GCC_HAS_ATTRIBUTE(format,4,4,0) && !defined(__USE_MINGW_ANSI_STDIO) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(ms_printf, string_idx, first_to_check))) +#elif defined(__MINGW32__) && JSON_HEDLEY_GCC_HAS_ATTRIBUTE(format,4,4,0) && defined(__USE_MINGW_ANSI_STDIO) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(gnu_printf, string_idx, first_to_check))) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(format) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(__printf__, string_idx, first_to_check))) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(6,0,0) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __declspec(vaformat(printf,string_idx,first_to_check)) +#else + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) +#endif + +#if defined(JSON_HEDLEY_CONSTEXPR) + #undef JSON_HEDLEY_CONSTEXPR +#endif +#if defined(__cplusplus) + #if __cplusplus >= 201103L + #define JSON_HEDLEY_CONSTEXPR JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(constexpr) + #endif +#endif +#if !defined(JSON_HEDLEY_CONSTEXPR) + #define JSON_HEDLEY_CONSTEXPR +#endif + +#if defined(JSON_HEDLEY_PREDICT) + #undef JSON_HEDLEY_PREDICT +#endif +#if defined(JSON_HEDLEY_LIKELY) + #undef JSON_HEDLEY_LIKELY +#endif +#if defined(JSON_HEDLEY_UNLIKELY) + #undef JSON_HEDLEY_UNLIKELY +#endif +#if defined(JSON_HEDLEY_UNPREDICTABLE) + #undef JSON_HEDLEY_UNPREDICTABLE +#endif +#if JSON_HEDLEY_HAS_BUILTIN(__builtin_unpredictable) + #define JSON_HEDLEY_UNPREDICTABLE(expr) __builtin_unpredictable((expr)) +#endif +#if \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_expect_with_probability) && !defined(JSON_HEDLEY_PGI_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(9,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PREDICT(expr, value, probability) __builtin_expect_with_probability( (expr), (value), (probability)) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) __builtin_expect_with_probability(!!(expr), 1 , (probability)) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) __builtin_expect_with_probability(!!(expr), 0 , (probability)) +# define JSON_HEDLEY_LIKELY(expr) __builtin_expect (!!(expr), 1 ) +# define JSON_HEDLEY_UNLIKELY(expr) __builtin_expect (!!(expr), 0 ) +#elif \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_expect) && !defined(JSON_HEDLEY_INTEL_CL_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,7,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,27) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PREDICT(expr, expected, probability) \ + (((probability) >= 0.9) ? __builtin_expect((expr), (expected)) : (JSON_HEDLEY_STATIC_CAST(void, expected), (expr))) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) \ + (__extension__ ({ \ + double hedley_probability_ = (probability); \ + ((hedley_probability_ >= 0.9) ? __builtin_expect(!!(expr), 1) : ((hedley_probability_ <= 0.1) ? __builtin_expect(!!(expr), 0) : !!(expr))); \ + })) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) \ + (__extension__ ({ \ + double hedley_probability_ = (probability); \ + ((hedley_probability_ >= 0.9) ? __builtin_expect(!!(expr), 0) : ((hedley_probability_ <= 0.1) ? __builtin_expect(!!(expr), 1) : !!(expr))); \ + })) +# define JSON_HEDLEY_LIKELY(expr) __builtin_expect(!!(expr), 1) +# define JSON_HEDLEY_UNLIKELY(expr) __builtin_expect(!!(expr), 0) +#else +# define JSON_HEDLEY_PREDICT(expr, expected, probability) (JSON_HEDLEY_STATIC_CAST(void, expected), (expr)) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) (!!(expr)) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) (!!(expr)) +# define JSON_HEDLEY_LIKELY(expr) (!!(expr)) +# define JSON_HEDLEY_UNLIKELY(expr) (!!(expr)) +#endif +#if !defined(JSON_HEDLEY_UNPREDICTABLE) + #define JSON_HEDLEY_UNPREDICTABLE(expr) JSON_HEDLEY_PREDICT(expr, 1, 0.5) +#endif + +#if defined(JSON_HEDLEY_MALLOC) + #undef JSON_HEDLEY_MALLOC +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(malloc) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(12,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_MALLOC __attribute__((__malloc__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_MALLOC _Pragma("returns_new_memory") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_MALLOC __declspec(restrict) +#else + #define JSON_HEDLEY_MALLOC +#endif + +#if defined(JSON_HEDLEY_PURE) + #undef JSON_HEDLEY_PURE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(pure) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(2,96,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PURE __attribute__((__pure__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) +# define JSON_HEDLEY_PURE _Pragma("does_not_write_global_data") +#elif defined(__cplusplus) && \ + ( \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(2,0,1) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) \ + ) +# define JSON_HEDLEY_PURE _Pragma("FUNC_IS_PURE;") +#else +# define JSON_HEDLEY_PURE +#endif + +#if defined(JSON_HEDLEY_CONST) + #undef JSON_HEDLEY_CONST +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(const) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(2,5,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_CONST __attribute__((__const__)) +#elif \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_CONST _Pragma("no_side_effect") +#else + #define JSON_HEDLEY_CONST JSON_HEDLEY_PURE +#endif + +#if defined(JSON_HEDLEY_RESTRICT) + #undef JSON_HEDLEY_RESTRICT +#endif +#if defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L) && !defined(__cplusplus) + #define JSON_HEDLEY_RESTRICT restrict +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,4) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,14,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) || \ + defined(__clang__) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_RESTRICT __restrict +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,3,0) && !defined(__cplusplus) + #define JSON_HEDLEY_RESTRICT _Restrict +#else + #define JSON_HEDLEY_RESTRICT +#endif + +#if defined(JSON_HEDLEY_INLINE) + #undef JSON_HEDLEY_INLINE +#endif +#if \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L)) || \ + (defined(__cplusplus) && (__cplusplus >= 199711L)) + #define JSON_HEDLEY_INLINE inline +#elif \ + defined(JSON_HEDLEY_GCC_VERSION) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(6,2,0) + #define JSON_HEDLEY_INLINE __inline__ +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(12,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,1,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_INLINE __inline +#else + #define JSON_HEDLEY_INLINE +#endif + +#if defined(JSON_HEDLEY_ALWAYS_INLINE) + #undef JSON_HEDLEY_ALWAYS_INLINE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(always_inline) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) +# define JSON_HEDLEY_ALWAYS_INLINE __attribute__((__always_inline__)) JSON_HEDLEY_INLINE +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(12,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_ALWAYS_INLINE __forceinline +#elif defined(__cplusplus) && \ + ( \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) \ + ) +# define JSON_HEDLEY_ALWAYS_INLINE _Pragma("FUNC_ALWAYS_INLINE;") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) +# define JSON_HEDLEY_ALWAYS_INLINE _Pragma("inline=forced") +#else +# define JSON_HEDLEY_ALWAYS_INLINE JSON_HEDLEY_INLINE +#endif + +#if defined(JSON_HEDLEY_NEVER_INLINE) + #undef JSON_HEDLEY_NEVER_INLINE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(noinline) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_NEVER_INLINE __attribute__((__noinline__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_NEVER_INLINE __declspec(noinline) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(10,2,0) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("noinline") +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,0,0) && defined(__cplusplus) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("FUNC_CANNOT_INLINE;") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("inline=never") +#elif JSON_HEDLEY_COMPCERT_VERSION_CHECK(3,2,0) + #define JSON_HEDLEY_NEVER_INLINE __attribute((noinline)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(9,0,0) + #define JSON_HEDLEY_NEVER_INLINE __declspec(noinline) +#else + #define JSON_HEDLEY_NEVER_INLINE +#endif + +#if defined(JSON_HEDLEY_PRIVATE) + #undef JSON_HEDLEY_PRIVATE +#endif +#if defined(JSON_HEDLEY_PUBLIC) + #undef JSON_HEDLEY_PUBLIC +#endif +#if defined(JSON_HEDLEY_IMPORT) + #undef JSON_HEDLEY_IMPORT +#endif +#if defined(_WIN32) || defined(__CYGWIN__) +# define JSON_HEDLEY_PRIVATE +# define JSON_HEDLEY_PUBLIC __declspec(dllexport) +# define JSON_HEDLEY_IMPORT __declspec(dllimport) +#else +# if \ + JSON_HEDLEY_HAS_ATTRIBUTE(visibility) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + ( \ + defined(__TI_EABI__) && \ + ( \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) \ + ) \ + ) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PRIVATE __attribute__((__visibility__("hidden"))) +# define JSON_HEDLEY_PUBLIC __attribute__((__visibility__("default"))) +# else +# define JSON_HEDLEY_PRIVATE +# define JSON_HEDLEY_PUBLIC +# endif +# define JSON_HEDLEY_IMPORT extern +#endif + +#if defined(JSON_HEDLEY_NO_THROW) + #undef JSON_HEDLEY_NO_THROW +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(nothrow) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_NO_THROW __attribute__((__nothrow__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) + #define JSON_HEDLEY_NO_THROW __declspec(nothrow) +#else + #define JSON_HEDLEY_NO_THROW +#endif + +#if defined(JSON_HEDLEY_FALL_THROUGH) + #undef JSON_HEDLEY_FALL_THROUGH +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(fallthrough) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(7,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_FALL_THROUGH __attribute__((__fallthrough__)) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(clang,fallthrough) + #define JSON_HEDLEY_FALL_THROUGH JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[clang::fallthrough]]) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE(fallthrough) + #define JSON_HEDLEY_FALL_THROUGH JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[fallthrough]]) +#elif defined(__fallthrough) /* SAL */ + #define JSON_HEDLEY_FALL_THROUGH __fallthrough +#else + #define JSON_HEDLEY_FALL_THROUGH +#endif + +#if defined(JSON_HEDLEY_RETURNS_NON_NULL) + #undef JSON_HEDLEY_RETURNS_NON_NULL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(returns_nonnull) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,9,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_RETURNS_NON_NULL __attribute__((__returns_nonnull__)) +#elif defined(_Ret_notnull_) /* SAL */ + #define JSON_HEDLEY_RETURNS_NON_NULL _Ret_notnull_ +#else + #define JSON_HEDLEY_RETURNS_NON_NULL +#endif + +#if defined(JSON_HEDLEY_ARRAY_PARAM) + #undef JSON_HEDLEY_ARRAY_PARAM +#endif +#if \ + defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L) && \ + !defined(__STDC_NO_VLA__) && \ + !defined(__cplusplus) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_TINYC_VERSION) + #define JSON_HEDLEY_ARRAY_PARAM(name) (name) +#else + #define JSON_HEDLEY_ARRAY_PARAM(name) +#endif + +#if defined(JSON_HEDLEY_IS_CONSTANT) + #undef JSON_HEDLEY_IS_CONSTANT +#endif +#if defined(JSON_HEDLEY_REQUIRE_CONSTEXPR) + #undef JSON_HEDLEY_REQUIRE_CONSTEXPR +#endif +/* JSON_HEDLEY_IS_CONSTEXPR_ is for + HEDLEY INTERNAL USE ONLY. API subject to change without notice. */ +#if defined(JSON_HEDLEY_IS_CONSTEXPR_) + #undef JSON_HEDLEY_IS_CONSTEXPR_ +#endif +#if \ + JSON_HEDLEY_HAS_BUILTIN(__builtin_constant_p) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,19) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) && !defined(__cplusplus)) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_IS_CONSTANT(expr) __builtin_constant_p(expr) +#endif +#if !defined(__cplusplus) +# if \ + JSON_HEDLEY_HAS_BUILTIN(__builtin_types_compatible_p) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,4,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,24) +#if defined(__INTPTR_TYPE__) + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) __builtin_types_compatible_p(__typeof__((1 ? (void*) ((__INTPTR_TYPE__) ((expr) * 0)) : (int*) 0)), int*) +#else + #include + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) __builtin_types_compatible_p(__typeof__((1 ? (void*) ((intptr_t) ((expr) * 0)) : (int*) 0)), int*) +#endif +# elif \ + ( \ + defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L) && \ + !defined(JSON_HEDLEY_SUNPRO_VERSION) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_IAR_VERSION)) || \ + (JSON_HEDLEY_HAS_EXTENSION(c_generic_selections) && !defined(JSON_HEDLEY_IAR_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,9,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(17,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(12,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,3,0) +#if defined(__INTPTR_TYPE__) + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) _Generic((1 ? (void*) ((__INTPTR_TYPE__) ((expr) * 0)) : (int*) 0), int*: 1, void*: 0) +#else + #include + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) _Generic((1 ? (void*) ((intptr_t) * 0) : (int*) 0), int*: 1, void*: 0) +#endif +# elif \ + defined(JSON_HEDLEY_GCC_VERSION) || \ + defined(JSON_HEDLEY_INTEL_VERSION) || \ + defined(JSON_HEDLEY_TINYC_VERSION) || \ + defined(JSON_HEDLEY_TI_ARMCL_VERSION) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(18,12,0) || \ + defined(JSON_HEDLEY_TI_CL2000_VERSION) || \ + defined(JSON_HEDLEY_TI_CL6X_VERSION) || \ + defined(JSON_HEDLEY_TI_CL7X_VERSION) || \ + defined(JSON_HEDLEY_TI_CLPRU_VERSION) || \ + defined(__clang__) +# define JSON_HEDLEY_IS_CONSTEXPR_(expr) ( \ + sizeof(void) != \ + sizeof(*( \ + 1 ? \ + ((void*) ((expr) * 0L) ) : \ +((struct { char v[sizeof(void) * 2]; } *) 1) \ + ) \ + ) \ + ) +# endif +#endif +#if defined(JSON_HEDLEY_IS_CONSTEXPR_) + #if !defined(JSON_HEDLEY_IS_CONSTANT) + #define JSON_HEDLEY_IS_CONSTANT(expr) JSON_HEDLEY_IS_CONSTEXPR_(expr) + #endif + #define JSON_HEDLEY_REQUIRE_CONSTEXPR(expr) (JSON_HEDLEY_IS_CONSTEXPR_(expr) ? (expr) : (-1)) +#else + #if !defined(JSON_HEDLEY_IS_CONSTANT) + #define JSON_HEDLEY_IS_CONSTANT(expr) (0) + #endif + #define JSON_HEDLEY_REQUIRE_CONSTEXPR(expr) (expr) +#endif + +#if defined(JSON_HEDLEY_BEGIN_C_DECLS) + #undef JSON_HEDLEY_BEGIN_C_DECLS +#endif +#if defined(JSON_HEDLEY_END_C_DECLS) + #undef JSON_HEDLEY_END_C_DECLS +#endif +#if defined(JSON_HEDLEY_C_DECL) + #undef JSON_HEDLEY_C_DECL +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_BEGIN_C_DECLS extern "C" { + #define JSON_HEDLEY_END_C_DECLS } + #define JSON_HEDLEY_C_DECL extern "C" +#else + #define JSON_HEDLEY_BEGIN_C_DECLS + #define JSON_HEDLEY_END_C_DECLS + #define JSON_HEDLEY_C_DECL +#endif + +#if defined(JSON_HEDLEY_STATIC_ASSERT) + #undef JSON_HEDLEY_STATIC_ASSERT +#endif +#if \ + !defined(__cplusplus) && ( \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L)) || \ + (JSON_HEDLEY_HAS_FEATURE(c_static_assert) && !defined(JSON_HEDLEY_INTEL_CL_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(6,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + defined(_Static_assert) \ + ) +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) _Static_assert(expr, message) +#elif \ + (defined(__cplusplus) && (__cplusplus >= 201103L)) || \ + JSON_HEDLEY_MSVC_VERSION_CHECK(16,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(static_assert(expr, message)) +#else +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) +#endif + +#if defined(JSON_HEDLEY_NULL) + #undef JSON_HEDLEY_NULL +#endif +#if defined(__cplusplus) + #if __cplusplus >= 201103L + #define JSON_HEDLEY_NULL JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(nullptr) + #elif defined(NULL) + #define JSON_HEDLEY_NULL NULL + #else + #define JSON_HEDLEY_NULL JSON_HEDLEY_STATIC_CAST(void*, 0) + #endif +#elif defined(NULL) + #define JSON_HEDLEY_NULL NULL +#else + #define JSON_HEDLEY_NULL ((void*) 0) +#endif + +#if defined(JSON_HEDLEY_MESSAGE) + #undef JSON_HEDLEY_MESSAGE +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") +# define JSON_HEDLEY_MESSAGE(msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS \ + JSON_HEDLEY_PRAGMA(message msg) \ + JSON_HEDLEY_DIAGNOSTIC_POP +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message msg) +#elif JSON_HEDLEY_CRAY_VERSION_CHECK(5,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(_CRI message msg) +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#else +# define JSON_HEDLEY_MESSAGE(msg) +#endif + +#if defined(JSON_HEDLEY_WARNING) + #undef JSON_HEDLEY_WARNING +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") +# define JSON_HEDLEY_WARNING(msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS \ + JSON_HEDLEY_PRAGMA(clang warning msg) \ + JSON_HEDLEY_DIAGNOSTIC_POP +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,8,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_PRAGMA(GCC warning msg) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#else +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_MESSAGE(msg) +#endif + +#if defined(JSON_HEDLEY_REQUIRE) + #undef JSON_HEDLEY_REQUIRE +#endif +#if defined(JSON_HEDLEY_REQUIRE_MSG) + #undef JSON_HEDLEY_REQUIRE_MSG +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(diagnose_if) +# if JSON_HEDLEY_HAS_WARNING("-Wgcc-compat") +# define JSON_HEDLEY_REQUIRE(expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wgcc-compat\"") \ + __attribute__((diagnose_if(!(expr), #expr, "error"))) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wgcc-compat\"") \ + __attribute__((diagnose_if(!(expr), msg, "error"))) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_REQUIRE(expr) __attribute__((diagnose_if(!(expr), #expr, "error"))) +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) __attribute__((diagnose_if(!(expr), msg, "error"))) +# endif +#else +# define JSON_HEDLEY_REQUIRE(expr) +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) +#endif + +#if defined(JSON_HEDLEY_FLAGS) + #undef JSON_HEDLEY_FLAGS +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(flag_enum) && (!defined(__cplusplus) || JSON_HEDLEY_HAS_WARNING("-Wbitfield-enum-conversion")) + #define JSON_HEDLEY_FLAGS __attribute__((__flag_enum__)) +#else + #define JSON_HEDLEY_FLAGS +#endif + +#if defined(JSON_HEDLEY_FLAGS_CAST) + #undef JSON_HEDLEY_FLAGS_CAST +#endif +#if JSON_HEDLEY_INTEL_VERSION_CHECK(19,0,0) +# define JSON_HEDLEY_FLAGS_CAST(T, expr) (__extension__ ({ \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("warning(disable:188)") \ + ((T) (expr)); \ + JSON_HEDLEY_DIAGNOSTIC_POP \ + })) +#else +# define JSON_HEDLEY_FLAGS_CAST(T, expr) JSON_HEDLEY_STATIC_CAST(T, expr) +#endif + +#if defined(JSON_HEDLEY_EMPTY_BASES) + #undef JSON_HEDLEY_EMPTY_BASES +#endif +#if \ + (JSON_HEDLEY_MSVC_VERSION_CHECK(19,0,23918) && !JSON_HEDLEY_MSVC_VERSION_CHECK(20,0,0)) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_EMPTY_BASES __declspec(empty_bases) +#else + #define JSON_HEDLEY_EMPTY_BASES +#endif + +/* Remaining macros are deprecated. */ + +#if defined(JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK) + #undef JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK +#endif +#if defined(__clang__) + #define JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK(major,minor,patch) (0) +#else + #define JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK(major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_CLANG_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_BUILTIN) + #undef JSON_HEDLEY_CLANG_HAS_BUILTIN +#endif +#define JSON_HEDLEY_CLANG_HAS_BUILTIN(builtin) JSON_HEDLEY_HAS_BUILTIN(builtin) + +#if defined(JSON_HEDLEY_CLANG_HAS_FEATURE) + #undef JSON_HEDLEY_CLANG_HAS_FEATURE +#endif +#define JSON_HEDLEY_CLANG_HAS_FEATURE(feature) JSON_HEDLEY_HAS_FEATURE(feature) + +#if defined(JSON_HEDLEY_CLANG_HAS_EXTENSION) + #undef JSON_HEDLEY_CLANG_HAS_EXTENSION +#endif +#define JSON_HEDLEY_CLANG_HAS_EXTENSION(extension) JSON_HEDLEY_HAS_EXTENSION(extension) + +#if defined(JSON_HEDLEY_CLANG_HAS_DECLSPEC_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_DECLSPEC_DECLSPEC_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_DECLSPEC_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_WARNING) + #undef JSON_HEDLEY_CLANG_HAS_WARNING +#endif +#define JSON_HEDLEY_CLANG_HAS_WARNING(warning) JSON_HEDLEY_HAS_WARNING(warning) + +#endif /* !defined(JSON_HEDLEY_VERSION) || (JSON_HEDLEY_VERSION < X) */ + + +// This file contains all internal macro definitions (except those affecting ABI) +// You MUST include macro_unscope.hpp at the end of json.hpp to undef all of them + +// #include + + +// exclude unsupported compilers +#if !defined(JSON_SKIP_UNSUPPORTED_COMPILER_CHECK) + #if defined(__clang__) + #if (__clang_major__ * 10000 + __clang_minor__ * 100 + __clang_patchlevel__) < 30400 + #error "unsupported Clang version - see https://github.com/nlohmann/json#supported-compilers" + #endif + #elif defined(__GNUC__) && !(defined(__ICC) || defined(__INTEL_COMPILER)) + #if (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) < 40800 + #error "unsupported GCC version - see https://github.com/nlohmann/json#supported-compilers" + #endif + #endif +#endif + +// C++ language standard detection +// if the user manually specified the used c++ version this is skipped +#if !defined(JSON_HAS_CPP_20) && !defined(JSON_HAS_CPP_17) && !defined(JSON_HAS_CPP_14) && !defined(JSON_HAS_CPP_11) + #if (defined(__cplusplus) && __cplusplus >= 202002L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 202002L) + #define JSON_HAS_CPP_20 + #define JSON_HAS_CPP_17 + #define JSON_HAS_CPP_14 + #elif (defined(__cplusplus) && __cplusplus >= 201703L) || (defined(_HAS_CXX17) && _HAS_CXX17 == 1) // fix for issue #464 + #define JSON_HAS_CPP_17 + #define JSON_HAS_CPP_14 + #elif (defined(__cplusplus) && __cplusplus >= 201402L) || (defined(_HAS_CXX14) && _HAS_CXX14 == 1) + #define JSON_HAS_CPP_14 + #endif + // the cpp 11 flag is always specified because it is the minimal required version + #define JSON_HAS_CPP_11 +#endif + +#ifdef __has_include + #if __has_include() + #include + #endif +#endif + +#if !defined(JSON_HAS_FILESYSTEM) && !defined(JSON_HAS_EXPERIMENTAL_FILESYSTEM) + #ifdef JSON_HAS_CPP_17 + #if defined(__cpp_lib_filesystem) + #define JSON_HAS_FILESYSTEM 1 + #elif defined(__cpp_lib_experimental_filesystem) + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #elif !defined(__has_include) + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #elif __has_include() + #define JSON_HAS_FILESYSTEM 1 + #elif __has_include() + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #endif + + // std::filesystem does not work on MinGW GCC 8: https://sourceforge.net/p/mingw-w64/bugs/737/ + #if defined(__MINGW32__) && defined(__GNUC__) && __GNUC__ == 8 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before GCC 8: https://en.cppreference.com/w/cpp/compiler_support + #if defined(__GNUC__) && !defined(__clang__) && __GNUC__ < 8 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before Clang 7: https://en.cppreference.com/w/cpp/compiler_support + #if defined(__clang_major__) && __clang_major__ < 7 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before MSVC 19.14: https://en.cppreference.com/w/cpp/compiler_support + #if defined(_MSC_VER) && _MSC_VER < 1914 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before iOS 13 + #if defined(__IPHONE_OS_VERSION_MIN_REQUIRED) && __IPHONE_OS_VERSION_MIN_REQUIRED < 130000 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before macOS Catalina + #if defined(__MAC_OS_X_VERSION_MIN_REQUIRED) && __MAC_OS_X_VERSION_MIN_REQUIRED < 101500 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + #endif +#endif + +#ifndef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 0 +#endif + +#ifndef JSON_HAS_FILESYSTEM + #define JSON_HAS_FILESYSTEM 0 +#endif + +#ifndef JSON_HAS_THREE_WAY_COMPARISON + #if defined(__cpp_impl_three_way_comparison) && __cpp_impl_three_way_comparison >= 201907L \ + && defined(__cpp_lib_three_way_comparison) && __cpp_lib_three_way_comparison >= 201907L + #define JSON_HAS_THREE_WAY_COMPARISON 1 + #else + #define JSON_HAS_THREE_WAY_COMPARISON 0 + #endif +#endif + +#ifndef JSON_HAS_RANGES + // ranges header shipping in GCC 11.1.0 (released 2021-04-27) has syntax error + #if defined(__GLIBCXX__) && __GLIBCXX__ == 20210427 + #define JSON_HAS_RANGES 0 + #elif defined(__cpp_lib_ranges) + #define JSON_HAS_RANGES 1 + #else + #define JSON_HAS_RANGES 0 + #endif +#endif + +#ifdef JSON_HAS_CPP_17 + #define JSON_INLINE_VARIABLE inline +#else + #define JSON_INLINE_VARIABLE +#endif + +#if JSON_HEDLEY_HAS_ATTRIBUTE(no_unique_address) + #define JSON_NO_UNIQUE_ADDRESS [[no_unique_address]] +#else + #define JSON_NO_UNIQUE_ADDRESS +#endif + +// disable documentation warnings on clang +#if defined(__clang__) + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wdocumentation" + #pragma clang diagnostic ignored "-Wdocumentation-unknown-command" +#endif + +// allow disabling exceptions +#if (defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND)) && !defined(JSON_NOEXCEPTION) + #define JSON_THROW(exception) throw exception + #define JSON_TRY try + #define JSON_CATCH(exception) catch(exception) + #define JSON_INTERNAL_CATCH(exception) catch(exception) +#else + #include + #define JSON_THROW(exception) std::abort() + #define JSON_TRY if(true) + #define JSON_CATCH(exception) if(false) + #define JSON_INTERNAL_CATCH(exception) if(false) +#endif + +// override exception macros +#if defined(JSON_THROW_USER) + #undef JSON_THROW + #define JSON_THROW JSON_THROW_USER +#endif +#if defined(JSON_TRY_USER) + #undef JSON_TRY + #define JSON_TRY JSON_TRY_USER +#endif +#if defined(JSON_CATCH_USER) + #undef JSON_CATCH + #define JSON_CATCH JSON_CATCH_USER + #undef JSON_INTERNAL_CATCH + #define JSON_INTERNAL_CATCH JSON_CATCH_USER +#endif +#if defined(JSON_INTERNAL_CATCH_USER) + #undef JSON_INTERNAL_CATCH + #define JSON_INTERNAL_CATCH JSON_INTERNAL_CATCH_USER +#endif + +// allow overriding assert +#if !defined(JSON_ASSERT) + #include // assert + #define JSON_ASSERT(x) assert(x) +#endif + +// allow to access some private functions (needed by the test suite) +#if defined(JSON_TESTS_PRIVATE) + #define JSON_PRIVATE_UNLESS_TESTED public +#else + #define JSON_PRIVATE_UNLESS_TESTED private +#endif + +/*! +@brief macro to briefly define a mapping between an enum and JSON +@def NLOHMANN_JSON_SERIALIZE_ENUM +@since version 3.4.0 +*/ +#define NLOHMANN_JSON_SERIALIZE_ENUM(ENUM_TYPE, ...) \ + template \ + inline void to_json(BasicJsonType& j, const ENUM_TYPE& e) \ + { \ + static_assert(std::is_enum::value, #ENUM_TYPE " must be an enum!"); \ + static const std::pair m[] = __VA_ARGS__; \ + auto it = std::find_if(std::begin(m), std::end(m), \ + [e](const std::pair& ej_pair) -> bool \ + { \ + return ej_pair.first == e; \ + }); \ + j = ((it != std::end(m)) ? it : std::begin(m))->second; \ + } \ + template \ + inline void from_json(const BasicJsonType& j, ENUM_TYPE& e) \ + { \ + static_assert(std::is_enum::value, #ENUM_TYPE " must be an enum!"); \ + static const std::pair m[] = __VA_ARGS__; \ + auto it = std::find_if(std::begin(m), std::end(m), \ + [&j](const std::pair& ej_pair) -> bool \ + { \ + return ej_pair.second == j; \ + }); \ + e = ((it != std::end(m)) ? it : std::begin(m))->first; \ + } + +// Ugly macros to avoid uglier copy-paste when specializing basic_json. They +// may be removed in the future once the class is split. + +#define NLOHMANN_BASIC_JSON_TPL_DECLARATION \ + template class ObjectType, \ + template class ArrayType, \ + class StringType, class BooleanType, class NumberIntegerType, \ + class NumberUnsignedType, class NumberFloatType, \ + template class AllocatorType, \ + template class JSONSerializer, \ + class BinaryType, \ + class CustomBaseClass> + +#define NLOHMANN_BASIC_JSON_TPL \ + basic_json + +// Macros to simplify conversion from/to types + +#define NLOHMANN_JSON_EXPAND( x ) x +#define NLOHMANN_JSON_GET_MACRO(_1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, _15, _16, _17, _18, _19, _20, _21, _22, _23, _24, _25, _26, _27, _28, _29, _30, _31, _32, _33, _34, _35, _36, _37, _38, _39, _40, _41, _42, _43, _44, _45, _46, _47, _48, _49, _50, _51, _52, _53, _54, _55, _56, _57, _58, _59, _60, _61, _62, _63, _64, NAME,...) NAME +#define NLOHMANN_JSON_PASTE(...) NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_GET_MACRO(__VA_ARGS__, \ + NLOHMANN_JSON_PASTE64, \ + NLOHMANN_JSON_PASTE63, \ + NLOHMANN_JSON_PASTE62, \ + NLOHMANN_JSON_PASTE61, \ + NLOHMANN_JSON_PASTE60, \ + NLOHMANN_JSON_PASTE59, \ + NLOHMANN_JSON_PASTE58, \ + NLOHMANN_JSON_PASTE57, \ + NLOHMANN_JSON_PASTE56, \ + NLOHMANN_JSON_PASTE55, \ + NLOHMANN_JSON_PASTE54, \ + NLOHMANN_JSON_PASTE53, \ + NLOHMANN_JSON_PASTE52, \ + NLOHMANN_JSON_PASTE51, \ + NLOHMANN_JSON_PASTE50, \ + NLOHMANN_JSON_PASTE49, \ + NLOHMANN_JSON_PASTE48, \ + NLOHMANN_JSON_PASTE47, \ + NLOHMANN_JSON_PASTE46, \ + NLOHMANN_JSON_PASTE45, \ + NLOHMANN_JSON_PASTE44, \ + NLOHMANN_JSON_PASTE43, \ + NLOHMANN_JSON_PASTE42, \ + NLOHMANN_JSON_PASTE41, \ + NLOHMANN_JSON_PASTE40, \ + NLOHMANN_JSON_PASTE39, \ + NLOHMANN_JSON_PASTE38, \ + NLOHMANN_JSON_PASTE37, \ + NLOHMANN_JSON_PASTE36, \ + NLOHMANN_JSON_PASTE35, \ + NLOHMANN_JSON_PASTE34, \ + NLOHMANN_JSON_PASTE33, \ + NLOHMANN_JSON_PASTE32, \ + NLOHMANN_JSON_PASTE31, \ + NLOHMANN_JSON_PASTE30, \ + NLOHMANN_JSON_PASTE29, \ + NLOHMANN_JSON_PASTE28, \ + NLOHMANN_JSON_PASTE27, \ + NLOHMANN_JSON_PASTE26, \ + NLOHMANN_JSON_PASTE25, \ + NLOHMANN_JSON_PASTE24, \ + NLOHMANN_JSON_PASTE23, \ + NLOHMANN_JSON_PASTE22, \ + NLOHMANN_JSON_PASTE21, \ + NLOHMANN_JSON_PASTE20, \ + NLOHMANN_JSON_PASTE19, \ + NLOHMANN_JSON_PASTE18, \ + NLOHMANN_JSON_PASTE17, \ + NLOHMANN_JSON_PASTE16, \ + NLOHMANN_JSON_PASTE15, \ + NLOHMANN_JSON_PASTE14, \ + NLOHMANN_JSON_PASTE13, \ + NLOHMANN_JSON_PASTE12, \ + NLOHMANN_JSON_PASTE11, \ + NLOHMANN_JSON_PASTE10, \ + NLOHMANN_JSON_PASTE9, \ + NLOHMANN_JSON_PASTE8, \ + NLOHMANN_JSON_PASTE7, \ + NLOHMANN_JSON_PASTE6, \ + NLOHMANN_JSON_PASTE5, \ + NLOHMANN_JSON_PASTE4, \ + NLOHMANN_JSON_PASTE3, \ + NLOHMANN_JSON_PASTE2, \ + NLOHMANN_JSON_PASTE1)(__VA_ARGS__)) +#define NLOHMANN_JSON_PASTE2(func, v1) func(v1) +#define NLOHMANN_JSON_PASTE3(func, v1, v2) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE2(func, v2) +#define NLOHMANN_JSON_PASTE4(func, v1, v2, v3) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE3(func, v2, v3) +#define NLOHMANN_JSON_PASTE5(func, v1, v2, v3, v4) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE4(func, v2, v3, v4) +#define NLOHMANN_JSON_PASTE6(func, v1, v2, v3, v4, v5) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE5(func, v2, v3, v4, v5) +#define NLOHMANN_JSON_PASTE7(func, v1, v2, v3, v4, v5, v6) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE6(func, v2, v3, v4, v5, v6) +#define NLOHMANN_JSON_PASTE8(func, v1, v2, v3, v4, v5, v6, v7) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE7(func, v2, v3, v4, v5, v6, v7) +#define NLOHMANN_JSON_PASTE9(func, v1, v2, v3, v4, v5, v6, v7, v8) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE8(func, v2, v3, v4, v5, v6, v7, v8) +#define NLOHMANN_JSON_PASTE10(func, v1, v2, v3, v4, v5, v6, v7, v8, v9) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE9(func, v2, v3, v4, v5, v6, v7, v8, v9) +#define NLOHMANN_JSON_PASTE11(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE10(func, v2, v3, v4, v5, v6, v7, v8, v9, v10) +#define NLOHMANN_JSON_PASTE12(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE11(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11) +#define NLOHMANN_JSON_PASTE13(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE12(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12) +#define NLOHMANN_JSON_PASTE14(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE13(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13) +#define NLOHMANN_JSON_PASTE15(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE14(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14) +#define NLOHMANN_JSON_PASTE16(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE15(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15) +#define NLOHMANN_JSON_PASTE17(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE16(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16) +#define NLOHMANN_JSON_PASTE18(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE17(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17) +#define NLOHMANN_JSON_PASTE19(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE18(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18) +#define NLOHMANN_JSON_PASTE20(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE19(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19) +#define NLOHMANN_JSON_PASTE21(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE20(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20) +#define NLOHMANN_JSON_PASTE22(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE21(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21) +#define NLOHMANN_JSON_PASTE23(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE22(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22) +#define NLOHMANN_JSON_PASTE24(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE23(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23) +#define NLOHMANN_JSON_PASTE25(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE24(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24) +#define NLOHMANN_JSON_PASTE26(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE25(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25) +#define NLOHMANN_JSON_PASTE27(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE26(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26) +#define NLOHMANN_JSON_PASTE28(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE27(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27) +#define NLOHMANN_JSON_PASTE29(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE28(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28) +#define NLOHMANN_JSON_PASTE30(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE29(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29) +#define NLOHMANN_JSON_PASTE31(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE30(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30) +#define NLOHMANN_JSON_PASTE32(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE31(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31) +#define NLOHMANN_JSON_PASTE33(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE32(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32) +#define NLOHMANN_JSON_PASTE34(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE33(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33) +#define NLOHMANN_JSON_PASTE35(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE34(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34) +#define NLOHMANN_JSON_PASTE36(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE35(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35) +#define NLOHMANN_JSON_PASTE37(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE36(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36) +#define NLOHMANN_JSON_PASTE38(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE37(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37) +#define NLOHMANN_JSON_PASTE39(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE38(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38) +#define NLOHMANN_JSON_PASTE40(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE39(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39) +#define NLOHMANN_JSON_PASTE41(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE40(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40) +#define NLOHMANN_JSON_PASTE42(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE41(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41) +#define NLOHMANN_JSON_PASTE43(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE42(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42) +#define NLOHMANN_JSON_PASTE44(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE43(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43) +#define NLOHMANN_JSON_PASTE45(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE44(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44) +#define NLOHMANN_JSON_PASTE46(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE45(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45) +#define NLOHMANN_JSON_PASTE47(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE46(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46) +#define NLOHMANN_JSON_PASTE48(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE47(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47) +#define NLOHMANN_JSON_PASTE49(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE48(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48) +#define NLOHMANN_JSON_PASTE50(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE49(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49) +#define NLOHMANN_JSON_PASTE51(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE50(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50) +#define NLOHMANN_JSON_PASTE52(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE51(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51) +#define NLOHMANN_JSON_PASTE53(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE52(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52) +#define NLOHMANN_JSON_PASTE54(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE53(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53) +#define NLOHMANN_JSON_PASTE55(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE54(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54) +#define NLOHMANN_JSON_PASTE56(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE55(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55) +#define NLOHMANN_JSON_PASTE57(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE56(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56) +#define NLOHMANN_JSON_PASTE58(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE57(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57) +#define NLOHMANN_JSON_PASTE59(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE58(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58) +#define NLOHMANN_JSON_PASTE60(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE59(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59) +#define NLOHMANN_JSON_PASTE61(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE60(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60) +#define NLOHMANN_JSON_PASTE62(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE61(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61) +#define NLOHMANN_JSON_PASTE63(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE62(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62) +#define NLOHMANN_JSON_PASTE64(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62, v63) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE63(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62, v63) + +#define NLOHMANN_JSON_TO(v1) nlohmann_json_j[#v1] = nlohmann_json_t.v1; +#define NLOHMANN_JSON_FROM(v1) nlohmann_json_j.at(#v1).get_to(nlohmann_json_t.v1); +#define NLOHMANN_JSON_FROM_WITH_DEFAULT(v1) nlohmann_json_t.v1 = nlohmann_json_j.value(#v1, nlohmann_json_default_obj.v1); + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_INTRUSIVE +@since version 3.9.0 +*/ +#define NLOHMANN_DEFINE_TYPE_INTRUSIVE(Type, ...) \ + friend void to_json(nlohmann::json& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + friend void from_json(const nlohmann::json& nlohmann_json_j, Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +#define NLOHMANN_DEFINE_TYPE_INTRUSIVE_WITH_DEFAULT(Type, ...) \ + friend void to_json(nlohmann::json& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + friend void from_json(const nlohmann::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE +@since version 3.9.0 +*/ +#define NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(Type, ...) \ + inline void to_json(nlohmann::json& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + inline void from_json(const nlohmann::json& nlohmann_json_j, Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +#define NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE_WITH_DEFAULT(Type, ...) \ + inline void to_json(nlohmann::json& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + inline void from_json(const nlohmann::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + + +// inspired from https://stackoverflow.com/a/26745591 +// allows to call any std function as if (e.g. with begin): +// using std::begin; begin(x); +// +// it allows using the detected idiom to retrieve the return type +// of such an expression +#define NLOHMANN_CAN_CALL_STD_FUNC_IMPL(std_name) \ + namespace detail { \ + using std::std_name; \ + \ + template \ + using result_of_##std_name = decltype(std_name(std::declval()...)); \ + } \ + \ + namespace detail2 { \ + struct std_name##_tag \ + { \ + }; \ + \ + template \ + std_name##_tag std_name(T&&...); \ + \ + template \ + using result_of_##std_name = decltype(std_name(std::declval()...)); \ + \ + template \ + struct would_call_std_##std_name \ + { \ + static constexpr auto const value = ::nlohmann::detail:: \ + is_detected_exact::value; \ + }; \ + } /* namespace detail2 */ \ + \ + template \ + struct would_call_std_##std_name : detail2::would_call_std_##std_name \ + { \ + } + +#ifndef JSON_USE_IMPLICIT_CONVERSIONS + #define JSON_USE_IMPLICIT_CONVERSIONS 1 +#endif + +#if JSON_USE_IMPLICIT_CONVERSIONS + #define JSON_EXPLICIT +#else + #define JSON_EXPLICIT explicit +#endif + +#ifndef JSON_DISABLE_ENUM_SERIALIZATION + #define JSON_DISABLE_ENUM_SERIALIZATION 0 +#endif + +#ifndef JSON_USE_GLOBAL_UDLS + #define JSON_USE_GLOBAL_UDLS 1 +#endif + +#if JSON_HAS_THREE_WAY_COMPARISON + #include // partial_ordering +#endif + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/////////////////////////// +// JSON type enumeration // +/////////////////////////// + +/*! +@brief the JSON type enumeration + +This enumeration collects the different JSON types. It is internally used to +distinguish the stored values, and the functions @ref basic_json::is_null(), +@ref basic_json::is_object(), @ref basic_json::is_array(), +@ref basic_json::is_string(), @ref basic_json::is_boolean(), +@ref basic_json::is_number() (with @ref basic_json::is_number_integer(), +@ref basic_json::is_number_unsigned(), and @ref basic_json::is_number_float()), +@ref basic_json::is_discarded(), @ref basic_json::is_primitive(), and +@ref basic_json::is_structured() rely on it. + +@note There are three enumeration entries (number_integer, number_unsigned, and +number_float), because the library distinguishes these three types for numbers: +@ref basic_json::number_unsigned_t is used for unsigned integers, +@ref basic_json::number_integer_t is used for signed integers, and +@ref basic_json::number_float_t is used for floating-point numbers or to +approximate integers which do not fit in the limits of their respective type. + +@sa see @ref basic_json::basic_json(const value_t value_type) -- create a JSON +value with the default value for a given type + +@since version 1.0.0 +*/ +enum class value_t : std::uint8_t +{ + null, ///< null value + object, ///< object (unordered set of name/value pairs) + array, ///< array (ordered collection of values) + string, ///< string value + boolean, ///< boolean value + number_integer, ///< number value (signed integer) + number_unsigned, ///< number value (unsigned integer) + number_float, ///< number value (floating-point) + binary, ///< binary array (ordered collection of bytes) + discarded ///< discarded by the parser callback function +}; + +/*! +@brief comparison operator for JSON types + +Returns an ordering that is similar to Python: +- order: null < boolean < number < object < array < string < binary +- furthermore, each type is not smaller than itself +- discarded values are not comparable +- binary is represented as a b"" string in python and directly comparable to a + string; however, making a binary array directly comparable with a string would + be surprising behavior in a JSON file. + +@since version 1.0.0 +*/ +#if JSON_HAS_THREE_WAY_COMPARISON + inline std::partial_ordering operator<=>(const value_t lhs, const value_t rhs) noexcept // *NOPAD* +#else + inline bool operator<(const value_t lhs, const value_t rhs) noexcept +#endif +{ + static constexpr std::array order = {{ + 0 /* null */, 3 /* object */, 4 /* array */, 5 /* string */, + 1 /* boolean */, 2 /* integer */, 2 /* unsigned */, 2 /* float */, + 6 /* binary */ + } + }; + + const auto l_index = static_cast(lhs); + const auto r_index = static_cast(rhs); +#if JSON_HAS_THREE_WAY_COMPARISON + if (l_index < order.size() && r_index < order.size()) + { + return order[l_index] <=> order[r_index]; // *NOPAD* + } + return std::partial_ordering::unordered; +#else + return l_index < order.size() && r_index < order.size() && order[l_index] < order[r_index]; +#endif +} + +// GCC selects the built-in operator< over an operator rewritten from +// a user-defined spaceship operator +// Clang, MSVC, and ICC select the rewritten candidate +// (see GCC bug https://gcc.gnu.org/bugzilla/show_bug.cgi?id=105200) +#if JSON_HAS_THREE_WAY_COMPARISON && defined(__GNUC__) +inline bool operator<(const value_t lhs, const value_t rhs) noexcept +{ + return std::is_lt(lhs <=> rhs); // *NOPAD* +} +#endif + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/*! +@brief replace all occurrences of a substring by another string + +@param[in,out] s the string to manipulate; changed so that all + occurrences of @a f are replaced with @a t +@param[in] f the substring to replace with @a t +@param[in] t the string to replace @a f + +@pre The search string @a f must not be empty. **This precondition is +enforced with an assertion.** + +@since version 2.0.0 +*/ +template +inline void replace_substring(StringType& s, const StringType& f, + const StringType& t) +{ + JSON_ASSERT(!f.empty()); + for (auto pos = s.find(f); // find first occurrence of f + pos != StringType::npos; // make sure f was found + s.replace(pos, f.size(), t), // replace with t, and + pos = s.find(f, pos + t.size())) // find next occurrence of f + {} +} + +/*! + * @brief string escaping as described in RFC 6901 (Sect. 4) + * @param[in] s string to escape + * @return escaped string + * + * Note the order of escaping "~" to "~0" and "/" to "~1" is important. + */ +template +inline StringType escape(StringType s) +{ + replace_substring(s, StringType{"~"}, StringType{"~0"}); + replace_substring(s, StringType{"/"}, StringType{"~1"}); + return s; +} + +/*! + * @brief string unescaping as described in RFC 6901 (Sect. 4) + * @param[in] s string to unescape + * @return unescaped string + * + * Note the order of escaping "~1" to "/" and "~0" to "~" is important. + */ +template +static void unescape(StringType& s) +{ + replace_substring(s, StringType{"~1"}, StringType{"/"}); + replace_substring(s, StringType{"~0"}, StringType{"~"}); +} + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // size_t + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/// struct to capture the start position of the current token +struct position_t +{ + /// the total number of characters read + std::size_t chars_read_total = 0; + /// the number of characters read in the current line + std::size_t chars_read_current_line = 0; + /// the number of lines read + std::size_t lines_read = 0; + + /// conversion to size_t to preserve SAX interface + constexpr operator size_t() const + { + return chars_read_total; + } +}; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-FileCopyrightText: 2018 The Abseil Authors +// SPDX-License-Identifier: MIT + + + +#include // array +#include // size_t +#include // conditional, enable_if, false_type, integral_constant, is_constructible, is_integral, is_same, remove_cv, remove_reference, true_type +#include // index_sequence, make_index_sequence, index_sequence_for + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template +using uncvref_t = typename std::remove_cv::type>::type; + +#ifdef JSON_HAS_CPP_14 + +// the following utilities are natively available in C++14 +using std::enable_if_t; +using std::index_sequence; +using std::make_index_sequence; +using std::index_sequence_for; + +#else + +// alias templates to reduce boilerplate +template +using enable_if_t = typename std::enable_if::type; + +// The following code is taken from https://github.com/abseil/abseil-cpp/blob/10cb35e459f5ecca5b2ff107635da0bfa41011b4/absl/utility/utility.h +// which is part of Google Abseil (https://github.com/abseil/abseil-cpp), licensed under the Apache License 2.0. + +//// START OF CODE FROM GOOGLE ABSEIL + +// integer_sequence +// +// Class template representing a compile-time integer sequence. An instantiation +// of `integer_sequence` has a sequence of integers encoded in its +// type through its template arguments (which is a common need when +// working with C++11 variadic templates). `absl::integer_sequence` is designed +// to be a drop-in replacement for C++14's `std::integer_sequence`. +// +// Example: +// +// template< class T, T... Ints > +// void user_function(integer_sequence); +// +// int main() +// { +// // user_function's `T` will be deduced to `int` and `Ints...` +// // will be deduced to `0, 1, 2, 3, 4`. +// user_function(make_integer_sequence()); +// } +template +struct integer_sequence +{ + using value_type = T; + static constexpr std::size_t size() noexcept + { + return sizeof...(Ints); + } +}; + +// index_sequence +// +// A helper template for an `integer_sequence` of `size_t`, +// `absl::index_sequence` is designed to be a drop-in replacement for C++14's +// `std::index_sequence`. +template +using index_sequence = integer_sequence; + +namespace utility_internal +{ + +template +struct Extend; + +// Note that SeqSize == sizeof...(Ints). It's passed explicitly for efficiency. +template +struct Extend, SeqSize, 0> +{ + using type = integer_sequence < T, Ints..., (Ints + SeqSize)... >; +}; + +template +struct Extend, SeqSize, 1> +{ + using type = integer_sequence < T, Ints..., (Ints + SeqSize)..., 2 * SeqSize >; +}; + +// Recursion helper for 'make_integer_sequence'. +// 'Gen::type' is an alias for 'integer_sequence'. +template +struct Gen +{ + using type = + typename Extend < typename Gen < T, N / 2 >::type, N / 2, N % 2 >::type; +}; + +template +struct Gen +{ + using type = integer_sequence; +}; + +} // namespace utility_internal + +// Compile-time sequences of integers + +// make_integer_sequence +// +// This template alias is equivalent to +// `integer_sequence`, and is designed to be a drop-in +// replacement for C++14's `std::make_integer_sequence`. +template +using make_integer_sequence = typename utility_internal::Gen::type; + +// make_index_sequence +// +// This template alias is equivalent to `index_sequence<0, 1, ..., N-1>`, +// and is designed to be a drop-in replacement for C++14's +// `std::make_index_sequence`. +template +using make_index_sequence = make_integer_sequence; + +// index_sequence_for +// +// Converts a typename pack into an index sequence of the same length, and +// is designed to be a drop-in replacement for C++14's +// `std::index_sequence_for()` +template +using index_sequence_for = make_index_sequence; + +//// END OF CODE FROM GOOGLE ABSEIL + +#endif + +// dispatch utility (taken from ranges-v3) +template struct priority_tag : priority_tag < N - 1 > {}; +template<> struct priority_tag<0> {}; + +// taken from ranges-v3 +template +struct static_const +{ + static JSON_INLINE_VARIABLE constexpr T value{}; +}; + +#ifndef JSON_HAS_CPP_17 + template + constexpr T static_const::value; +#endif + +template +inline constexpr std::array make_array(Args&& ... args) +{ + return std::array {{static_cast(std::forward(args))...}}; +} + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // numeric_limits +#include // false_type, is_constructible, is_integral, is_same, true_type +#include // declval +#include // tuple + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // random_access_iterator_tag + +// #include + +// #include + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template +struct iterator_types {}; + +template +struct iterator_types < + It, + void_t> +{ + using difference_type = typename It::difference_type; + using value_type = typename It::value_type; + using pointer = typename It::pointer; + using reference = typename It::reference; + using iterator_category = typename It::iterator_category; +}; + +// This is required as some compilers implement std::iterator_traits in a way that +// doesn't work with SFINAE. See https://github.com/nlohmann/json/issues/1341. +template +struct iterator_traits +{ +}; + +template +struct iterator_traits < T, enable_if_t < !std::is_pointer::value >> + : iterator_types +{ +}; + +template +struct iterator_traits::value>> +{ + using iterator_category = std::random_access_iterator_tag; + using value_type = T; + using difference_type = ptrdiff_t; + using pointer = T*; + using reference = T&; +}; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN + +NLOHMANN_CAN_CALL_STD_FUNC_IMPL(begin); + +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN + +NLOHMANN_CAN_CALL_STD_FUNC_IMPL(end); + +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.11.2 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013-2022 Niels Lohmann +// SPDX-License-Identifier: MIT + +#ifndef INCLUDE_NLOHMANN_JSON_FWD_HPP_ + #define INCLUDE_NLOHMANN_JSON_FWD_HPP_ + + #include // int64_t, uint64_t + #include // map + #include // allocator + #include // string + #include // vector + + // #include + + + /*! + @brief namespace for Niels Lohmann + @see https://github.com/nlohmann + @since version 1.0.0 + */ + NLOHMANN_JSON_NAMESPACE_BEGIN + + /*! + @brief default JSONSerializer template argument + + This serializer ignores the template arguments and uses ADL + ([argument-dependent lookup](https://en.cppreference.com/w/cpp/language/adl)) + for serialization. + */ + template + struct adl_serializer; + + /// a class to store JSON values + /// @sa https://json.nlohmann.me/api/basic_json/ + template class ObjectType = + std::map, + template class ArrayType = std::vector, + class StringType = std::string, class BooleanType = bool, + class NumberIntegerType = std::int64_t, + class NumberUnsignedType = std::uint64_t, + class NumberFloatType = double, + template class AllocatorType = std::allocator, + template class JSONSerializer = + adl_serializer, + class BinaryType = std::vector, // cppcheck-suppress syntaxError + class CustomBaseClass = void> + class basic_json; + + /// @brief JSON Pointer defines a string syntax for identifying a specific value within a JSON document + /// @sa https://json.nlohmann.me/api/json_pointer/ + template + class json_pointer; + + /*! + @brief default specialization + @sa https://json.nlohmann.me/api/json/ + */ + using json = basic_json<>; + + /// @brief a minimal map-like container that preserves insertion order + /// @sa https://json.nlohmann.me/api/ordered_map/ + template + struct ordered_map; + + /// @brief specialization that maintains the insertion order of object keys + /// @sa https://json.nlohmann.me/api/ordered_json/ + using ordered_json = basic_json; + + NLOHMANN_JSON_NAMESPACE_END + +#endif // INCLUDE_NLOHMANN_JSON_FWD_HPP_ + + +NLOHMANN_JSON_NAMESPACE_BEGIN +/*! +@brief detail namespace with internal helper functions + +This namespace collects functions that should not be exposed, +implementations of some @ref basic_json methods, and meta-programming helpers. + +@since version 2.1.0 +*/ +namespace detail +{ + +///////////// +// helpers // +///////////// + +// Note to maintainers: +// +// Every trait in this file expects a non CV-qualified type. +// The only exceptions are in the 'aliases for detected' section +// (i.e. those of the form: decltype(T::member_function(std::declval()))) +// +// In this case, T has to be properly CV-qualified to constraint the function arguments +// (e.g. to_json(BasicJsonType&, const T&)) + +template struct is_basic_json : std::false_type {}; + +NLOHMANN_BASIC_JSON_TPL_DECLARATION +struct is_basic_json : std::true_type {}; + +// used by exceptions create() member functions +// true_type for pointer to possibly cv-qualified basic_json or std::nullptr_t +// false_type otherwise +template +struct is_basic_json_context : + std::integral_constant < bool, + is_basic_json::type>::type>::value + || std::is_same::value > +{}; + +////////////////////// +// json_ref helpers // +////////////////////// + +template +class json_ref; + +template +struct is_json_ref : std::false_type {}; + +template +struct is_json_ref> : std::true_type {}; + +////////////////////////// +// aliases for detected // +////////////////////////// + +template +using mapped_type_t = typename T::mapped_type; + +template +using key_type_t = typename T::key_type; + +template +using value_type_t = typename T::value_type; + +template +using difference_type_t = typename T::difference_type; + +template +using pointer_t = typename T::pointer; + +template +using reference_t = typename T::reference; + +template +using iterator_category_t = typename T::iterator_category; + +template +using to_json_function = decltype(T::to_json(std::declval()...)); + +template +using from_json_function = decltype(T::from_json(std::declval()...)); + +template +using get_template_function = decltype(std::declval().template get()); + +// trait checking if JSONSerializer::from_json(json const&, udt&) exists +template +struct has_from_json : std::false_type {}; + +// trait checking if j.get is valid +// use this trait instead of std::is_constructible or std::is_convertible, +// both rely on, or make use of implicit conversions, and thus fail when T +// has several constructors/operator= (see https://github.com/nlohmann/json/issues/958) +template +struct is_getable +{ + static constexpr bool value = is_detected::value; +}; + +template +struct has_from_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +// This trait checks if JSONSerializer::from_json(json const&) exists +// this overload is used for non-default-constructible user-defined-types +template +struct has_non_default_from_json : std::false_type {}; + +template +struct has_non_default_from_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +// This trait checks if BasicJsonType::json_serializer::to_json exists +// Do not evaluate the trait when T is a basic_json type, to avoid template instantiation infinite recursion. +template +struct has_to_json : std::false_type {}; + +template +struct has_to_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +template +using detect_key_compare = typename T::key_compare; + +template +struct has_key_compare : std::integral_constant::value> {}; + +// obtains the actual object key comparator +template +struct actual_object_comparator +{ + using object_t = typename BasicJsonType::object_t; + using object_comparator_t = typename BasicJsonType::default_object_comparator_t; + using type = typename std::conditional < has_key_compare::value, + typename object_t::key_compare, object_comparator_t>::type; +}; + +template +using actual_object_comparator_t = typename actual_object_comparator::type; + +/////////////////// +// is_ functions // +/////////////////// + +// https://en.cppreference.com/w/cpp/types/conjunction +template struct conjunction : std::true_type { }; +template struct conjunction : B { }; +template +struct conjunction +: std::conditional(B::value), conjunction, B>::type {}; + +// https://en.cppreference.com/w/cpp/types/negation +template struct negation : std::integral_constant < bool, !B::value > { }; + +// Reimplementation of is_constructible and is_default_constructible, due to them being broken for +// std::pair and std::tuple until LWG 2367 fix (see https://cplusplus.github.io/LWG/lwg-defects.html#2367). +// This causes compile errors in e.g. clang 3.5 or gcc 4.9. +template +struct is_default_constructible : std::is_default_constructible {}; + +template +struct is_default_constructible> + : conjunction, is_default_constructible> {}; + +template +struct is_default_constructible> + : conjunction, is_default_constructible> {}; + +template +struct is_default_constructible> + : conjunction...> {}; + +template +struct is_default_constructible> + : conjunction...> {}; + + +template +struct is_constructible : std::is_constructible {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + + +template +struct is_iterator_traits : std::false_type {}; + +template +struct is_iterator_traits> +{ + private: + using traits = iterator_traits; + + public: + static constexpr auto value = + is_detected::value && + is_detected::value && + is_detected::value && + is_detected::value && + is_detected::value; +}; + +template +struct is_range +{ + private: + using t_ref = typename std::add_lvalue_reference::type; + + using iterator = detected_t; + using sentinel = detected_t; + + // to be 100% correct, it should use https://en.cppreference.com/w/cpp/iterator/input_or_output_iterator + // and https://en.cppreference.com/w/cpp/iterator/sentinel_for + // but reimplementing these would be too much work, as a lot of other concepts are used underneath + static constexpr auto is_iterator_begin = + is_iterator_traits>::value; + + public: + static constexpr bool value = !std::is_same::value && !std::is_same::value && is_iterator_begin; +}; + +template +using iterator_t = enable_if_t::value, result_of_begin())>>; + +template +using range_value_t = value_type_t>>; + +// The following implementation of is_complete_type is taken from +// https://blogs.msdn.microsoft.com/vcblog/2015/12/02/partial-support-for-expression-sfinae-in-vs-2015-update-1/ +// and is written by Xiang Fan who agreed to using it in this library. + +template +struct is_complete_type : std::false_type {}; + +template +struct is_complete_type : std::true_type {}; + +template +struct is_compatible_object_type_impl : std::false_type {}; + +template +struct is_compatible_object_type_impl < + BasicJsonType, CompatibleObjectType, + enable_if_t < is_detected::value&& + is_detected::value >> +{ + using object_t = typename BasicJsonType::object_t; + + // macOS's is_constructible does not play well with nonesuch... + static constexpr bool value = + is_constructible::value && + is_constructible::value; +}; + +template +struct is_compatible_object_type + : is_compatible_object_type_impl {}; + +template +struct is_constructible_object_type_impl : std::false_type {}; + +template +struct is_constructible_object_type_impl < + BasicJsonType, ConstructibleObjectType, + enable_if_t < is_detected::value&& + is_detected::value >> +{ + using object_t = typename BasicJsonType::object_t; + + static constexpr bool value = + (is_default_constructible::value && + (std::is_move_assignable::value || + std::is_copy_assignable::value) && + (is_constructible::value && + std::is_same < + typename object_t::mapped_type, + typename ConstructibleObjectType::mapped_type >::value)) || + (has_from_json::value || + has_non_default_from_json < + BasicJsonType, + typename ConstructibleObjectType::mapped_type >::value); +}; + +template +struct is_constructible_object_type + : is_constructible_object_type_impl {}; + +template +struct is_compatible_string_type +{ + static constexpr auto value = + is_constructible::value; +}; + +template +struct is_constructible_string_type +{ + // launder type through decltype() to fix compilation failure on ICPC +#ifdef __INTEL_COMPILER + using laundered_type = decltype(std::declval()); +#else + using laundered_type = ConstructibleStringType; +#endif + + static constexpr auto value = + conjunction < + is_constructible, + is_detected_exact>::value; +}; + +template +struct is_compatible_array_type_impl : std::false_type {}; + +template +struct is_compatible_array_type_impl < + BasicJsonType, CompatibleArrayType, + enable_if_t < + is_detected::value&& + is_iterator_traits>>::value&& +// special case for types like std::filesystem::path whose iterator's value_type are themselves +// c.f. https://github.com/nlohmann/json/pull/3073 + !std::is_same>::value >> +{ + static constexpr bool value = + is_constructible>::value; +}; + +template +struct is_compatible_array_type + : is_compatible_array_type_impl {}; + +template +struct is_constructible_array_type_impl : std::false_type {}; + +template +struct is_constructible_array_type_impl < + BasicJsonType, ConstructibleArrayType, + enable_if_t::value >> + : std::true_type {}; + +template +struct is_constructible_array_type_impl < + BasicJsonType, ConstructibleArrayType, + enable_if_t < !std::is_same::value&& + !is_compatible_string_type::value&& + is_default_constructible::value&& +(std::is_move_assignable::value || + std::is_copy_assignable::value)&& +is_detected::value&& +is_iterator_traits>>::value&& +is_detected::value&& +// special case for types like std::filesystem::path whose iterator's value_type are themselves +// c.f. https://github.com/nlohmann/json/pull/3073 +!std::is_same>::value&& + is_complete_type < + detected_t>::value >> +{ + using value_type = range_value_t; + + static constexpr bool value = + std::is_same::value || + has_from_json::value || + has_non_default_from_json < + BasicJsonType, + value_type >::value; +}; + +template +struct is_constructible_array_type + : is_constructible_array_type_impl {}; + +template +struct is_compatible_integer_type_impl : std::false_type {}; + +template +struct is_compatible_integer_type_impl < + RealIntegerType, CompatibleNumberIntegerType, + enable_if_t < std::is_integral::value&& + std::is_integral::value&& + !std::is_same::value >> +{ + // is there an assert somewhere on overflows? + using RealLimits = std::numeric_limits; + using CompatibleLimits = std::numeric_limits; + + static constexpr auto value = + is_constructible::value && + CompatibleLimits::is_integer && + RealLimits::is_signed == CompatibleLimits::is_signed; +}; + +template +struct is_compatible_integer_type + : is_compatible_integer_type_impl {}; + +template +struct is_compatible_type_impl: std::false_type {}; + +template +struct is_compatible_type_impl < + BasicJsonType, CompatibleType, + enable_if_t::value >> +{ + static constexpr bool value = + has_to_json::value; +}; + +template +struct is_compatible_type + : is_compatible_type_impl {}; + +template +struct is_constructible_tuple : std::false_type {}; + +template +struct is_constructible_tuple> : conjunction...> {}; + +template +struct is_json_iterator_of : std::false_type {}; + +template +struct is_json_iterator_of : std::true_type {}; + +template +struct is_json_iterator_of : std::true_type +{}; + +// checks if a given type T is a template specialization of Primary +template