From 36e5192c33be43bd236ae22b67b88757931a53dd Mon Sep 17 00:00:00 2001 From: Mats Nilsson Date: Mon, 3 Feb 2025 08:33:01 +0100 Subject: [PATCH 1/7] Fix trailing whitespace --- .../EsminiAdapter/src/esminiadapter.cpp | 32 ++++++------- atos/modules/ObjectControl/CMakeLists.txt | 3 +- .../ObjectControl/src/objectcontrol.cpp | 46 +++++++++---------- 3 files changed, 40 insertions(+), 41 deletions(-) diff --git a/atos/modules/EsminiAdapter/src/esminiadapter.cpp b/atos/modules/EsminiAdapter/src/esminiadapter.cpp index fbce01a01..6b4da4917 100644 --- a/atos/modules/EsminiAdapter/src/esminiadapter.cpp +++ b/atos/modules/EsminiAdapter/src/esminiadapter.cpp @@ -65,7 +65,7 @@ std::filesystem::path EsminiAdapter::getOpenDriveFile() { std::filesystem::path odrFilePath; if (SE_GetODRFilename() != nullptr) { - odrFilePath = std::filesystem::path(SE_GetODRFilename()); + odrFilePath = std::filesystem::path(SE_GetODRFilename()); RCLCPP_INFO(me->get_logger(), "Got ODR file %s from scenario", odrFilePath.string().c_str()); } else { @@ -101,7 +101,7 @@ std::shared_ptr EsminiAdapter::instance() { me->connectedObjectIdsSub = ROSChannels::ConnectedObjectIds::Sub(*me,&EsminiAdapter::onConnectedObjectIdsMessage); me->exitSub = ROSChannels::Exit::Sub(*me,&EsminiAdapter::onStaticExitMessage); me->stateChangeSub = ROSChannels::StateChange::Sub(*me,&EsminiAdapter::onStaticStateChangeMessage); - + } return me; } @@ -113,7 +113,7 @@ std::shared_ptr EsminiAdapter::instance() { void EsminiAdapter::onConnectedObjectIdsMessage(const ConnectedObjectIds::message_type::SharedPtr msg) { for (uint32_t id : msg->ids) { if (me->monrSubscribers.find(id) == me->monrSubscribers.end()){ - me->monrSubscribers[id] = std::make_shared(*me, id, std::bind(&EsminiAdapter::onMonitorMessage, me, _1, id)); + me->monrSubscribers[id] = std::make_shared(*me, id, std::bind(&EsminiAdapter::onMonitorMessage, me, _1, id)); } } } @@ -122,7 +122,7 @@ void EsminiAdapter::onConnectedObjectIdsMessage(const ConnectedObjectIds::messag * @brief To ensure that EsminiAdapter follows the states, we execute actions only when going from IDLE to INITIALIZED, * from ARMED to RUNNING and from any state to ABORTING. We do this instead of subscribing to "/init", "/start", etc., * because we only want to execute the actions once when changing to these states. - * + * * @param msg StateChange message */ void EsminiAdapter::onStaticStateChangeMessage(const ROSChannels::StateChange::message_type::SharedPtr msg) { @@ -163,7 +163,7 @@ void EsminiAdapter::fetchOSCFilePath() if (done.get_future().wait_for(250ms) == std::future_status::timeout) { RCLCPP_ERROR(me->get_logger(), "Failed to fetch open scenario file path"); } - + } void EsminiAdapter::onStaticExitMessage(const ROSChannels::Exit::message_type::SharedPtr) @@ -244,7 +244,7 @@ void EsminiAdapter::onMonitorMessage(const Monitor::message_type::SharedPtr monr if (auto idMapping = atosIdToEsminiId.find(ATOSObjectId); idMapping != atosIdToEsminiId.end()) { reportObjectPosition(monr, idMapping->second); // Report object position to esmini SE_Step(); // Advance the "simulation world"-time - } + } else { RCLCPP_WARN(me->get_logger(), "Received MONR message for object with ATOS Object ID %d, but no such object exists in the scenario", ATOSObjectId); } @@ -388,10 +388,10 @@ std::string EsminiAdapter::projStrFromGeoReference(RM_GeoReference& geoRef) { /*! * \brief Returns object states for each timestep by simulating the loaded scenario. - * The simulation is stopped if there is no vehicle movement and at least + * The simulation is stopped if there is no vehicle movement and at least * MIN_SCENARIO_TIME has passed or if more than MAX_SCENARIO_TIME has passed. * Inspired by ScenarioGateway::WriteStatesToFile from esmini lib. - * + * * \param timeStep Time step to use for generating the trajectories * \param endTime End time of the simulation * \param states The return map of ids mapping to the respective object states at different timesteps @@ -425,7 +425,7 @@ void EsminiAdapter::getObjectStates( if (SE_GetQuitFlag() != 0) { break; } - + SE_StepDT(timeStep); accumTime += timeStep; for (int j = 0; j < SE_GetNumberOfObjects(); j++){ @@ -479,7 +479,7 @@ std::map EsminiAdapter::extractTrajectories( /*! * \brief Initialize the esmini simulator and perform subsequent setup tasks. - * Can be called many times, each time the test is initialized. + * Can be called many times, each time the test is initialized. */ void EsminiAdapter::runEsminiSimulation() { @@ -503,7 +503,7 @@ void EsminiAdapter::runEsminiSimulation() throw std::runtime_error(std::string("Failed to initialize with odr file ").append(odrFile)); } - + // Call RM_GetOpenDriveGeoReference to get the RM_GeoReference struct RM_GeoReference geoRef; if (RM_GetOpenDriveGeoReference(&geoRef) == 0) { @@ -517,13 +517,13 @@ void EsminiAdapter::runEsminiSimulation() me->testOrigin.position.altitude = llh_0[2]; me->testOriginSet = true; - std::string projStringTo = "+proj=tmerc +lat_0=" + std::to_string(llh_0[0]) + - " +lon_0=" + std::to_string(llh_0[1]) + + std::string projStringTo = "+proj=tmerc +lat_0=" + std::to_string(llh_0[0]) + + " +lon_0=" + std::to_string(llh_0[1]) + " +datum="+ toDatum + " +units=m +no_defs"; me->crsTransformation = std::make_shared(projStringFrom, projStringTo); me->applyTrajTransform = true; - } + } catch (std::exception& e) { RCLCPP_ERROR(me->get_logger(), e.what()); return; @@ -565,7 +565,7 @@ void EsminiAdapter::runEsminiSimulation() me->atosObjectIdToTraj.emplace(atos_id, traj); me->atosIdToEsminiId.emplace(atos_id, esminiId); RCLCPP_INFO(me->get_logger(), "Extracted trajectory for object %s with size %d", objectName, traj.points.size()); - + me->pathPublishers.emplace(atos_id, ROSChannels::Path::Pub(*me, atos_id)); me->pathPublishers.at(atos_id).publish(traj.toPath()); std::array llh_0 = {me->testOrigin.position.latitude, me->testOrigin.position.longitude, me->testOrigin.position.altitude}; @@ -632,4 +632,4 @@ int EsminiAdapter::initializeModule() { std::bind(&EsminiAdapter::onRequestTestOrigin, _1, _2)); return retval; -} \ No newline at end of file +} diff --git a/atos/modules/ObjectControl/CMakeLists.txt b/atos/modules/ObjectControl/CMakeLists.txt index c08aed41f..2b04017a9 100644 --- a/atos/modules/ObjectControl/CMakeLists.txt +++ b/atos/modules/ObjectControl/CMakeLists.txt @@ -61,7 +61,7 @@ add_executable(${OBJECT_CONTROL_TARGET} ${CMAKE_CURRENT_SOURCE_DIR}/src/objectcontrol.cpp ) # Link project executable to util libraries -target_link_libraries(${OBJECT_CONTROL_TARGET} +target_link_libraries(${OBJECT_CONTROL_TARGET} ${TIME_LIBRARY} ${COREUTILS_LIBRARY} ${FILESYSTEM_LIBRARY} @@ -97,4 +97,3 @@ install(TARGETS ${OBJECT_CONTROL_TARGET} ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} ) - diff --git a/atos/modules/ObjectControl/src/objectcontrol.cpp b/atos/modules/ObjectControl/src/objectcontrol.cpp index a425a0dee..1efdf58e4 100644 --- a/atos/modules/ObjectControl/src/objectcontrol.cpp +++ b/atos/modules/ObjectControl/src/objectcontrol.cpp @@ -41,7 +41,7 @@ ObjectControl::ObjectControl(std::shared_ptrstate->asNumber(); @@ -152,7 +152,7 @@ void ObjectControl::onArmMessage(const Arm::message_type::SharedPtr){ stateChangePub.publish(stateChangeMsg); } -void ObjectControl::onDisarmMessage(const Disarm::message_type::SharedPtr){ +void ObjectControl::onDisarmMessage(const Disarm::message_type::SharedPtr){ COMMAND cmd = COMM_DISARM; atos_interfaces::msg::StateChange stateChangeMsg = atos_interfaces::msg::StateChange(); stateChangeMsg.prev_state = this->state->asNumber(); @@ -163,7 +163,7 @@ void ObjectControl::onDisarmMessage(const Disarm::message_type::SharedPtr){ stateChangePub.publish(stateChangeMsg); } -void ObjectControl::onStartMessage(const Start::message_type::SharedPtr){ +void ObjectControl::onStartMessage(const Start::message_type::SharedPtr){ COMMAND cmd = COMM_STRT; atos_interfaces::msg::StateChange stateChangeMsg = atos_interfaces::msg::StateChange(); stateChangeMsg.prev_state = this->state->asNumber(); @@ -182,7 +182,7 @@ void ObjectControl::onStartObjectMessage(const StartObject::message_type::Shared this->tryHandleMessage(f_try,f_catch, StartObject::topicName, get_logger()); } -void ObjectControl::onDisconnectMessage(const Disconnect::message_type::SharedPtr){ +void ObjectControl::onDisconnectMessage(const Disconnect::message_type::SharedPtr){ COMMAND cmd = COMM_DISCONNECT; atos_interfaces::msg::StateChange stateChangeMsg = atos_interfaces::msg::StateChange(); stateChangeMsg.prev_state = this->state->asNumber(); @@ -202,14 +202,14 @@ void ObjectControl::onStopMessage(const Stop::message_type::SharedPtr){ failurePub.publish(msgCtr1(cmd)); scnAbortPub.publish(Abort::message_type()); }; - this->tryHandleMessage(f_try,f_catch, Stop::topicName, get_logger()); + this->tryHandleMessage(f_try,f_catch, Stop::topicName, get_logger()); stateChangeMsg.current_state = this->state->asNumber(); stateChangePub.publish(stateChangeMsg); } /** * @brief Resets the test objects to the scenario starting positions - * + * * @param msg Trigger message for resetting test objects (std_msgs/msg/Empty) */ void ObjectControl::onResetTestObjectsMessage(const ResetTestObjects::message_type::SharedPtr) { @@ -221,7 +221,7 @@ void ObjectControl::onResetTestObjectsMessage(const ResetTestObjects::message_ty /** * @brief Reloads the object settings from the configuration file - * + * * @param msg Trigger message for reloading object settings (std_msgs/msg/Empty) */ void ObjectControl::onReloadObjectSettingsMessage(const ReloadObjectSettings::message_type::SharedPtr) { @@ -258,7 +258,7 @@ void ObjectControl::onRemoteControlEnableMessage(const RemoteControlEnable::mess auto f_catch = [&]() { failurePub.publish(msgCtr1(cmd)); }; - this->tryHandleMessage(f_try,f_catch, RemoteControlEnable::topicName, get_logger()); + this->tryHandleMessage(f_try,f_catch, RemoteControlEnable::topicName, get_logger()); } void ObjectControl::onRemoteControlDisableMessage(const RemoteControlDisable::message_type::SharedPtr){ @@ -267,7 +267,7 @@ void ObjectControl::onRemoteControlDisableMessage(const RemoteControlDisable::me auto f_catch = [&]() { failurePub.publish(msgCtr1(cmd)); }; - this->tryHandleMessage(f_try,f_catch, RemoteControlDisable::topicName, get_logger()); + this->tryHandleMessage(f_try,f_catch, RemoteControlDisable::topicName, get_logger()); } void ObjectControl::onControlSignalMessage(const ControlSignal::message_type::SharedPtr csp){ @@ -460,7 +460,7 @@ void ObjectControl::loadObjectFiles() { catch (std::invalid_argument& e) { RCLCPP_ERROR(get_logger(), e.what()); errors.push_back(e); - } + } } } @@ -473,7 +473,7 @@ void ObjectControl::loadObjectFiles() { objects.at(sourceID)->setObjectConfig(conf); } } - + if (!errors.empty()) { objects.clear(); std::ostringstream ostr; @@ -648,7 +648,7 @@ OsiHandler::LocalObjectGroundTruth_t ObjectControl::buildOSILocalGroundTruth( return gt; } -// TODO (NOT WORKING ATM!): Replace this with a subscriber that listens for monr messages. +// TODO (NOT WORKING ATM!): Replace this with a subscriber that listens for monr messages. void ObjectControl::injectObjectData(const MonitorMessage &monr) { if (!objects.at(monr.first)->getObjectConfig().getInjectionMap().targetIDs.empty()) { std::chrono::system_clock::time_point ts; @@ -798,7 +798,7 @@ void ObjectControl::disarmObjects() { /** * @brief Resets the scenario by offering return trajectories for all objects - * + * * @param isResetting state-flag to indicate if the reset procedure is currently running */ void ObjectControl::resetTestObjects() { @@ -817,7 +817,7 @@ void ObjectControl::resetTestObjects() { /** * @brief Reloads the scenario trajectories for all objects - * + * * @param isResetting state-flag to indicate if the reset procedure is currently running */ void ObjectControl::reloadScenarioTrajectories() { @@ -836,7 +836,7 @@ void ObjectControl::reloadScenarioTrajectories() { /** * @brief Republishes the trajectory paths for a given object - * + * * @param id the object id */ void ObjectControl::republishTrajectoryPaths(uint32_t id){ @@ -854,7 +854,7 @@ void ObjectControl::republishTrajectoryPaths(uint32_t id){ /** * @brief Callback function for the trajectory service call. Sets the new trajectory for the object in ATOS and sends it to the object - * + * * @param future the future object containing the response from the trajectory service call */ void ObjectControl::trajectoryCallback(const rclcpp::Client::SharedFuture future) { @@ -878,7 +878,7 @@ void ObjectControl::trajectoryCallback(const rclcpp::Client::SharedFuture future) { @@ -902,7 +902,7 @@ void ObjectControl::returnTrajectoryCallback(const rclcpp::Client Object " << index << ": \n" - << "\t - ID: " << object.first << "\n" + << "\t - ID: " << object.first << "\n" << "\t - IP: " << ip_str << "\n" << "\t - Origin: (" << testObject->getOrigin().latitude_deg << ", " << testObject->getOrigin().longitude_deg << ", " << testObject->getOrigin().altitude_m << ")\n" << "\t - Trajectory size: " << testObject->getTrajectory().size() << "\n" @@ -1079,4 +1079,4 @@ void ObjectControl::publishScenarioInfoToJournal() { params << "Parameters from params.yaml: \n" << ifs.rdbuf(); JournalRecordData(JOURNAL_RECORD_STRING, params.str().c_str()); JournalRecordData(JOURNAL_RECORD_STRING, "--- End of Scenario Info ---"); -} \ No newline at end of file +} From 4e587904f4d8ac62313c677735675e7a816dd00f Mon Sep 17 00:00:00 2001 From: Mats Nilsson Date: Mon, 3 Feb 2025 10:10:32 +0100 Subject: [PATCH 2/7] Make ObjectControl a class enum --- atos/modules/ObjectControl/inc/objectcontrol.hpp | 11 ++++++----- atos/modules/ObjectControl/src/states/idle.cpp | 4 ++-- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/atos/modules/ObjectControl/inc/objectcontrol.hpp b/atos/modules/ObjectControl/inc/objectcontrol.hpp index d85db375f..8514f5d70 100644 --- a/atos/modules/ObjectControl/inc/objectcontrol.hpp +++ b/atos/modules/ObjectControl/inc/objectcontrol.hpp @@ -78,6 +78,12 @@ namespace AbsoluteKinematics { class RemoteControlled; } +enum class ControlMode : int { + AbsoluteKinematics, + RelativeKinematics, +}; + + /*! * \brief The ObjectControl class is intended as an overarching device * used to control a scenario. No behaviour is implemented in it @@ -123,11 +129,6 @@ class ObjectControl : public Module public: ObjectControl(std::shared_ptr); - typedef enum { - RELATIVE_KINEMATICS, //!< Scenario executed relative to immobile VUT - ABSOLUTE_KINEMATICS //!< Scenario executed relative to earth-fixed point - } ControlMode; - typedef struct { unsigned int numberOfTargets; diff --git a/atos/modules/ObjectControl/src/states/idle.cpp b/atos/modules/ObjectControl/src/states/idle.cpp index c5d0074a8..6f28f24ff 100644 --- a/atos/modules/ObjectControl/src/states/idle.cpp +++ b/atos/modules/ObjectControl/src/states/idle.cpp @@ -28,11 +28,11 @@ void AbstractKinematics::Idle::initializeRequest( try { auto anchorID = handler.getAnchorObjectID(); handler.transformScenarioRelativeTo(anchorID); - handler.controlMode = ObjectControl::RELATIVE_KINEMATICS; + handler.controlMode = ControlMode::RelativeKinematics; setState(handler, new RelativeKinematics::Initialized); RCLCPP_INFO(handler.get_logger(), "Relative control mode enabled"); } catch (std::invalid_argument&) { - handler.controlMode = ObjectControl::ABSOLUTE_KINEMATICS; + handler.controlMode = ControlMode::AbsoluteKinematics; setState(handler, new AbsoluteKinematics::Initialized); RCLCPP_INFO(handler.get_logger(), "Absolute control mode enabled"); } From 0dafba92155d2083f1ea23baa3a3b0fea57a43d3 Mon Sep 17 00:00:00 2001 From: Mats Nilsson Date: Mon, 3 Feb 2025 15:45:54 +0100 Subject: [PATCH 3/7] Add boost::sml --- atos/modules/ObjectControl/inc/sml.hpp | 2900 ++++++++++++++++++++++++ 1 file changed, 2900 insertions(+) create mode 100644 atos/modules/ObjectControl/inc/sml.hpp diff --git a/atos/modules/ObjectControl/inc/sml.hpp b/atos/modules/ObjectControl/inc/sml.hpp new file mode 100644 index 000000000..ca66764b4 --- /dev/null +++ b/atos/modules/ObjectControl/inc/sml.hpp @@ -0,0 +1,2900 @@ +// +// Copyright (c) 2016-2024 Kris Jusiak (kris at jusiak dot net) +// +// Distributed under the Boost Software License, Version 1.0. +// (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) +// +#ifndef BOOST_SML_HPP +#define BOOST_SML_HPP +#if (__cplusplus < 201305L && _MSC_VER < 1900) +#error "[Boost::ext].SML requires C++14 support (Clang-3.4+, GCC-5.1+, MSVC-2015+)" +#else +#if defined(__ICCARM__) && __IAR_SYSTEMS_ICC__ < 8 +#error "[Boost::ext].SML requires C++14 support (IAR C/C++ ARM 8.1+)" +#endif +#define BOOST_SML_VERSION 1'1'11 +#define BOOST_SML_NAMESPACE_BEGIN \ + namespace boost { \ + inline namespace ext { \ + namespace sml { \ + inline namespace v1_1_11 { +#define BOOST_SML_NAMESPACE_END \ + } \ + } \ + } \ + } +#if defined(__clang__) +#define __BOOST_SML_UNUSED __attribute__((unused)) +#define __BOOST_SML_VT_INIT \ + {} +#if !defined(BOOST_SML_CFG_DISABLE_MIN_SIZE) +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) __VA_ARGS__ _[0] +#else +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) +#endif +#define __BOOST_SML_ZERO_SIZE_ARRAY_CREATE(...) +#define __BOOST_SML_TEMPLATE_KEYWORD template +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wgnu-string-literal-operator-template" +#pragma clang diagnostic ignored "-Wzero-length-array" +#elif defined(__GNUC__) +#if !defined(__has_builtin) +#define __BOOST_SML_DEFINED_HAS_BUILTIN +#define __has_builtin(...) 0 +#endif +#define __BOOST_SML_UNUSED __attribute__((unused)) +#define __BOOST_SML_VT_INIT \ + {} +#if !defined(BOOST_SML_CFG_DISABLE_MIN_SIZE) +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) __VA_ARGS__ _[0]{} +#else +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) +#endif +#define __BOOST_SML_ZERO_SIZE_ARRAY_CREATE(...) __VA_ARGS__ ? __VA_ARGS__ : 1 +#define __BOOST_SML_TEMPLATE_KEYWORD template +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wpedantic" +#if defined(__GNUC__) && (__GNUC__ >= 10) +#pragma GCC diagnostic ignored "-Wsubobject-linkage" +#endif +#elif defined(_MSC_VER) && !defined(__clang__) +#define __BOOST_SML_DEFINED_HAS_BUILTIN +#define __has_builtin(...) __has_builtin##__VA_ARGS__ +#define __has_builtin__make_integer_seq(...) 1 +#define __BOOST_SML_UNUSED +#define __BOOST_SML_VT_INIT +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) +#define __BOOST_SML_ZERO_SIZE_ARRAY_CREATE(...) __VA_ARGS__ ? __VA_ARGS__ : 1 +#if defined(_MSC_VER) && !defined(__clang__) && _MSC_VER >= 1910 // MSVC 2017 +#define __BOOST_SML_TEMPLATE_KEYWORD template +#else +#define __BOOST_SML_TEMPLATE_KEYWORD +#endif +#pragma warning(disable : 4503) +#pragma warning(disable : 4200) +#elif defined(__ICCARM__) +#if !defined(__has_builtin) +#define __BOOST_SML_DEFINED_HAS_BUILTIN +#define __has_builtin(...) 0 +#endif +/* Needs IAR language extensions */ +#define __BOOST_SML_UNUSED __attribute__((unused)) +#define __BOOST_SML_VT_INIT \ + {} +#define __BOOST_SML_ZERO_SIZE_ARRAY(...) +#define __BOOST_SML_ZERO_SIZE_ARRAY_CREATE(...) __VA_ARGS__ ? __VA_ARGS__ : 1 +#define __BOOST_SML_TEMPLATE_KEYWORD template +#endif +BOOST_SML_NAMESPACE_BEGIN +#define __BOOST_SML_REQUIRES(...) typename aux::enable_if<__VA_ARGS__, int>::type = 0 +namespace aux { +using byte = unsigned char; +struct none_type {}; +template +struct type {}; +template +struct non_type {}; +template +struct pair {}; +template +struct type_list { + using type = type_list; +}; +template +struct bool_list { + using type = bool_list; +}; +template +struct inherit : Ts... { + using type = inherit; +}; +template +struct identity { + using type = T; +}; +template +T &&declval(); +template +struct integral_constant { + using type = integral_constant; + static constexpr T value = V; +}; +using true_type = integral_constant; +using false_type = integral_constant; +template +using void_t = void; +template +struct always : true_type {}; +template +struct never : false_type {}; +namespace detail { +template +struct conditional; +template <> +struct conditional { + template + using fn = T; +}; +template <> +struct conditional { + template + using fn = T; +}; +} // namespace detail +template +struct conditional { + using type = typename detail::conditional::template fn; +}; +template +using conditional_t = typename detail::conditional::template fn; +template +struct enable_if {}; +template +struct enable_if { + using type = T; +}; +template +using enable_if_t = typename enable_if::type; +template +struct is_same : false_type {}; +template +struct is_same : true_type {}; +template +#if defined(_MSC_VER) && !defined(__clang__) +struct is_base_of : integral_constant { +}; +#else +using is_base_of = integral_constant; +#endif +template +decltype(T(declval()...), true_type{}) test_is_constructible(int); +template +false_type test_is_constructible(...); +template +#if defined(_MSC_VER) && !defined(__clang__) +struct is_constructible : decltype(test_is_constructible(0)) { +}; +#else +using is_constructible = decltype(test_is_constructible(0)); +#endif +template +struct is_empty_base : T { + U _; +}; +template +struct is_empty : aux::integral_constant) == sizeof(none_type)> {}; +template +struct function_traits; +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +#if defined(__cpp_noexcept_function_type) +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +template +struct function_traits { + using args = type_list; +}; +#endif +template +using function_traits_t = typename function_traits::args; +template +struct remove_const { + using type = T; +}; +template +struct remove_const { + using type = T; +}; +template +using remove_const_t = typename remove_const::type; +template +struct remove_reference { + using type = T; +}; +template +struct remove_reference { + using type = T; +}; +template +struct remove_reference { + using type = T; +}; +template +using remove_reference_t = typename remove_reference::type; +template +struct remove_pointer { + using type = T; +}; +template +struct remove_pointer { + using type = T; +}; +template +using remove_pointer_t = typename remove_pointer::type; +} // namespace aux +namespace aux { +using swallow = int[]; +template +struct index_sequence { + using type = index_sequence; +}; +#if __has_builtin(__make_integer_seq) +template +struct integer_sequence; +template +struct integer_sequence { + using type = index_sequence; +}; +template +struct make_index_sequence_impl { + using type = typename __make_integer_seq::type; +}; +#else +template +struct concat; +template +struct concat, index_sequence> : index_sequence {}; +template +struct make_index_sequence_impl + : concat::type, typename make_index_sequence_impl::type>::type {}; +template <> +struct make_index_sequence_impl<0> : index_sequence<> {}; +template <> +struct make_index_sequence_impl<1> : index_sequence<0> {}; +#endif +template +using make_index_sequence = typename make_index_sequence_impl::type; +template +struct join { + using type = type_list<>; +}; +template +struct join { + using type = T; +}; +template +struct join> : type_list {}; +template +struct join, type_list> : type_list {}; +template +struct join, type_list, type_list> : type_list {}; +template +struct join, type_list, Ts...> : join, Ts...> {}; +template +struct join, type_list, type_list, type_list, type_list, type_list, + type_list, type_list, type_list, type_list, type_list, type_list, + type_list, type_list, type_list, type_list, type_list, Us...> + : join, + Us...> {}; +template +using join_t = typename join::type; +template +struct unique_impl; +template +struct unique_impl, T, Ts...> : conditional_t, inherit...>>::value, + unique_impl, Ts...>, unique_impl, Ts...>> { +}; +template +struct unique_impl> : type_list {}; +template +struct unique : unique_impl, Ts...> {}; +template +struct unique : type_list {}; +template +using unique_t = typename unique::type; +template +struct is_unique; +template +struct is_unique : true_type {}; +template +struct is_unique, T, Ts...> + : conditional_t, inherit...>>::value, false_type, is_unique, Ts...>> {}; +template +using is_unique_t = is_unique, Ts...>; +template