diff --git a/.codespell_ignore_words b/.codespell_ignore_words new file mode 100644 index 000000000..ab09b3c2f --- /dev/null +++ b/.codespell_ignore_words @@ -0,0 +1,7 @@ +INOUT +InOut +delimeter +Succesful +worl +valu +Exeption diff --git a/.github/workflows/cmake_ubuntu.yml b/.github/workflows/cmake_ubuntu.yml index aaf5f628d..41ed9a196 100644 --- a/.github/workflows/cmake_ubuntu.yml +++ b/.github/workflows/cmake_ubuntu.yml @@ -1,6 +1,11 @@ name: cmake Ubuntu -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) @@ -15,7 +20,7 @@ jobs: runs-on: ${{ matrix.os }} strategy: matrix: - os: [ubuntu-20.04] + os: [ubuntu-22.04] steps: - uses: actions/checkout@v2 @@ -23,14 +28,9 @@ jobs: - name: Install Conan id: conan uses: turtlebrowser/get-conan@main - with: - version: 1.59.0 - name: Create default profile - run: conan profile new default --detect - - - name: Update profile - run: conan profile update settings.compiler.libcxx=libstdc++11 default + run: conan profile detect - name: Create Build Environment # Some projects don't allow in-source building, so create a separate build directory @@ -44,7 +44,7 @@ jobs: - name: Configure CMake shell: bash working-directory: ${{github.workspace}}/build - run: cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_TOOLCHAIN_FILE=conan_toolchain.cmake + run: cmake ${{github.workspace}} -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_TOOLCHAIN_FILE=conan_toolchain.cmake - name: Build shell: bash @@ -52,8 +52,8 @@ jobs: run: cmake --build . --config ${{env.BUILD_TYPE}} - name: run test (Linux) - working-directory: ${{github.workspace}}/build - run: ./tests/behaviortree_cpp_test + working-directory: ${{github.workspace}}/build/tests + run: ctest - name: Upload coverage reports to Codecov uses: codecov/codecov-action@v3 diff --git a/.github/workflows/cmake_windows.yml b/.github/workflows/cmake_windows.yml index 192fdcac6..34f4f97ce 100644 --- a/.github/workflows/cmake_windows.yml +++ b/.github/workflows/cmake_windows.yml @@ -1,6 +1,11 @@ name: cmake Windows -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) diff --git a/.github/workflows/doxygen-gh-pages.yml b/.github/workflows/doxygen-gh-pages.yml new file mode 100644 index 000000000..b8fb8f46b --- /dev/null +++ b/.github/workflows/doxygen-gh-pages.yml @@ -0,0 +1,18 @@ +name: Doxygen GitHub Pages Deploy Action + +on: + push: + branches: + - main + - master + +jobs: + deploy: + runs-on: ubuntu-latest + permissions: + contents: write + steps: + - uses: DenverCoder1/doxygen-github-pages-action@v2.0.0 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + folder: doc/html diff --git a/.github/workflows/pixi.yaml b/.github/workflows/pixi.yaml index bf156ec1d..ddd1cbfb8 100644 --- a/.github/workflows/pixi.yaml +++ b/.github/workflows/pixi.yaml @@ -1,6 +1,11 @@ name: Pixi (conda) -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] jobs: pixi_conda_build: @@ -13,9 +18,9 @@ jobs: steps: # Pixi is the tool used to create/manage conda environment - uses: actions/checkout@v3 - - uses: prefix-dev/setup-pixi@v0.4.1 + - uses: prefix-dev/setup-pixi@v0.8.1 with: - pixi-version: v0.16.1 + pixi-version: v0.40.3 - name: Build run: pixi run build - name: Run tests diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index 6095e0861..ee7fa9229 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -1,9 +1,11 @@ name: pre-commit on: - pull_request: push: - branches: [master] + branches: + - master + pull_request: + types: [opened, synchronize, reopened] jobs: pre-commit: diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml deleted file mode 100644 index 9d244f60f..000000000 --- a/.github/workflows/ros1.yaml +++ /dev/null @@ -1,17 +0,0 @@ -name: ros1 - -on: [push, pull_request] - -jobs: - industrial_ci: - strategy: - matrix: - env: - - {ROS_DISTRO: noetic, ROS_REPO: main} - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v1 - - uses: 'ros-industrial/industrial_ci@master' - env: ${{matrix.env}} - with: - package-name: behaviortree_cpp diff --git a/.github/workflows/ros2-rolling.yaml b/.github/workflows/ros2-rolling.yaml index cb5004506..446c49879 100644 --- a/.github/workflows/ros2-rolling.yaml +++ b/.github/workflows/ros2-rolling.yaml @@ -1,6 +1,11 @@ name: ros2-rolling -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] jobs: industrial_ci: diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml index afdccc466..099cc04f2 100644 --- a/.github/workflows/ros2.yaml +++ b/.github/workflows/ros2.yaml @@ -1,6 +1,11 @@ name: ros2 -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] jobs: industrial_ci: @@ -8,7 +13,7 @@ jobs: matrix: env: - {ROS_DISTRO: humble, ROS_REPO: main} - - {ROS_DISTRO: iron, ROS_REPO: main} + - {ROS_DISTRO: jazzy, ROS_REPO: main} runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 diff --git a/.github/workflows/sonarcube.yml.bkp b/.github/workflows/sonarcube.yml.bkp new file mode 100644 index 000000000..926306125 --- /dev/null +++ b/.github/workflows/sonarcube.yml.bkp @@ -0,0 +1,42 @@ +name: Sonarcube Scan + +on: + push: + branches: + - master + pull_request: + types: [opened, synchronize, reopened] + +jobs: + build: + name: Build + runs-on: ubuntu-latest + env: + BUILD_WRAPPER_OUT_DIR: build_wrapper_output_directory # Directory where build-wrapper output will be placed + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 # Shallow clones should be disabled for a better relevancy of analysis + - name: Install Build Wrapper + uses: SonarSource/sonarqube-scan-action/install-build-wrapper@v4 + + - name: Install Dependencies + run: | + sudo apt-get update + sudo apt-get install -y libzmq3-dev libsqlite3-dev + + - name: Install googletest + uses: Bacondish2023/setup-googletest@v1 + + - name: Run Build Wrapper + run: | + mkdir build + cmake -S . -B build + build-wrapper-linux-x86-64 --out-dir ${{ env.BUILD_WRAPPER_OUT_DIR }} cmake --build build/ --config Release + - name: SonarQube Scan + uses: SonarSource/sonarqube-scan-action@v4 + env: + SONAR_TOKEN: ${{ secrets.SONAR_TOKEN }} # Put the name of your token here + with: + args: > + --define sonar.cfamily.compile-commands="${{ env.BUILD_WRAPPER_OUT_DIR }}/compile_commands.json" diff --git a/.gitignore b/.gitignore index cba22ead7..9d5bd4326 100644 --- a/.gitignore +++ b/.gitignore @@ -16,3 +16,5 @@ CMakeSettings.json .pixi CMakeUserPresets.json + +tags diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e6ace8262..d491f36d9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -42,3 +42,13 @@ repos: hooks: - id: clang-format args: ['-fallback-style=none', '-i'] + + # Spell check + - repo: https://github.com/codespell-project/codespell + rev: v2.4.1 + hooks: + - id: codespell + additional_dependencies: + - tomli + args: + [--toml=./pyproject.toml] diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 49aa120c2..600abbaa3 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,83 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.7.2 (2025-05-29) +------------------ +* Fix issue `#978 `_ : skipped was not working properly +* Added codespell as a pre-commit hook. (`#977 `_) +* fix: Make impossible to accidentally copy JsonExporter singleton (`#975 `_) +* Contributors: Davide Faconti, Leander Stephen D'Souza, tony-p + +4.7.1 (2025-05-13) +------------------ +* fix ROS CI +* Add action to publish Doxygen documentation as GH Page (`#972 `_) +* Update Doxyfile +* Make BT::Any::copyInto const (`#970 `_) +* more changes related to TestNode +* Contributors: David Sobek, Davide Faconti, Marcus Ebner von Eschenbach + +4.7.0 (2025-04-24) +------------------ +* change TestNodeConfig preferred constructor +* Fix dangling‐capture in TestNodeConfig +* Fix Precondition to only check condition once (`#904 `_) +* fix issue 945 +* extend JSON conversion to include vectors (`#965 `_) +* Fix CI, add BUILD_TESTS and remove catkin support +* Fix testing CMake issue to resolve Rolling regression (`#961 `_) +* Bug fix/set blackboard (`#955 `_) +* feat: add fuzzing harnesses (`#925 `_) +* fix warnings +* Add const to applyVisitor (`#935 `_) +* try fix (`#941 `_) +* add workflow for sonarcube (`#936 `_) +* Fix issue `#909 `_: static queue in Loop +* apply changes suggested in `#893 `_ +* apply fix mentioned in `#916 `_ +* apply fixes suggested in `#919 `_ +* fix issue `#918 `_ (introduced in `#885 `_) +* add fix suggested in `#920 `_ +* add unit test related to `#931 `_ +* Fix compilation error when targeting C++23 (`#926 `_) ^~~~~~~~~~~~~ +* Fixes issue # `#929 `_ and `#921 `_ +* apply check suggested in `#924 `_ +* Fix ROS 2 build when ZeroMQ or SQlite3 include are not in the default include path (`#911 `_) + * Fix ROS 2 build when ZeroMQ or SQlite3 include are not in the default include path + * Update ament_build.cmake +* Fix/use correct compiler pixi/conda (`#914 `_) + * fix: Use the cxx-compiler package which will set the correct compiler for the platform, and setup the required environment for it to work as expected + * misc: update pixi versions in pipeline +* Add "other ports" to NodeConfig (`#910 `_) +* [retry_node] Refresh max_attempts\_ in case it changed (`#905 `_) + Co-authored-by: Guillaume Doisy +* use relative path in .Doxyfile (`#882 `_) +* Additional XML verification for ReactiveSequence nodes (`#885 `_) + Co-authored-by: AndyZe +* fix script parse error while 'A==-1' (`#896 `_) + Co-authored-by: wangzheng +* Expose return value of wait_for (`#887 `_) +* fix(examples): update t11_groot_howto log filename (`#886 `_) +* put minitrace in the build_interface link library (`#874 `_) + fixes the cmake export set when building behavior tree on standard cmake: CMake Error: install(EXPORT "behaviortree_cppTargets" ...) includes target "behaviortree_cpp" which requires target "minitrace" that is not in any export set. +* Improved XML parsing error message to say where in the XML the offending port is found. (`#876 `_) + Example output: + a port with name [ball_pose] is found in the XML (, line 7) but not in the providedPorts() of its registered node type. +* Refactored the TreeNode::executeTick() function to use a scoped timer for performance monitoring. (`#861 `_) (`#863 `_) + Update src/tree_node.cpp + Co-authored-by: wangzheng + Co-authored-by: Davide Faconti +* fix issue `#852 `_: thread safety in Loggers +* Lexy updated +* tinyXML updated to version 10.0 +* cppzmq updated to version 4.10 +* fix the "all_skipped" logic +* fixed: support utf-8 path xml-file (`#845 `_) + * fixed: 1. added compile version check to support Chinese path xml-file parsing 2. cmake add msvc /utf-8 options + * change cmake /utf-8 option add mode +* Export plugins to share directory & register CrossDoor plugin (`#804 `_) +* Contributors: Aglargil, AndyZe, Antoine Hoarau, David Sobek, Davide Faconti, Guillaume Doisy, Isar Meijer, Jake Keller, Marq Rasmussen, Michele Tartari, Silvio Traversaro, Tony Najjar, b-adkins, ckrah, devis12, kinly, tony-p, vincent-hui + 4.6.2 (2024-06-26) ------------------ * Initialize template variable `T out` (`#839 `_) @@ -46,7 +123,7 @@ Changelog for package behaviortree_cpp * warn about overwritten enums * fix ambiguous to_json * Extend unit test for blackboard backup to run the second tree (`#789 `_) -* json convertion changed and +* json conversion changed and * issue `#755 `_ : add backchaining test and change reactive nodes checks (`#770 `_) * Update switch_node.h * test moved and port remapping fixed @@ -323,7 +400,7 @@ Changelog for package behaviortree_cpp * better include paths * Control node and Decorators RUNNING before first child * blackboard: update getKeys and add mutex to scripting -* add [[nodiscard]] and some othe minor changes +* add [[nodiscard]] and some other minor changes * add screenshot * change the behavior of tickOnce to actually loop is wake up signal is… (`#522 `_) * change the behavior of tickOnce to actually loop is wake up signal is received @@ -422,7 +499,7 @@ Changelog for package behaviortree_cpp dependency explicitly. * Change order of lock to prevent deadlock. (`#368 `_) Resolves `#367 `_. -* Fix `#320 `_ : forbit refrences in Any +* Fix `#320 `_ : forbid references in Any * Update action_node.h * Contributors: Adam Sasine, Davide Faconti, Fabian Schurig, Griswald Brooks, Hyeongsik Min, Robodrome, imgbot[bot], panwauu @@ -769,9 +846,9 @@ Changelog for package behaviortree_cpp * Conan package distribution (#39) * Non-functional refactoring of xml_parsing to clean up the code * cosmetic changes in the code of BehaviorTreeFactory -* XML schema. Related to enchancement #40 +* XML schema. Related to enhancement #40 * call setRegistrationName() for built-in Nodes - The methos is called by BehaviorTreefactory, therefore it + The method is called by BehaviorTreefactory, therefore it registrationName is empty if trees are created programmatically. * Reset reference count when destroying logger (issue #38) * Contributors: Davide Facont, Davide Faconti, Uilian Ries @@ -787,7 +864,7 @@ Changelog for package behaviortree_cpp ------------------ * adding virtual TreeNode::onInit() [issue #33] * fix issue #34 : if you don't implement convertFromString, it will compile but it may throw -* Pretty demangled names and obsolate comments removed +* Pretty demangled names and obsolete comments removed * bug fixes * more comments * [enhancement #32]: add CoroActionNode and rename ActionNode as "AsynActionNode" @@ -854,7 +931,7 @@ Changelog for package behaviortree_cpp * Fix: registerBuilder did not register the manifest. It was "broken" as public API method * Use the Pimpl idiom to hide zmq from the header file * move header of minitrace in the cpp file -* Fixed a crash occuring when you didn't initialized a Tree object (#20) +* Fixed a crash occurring when you didn't initialized a Tree object (#20) * Fix issue #16 * add ParallelNode to pre-registered entries in factory (issue #13) * removed M_PI diff --git a/CMakeLists.txt b/CMakeLists.txt index 722e102b7..e69c9e96c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,19 +1,54 @@ cmake_minimum_required(VERSION 3.16.3) # version on Ubuntu Focal -project(behaviortree_cpp VERSION 4.6.2 LANGUAGES C CXX) +project(behaviortree_cpp VERSION 4.7.2 LANGUAGES C CXX) -set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") +# create compile_commands.json +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +#---- project configuration ---- +option(BTCPP_SHARED_LIBS "Build shared libraries" ON) +option(BTCPP_BUILD_TOOLS "Build commandline tools" ON) +option(BTCPP_EXAMPLES "Build tutorials and examples" ON) +option(BUILD_TESTING "Build the unit tests" ON) +option(BTCPP_GROOT_INTERFACE "Add Groot2 connection. Requires ZeroMQ" ON) +option(BTCPP_SQLITE_LOGGING "Add SQLite logging." ON) + +option(USE_V3_COMPATIBLE_NAMES "Use some alias to compile more easily old 3.x code" OFF) +option(ENABLE_FUZZING "Enable fuzzing builds" OFF) +option(USE_AFLPLUSPLUS "Use AFL++ instead of libFuzzer" OFF) +option(ENABLE_DEBUG "Enable debug build with full symbols" OFF) +option(FORCE_STATIC_LINKING "Force static linking of all dependencies" OFF) + +set(BASE_FLAGS "") + +if(ENABLE_DEBUG) + list(APPEND BASE_FLAGS + -g3 + -ggdb3 + -O0 + -fno-omit-frame-pointer + ) +endif() + +# Include fuzzing configuration if enabled +if(ENABLE_FUZZING) + include(${CMAKE_CURRENT_SOURCE_DIR}/cmake/fuzzing_build.cmake) +else() + # Apply base flags for non-fuzzing builds + add_compile_options(${BASE_FLAGS}) + add_link_options(${BASE_FLAGS}) +endif() + +set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") set(BTCPP_LIBRARY ${PROJECT_NAME}) if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) - message(STATUS "Setting build type to 'Release' as none was specified.") - set(CMAKE_BUILD_TYPE "Release" CACHE - STRING "Choose the type of build." FORCE) - # Set the possible values of build type for cmake-gui - set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS - "Debug" "Release" "MinSizeRel" "RelWithDebInfo") + message(STATUS "Setting build type to 'Release' as none was specified.") + set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Choose the type of build." FORCE) + set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS + "Debug" "Release" "MinSizeRel" "RelWithDebInfo") endif() if(MSVC) @@ -22,17 +57,6 @@ else() add_definitions(-Wpedantic -fno-omit-frame-pointer) endif() - -#---- project configuration ---- -option(BTCPP_SHARED_LIBS "Build shared libraries" ON) -option(BTCPP_BUILD_TOOLS "Build commandline tools" ON) -option(BTCPP_EXAMPLES "Build tutorials and examples" ON) -option(BTCPP_UNIT_TESTS "Build the unit tests" ON) -option(BTCPP_GROOT_INTERFACE "Add Groot2 connection. Requires ZeroMQ" ON) -option(BTCPP_SQLITE_LOGGING "Add SQLite logging." ON) - -option(USE_V3_COMPATIBLE_NAMES "Use some alias to compile more easily old 3.x code" OFF) - if(USE_V3_COMPATIBLE_NAMES) add_definitions(-DUSE_BTCPP3_OLD_NAMES) endif() @@ -55,21 +79,12 @@ if ( ament_cmake_FOUND ) add_definitions( -DUSING_ROS2 ) message(STATUS "------------------------------------------") - message(STATUS "BehaviourTree is being built using AMENT.") + message(STATUS "BehaviorTree is being built using AMENT.") message(STATUS "------------------------------------------") include(cmake/ament_build.cmake) - -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) - - add_definitions( -DUSING_ROS ) - message(STATUS "------------------------------------------") - message(STATUS "BehaviourTree is being built using CATKIN.") - message(STATUS "------------------------------------------") - include(cmake/catkin_build.cmake) - set(catkin_FOUND TRUE) else() message(STATUS "------------------------------------------") - message(STATUS "BehaviourTree is being built with conan.") + message(STATUS "BehaviorTree is being built with conan.") message(STATUS "------------------------------------------") include(cmake/conan_build.cmake) endif() @@ -186,25 +201,35 @@ target_compile_definitions(${BTCPP_LIBRARY} PUBLIC BTCPP_LIBRARY_VERSION="${CMAK target_compile_features(${BTCPP_LIBRARY} PUBLIC cxx_std_17) if(MSVC) - target_compile_options(${BTCPP_LIBRARY} PRIVATE "/source-charset:utf-8") + target_compile_options(${BTCPP_LIBRARY} PRIVATE "/source-charset:utf-8") else() - target_compile_options(${BTCPP_LIBRARY} PRIVATE -Wall -Wextra) + if(ENABLE_DEBUG) + target_compile_options(${BTCPP_LIBRARY} PRIVATE -Wall -Wextra -g3 -ggdb3 -O0 -fno-omit-frame-pointer) + else() + target_compile_options(${BTCPP_LIBRARY} PRIVATE -Wall -Wextra) + endif() endif() add_library(BT::${BTCPP_LIBRARY} ALIAS ${BTCPP_LIBRARY}) +# Add fuzzing targets +if(ENABLE_FUZZING) + add_fuzzing_targets() +endif() + ############################################################# message( STATUS "BTCPP_LIB_DESTINATION: ${BTCPP_LIB_DESTINATION} " ) message( STATUS "BTCPP_INCLUDE_DESTINATION: ${BTCPP_INCLUDE_DESTINATION} " ) -message( STATUS "BTCPP_UNIT_TESTS: ${BTCPP_UNIT_TESTS} " ) -if (BTCPP_UNIT_TESTS OR BTCPP_EXAMPLES) -add_subdirectory(sample_nodes) +if (BUILD_TESTING OR BTCPP_EXAMPLES) + add_subdirectory(sample_nodes) endif() ###################################################### -if (BTCPP_UNIT_TESTS) +include(CTest) +message( STATUS "BUILD_TESTING: ${BUILD_TESTING} " ) +if (BUILD_TESTING) add_subdirectory(tests) endif() diff --git a/Doxyfile b/Doxyfile index 7c24f87b6..d06db140e 100644 --- a/Doxyfile +++ b/Doxyfile @@ -58,7 +58,7 @@ PROJECT_LOGO = # entered, it will be relative to the location where doxygen was started. If # left blank the current directory will be used. -OUTPUT_DIRECTORY = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/doc +OUTPUT_DIRECTORY = ./doc # If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- # directories (in 2 levels) under the output directory of each output format and @@ -781,7 +781,7 @@ WARN_LOGFILE = # spaces. See also FILE_PATTERNS and EXTENSION_MAPPING # Note: If this tag is empty the current directory is searched. -INPUT = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/include +INPUT = ./include # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses @@ -863,8 +863,9 @@ RECURSIVE = YES # Note that relative paths are relative to the directory from which doxygen is # run. -EXCLUDE = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/3rdparty \ - /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/gtest +EXCLUDE = ./3rdparty \ + ./gtest \ + ./include/behaviortree_cpp/contrib # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded diff --git a/README.md b/README.md index cd8e3371a..6fda200c7 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,10 @@ ![License MIT](https://img.shields.io/github/license/BehaviorTree/BehaviorTree.CPP?color=blue) -![Version](https://img.shields.io/badge/version-4.6-blue.svg) [![conan Ubuntu](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake_ubuntu.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake_ubuntu.yml) [![conan Windows](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake_windows.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake_windows.yml) -[![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) -[![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) +[![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/ros2.yaml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/ros2.yaml) [![pixi (Conda)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/pixi.yaml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/pixi.yaml) -# BehaviorTree.CPP 4.6 +# BehaviorTree.CPP 4.7

@@ -37,6 +35,8 @@ to visualize, record, replay and analyze state transitions. You can learn about the main concepts, the API and the tutorials here: https://www.behaviortree.dev/ +An automatically generated API documentation can be found here: https://BehaviorTree.github.io/BehaviorTree.CPP/ + If the documentation doesn't answer your questions and/or you want to connect with the other **BT.CPP** users, visit [our forum](https://github.com/BehaviorTree/BehaviorTree.CPP/discussions) @@ -55,7 +55,6 @@ If you are looking for a more fancy graphical user interface (and I know you do) Three build systems are supported: -- **catkin**, if you use ROS - **colcon (ament)**, if you use ROS2 - **conan** otherwise (Linux/Windows). - **straight cmake** if you want to be personally responsible for dependencies :) diff --git a/cmake/FindZeroMQ.cmake b/cmake/FindZeroMQ.cmake index 8553df95c..b11258812 100644 --- a/cmake/FindZeroMQ.cmake +++ b/cmake/FindZeroMQ.cmake @@ -29,8 +29,6 @@ else (ZeroMQ_LIBRARIES AND ZeroMQ_INCLUDE_DIRS) find_path(ZeroMQ_INCLUDE_DIR NAMES zmq.h - HINTS - "$ENV{CONDA_PREFIX}/include" PATHS /usr/include /usr/local/include diff --git a/cmake/ament_build.cmake b/cmake/ament_build.cmake index 55c3011b2..ec1e0a66b 100644 --- a/cmake/ament_build.cmake +++ b/cmake/ament_build.cmake @@ -12,6 +12,9 @@ endif() find_package(ament_index_cpp REQUIRED) +set(BTCPP_EXTRA_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIRS} + ${SQLite3_INCLUDE_DIRS}) + set( BTCPP_EXTRA_LIBRARIES $ $ @@ -26,6 +29,7 @@ set( BTCPP_BIN_DESTINATION bin ) mark_as_advanced( BTCPP_EXTRA_LIBRARIES + BTCPP_EXTRA_INCLUDE_DIRS BTCPP_LIB_DESTINATION BTCPP_INCLUDE_DESTINATION BTCPP_BIN_DESTINATION ) diff --git a/cmake/catkin_build.cmake b/cmake/catkin_build.cmake deleted file mode 100644 index 487d84773..000000000 --- a/cmake/catkin_build.cmake +++ /dev/null @@ -1,40 +0,0 @@ -#---- Add the subdirectory cmake ---- -set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${PROJECT_SOURCE_DIR}/cmake") -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") - -if(BTCPP_GROOT_INTERFACE) - find_package(ZeroMQ REQUIRED) -endif() - -if(BTCPP_SQLITE_LOGGING) - find_package(SQLite3 REQUIRED) -endif() - -find_package(catkin REQUIRED COMPONENTS roslib) - -catkin_package( - INCLUDE_DIRS include - LIBRARIES ${BTCPP_LIBRARY} - CATKIN_DEPENDS roslib ) - -set(BTCPP_EXTRA_INCLUDE_DIRS ${catkin_INCLUDE_DIRS} ) - -set( BTCPP_EXTRA_LIBRARIES - ${catkin_LIBRARIES} - ${ZeroMQ_LIBRARIES} - ${SQLite3_LIBRARIES}) - -set( BTCPP_LIB_DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ) -set( BTCPP_INCLUDE_DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} ) -set( BTCPP_BIN_DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) - -mark_as_advanced( - BTCPP_EXTRA_LIBRARIES - BTCPP_EXTRA_INCLUDE_DIRS - BTCPP_LIB_DESTINATION - BTCPP_INCLUDE_DESTINATION - BTCPP_BIN_DESTINATION ) - -macro(export_btcpp_package) - # do nothing -endmacro() diff --git a/cmake/conan.cmake b/cmake/conan.cmake index 3fa9a26ba..d36c5ed44 100644 --- a/cmake/conan.cmake +++ b/cmake/conan.cmake @@ -116,7 +116,7 @@ macro(_conan_check_language) set(LANGUAGE C) set(USING_CXX 0) else () - message(FATAL_ERROR "Conan: Neither C or C++ was detected as a language for the project. Unabled to detect compiler version.") + message(FATAL_ERROR "Conan: Neither C or C++ was detected as a language for the project. Unable to detect compiler version.") endif() endmacro() @@ -1050,7 +1050,7 @@ macro(conan_config_install) endif() if(DEFINED CONAN_ARGS) - # Convert ; seperated multi arg list into space seperated string + # Convert ; separated multi arg list into space separated string string(REPLACE ";" " " l_CONAN_ARGS "${CONAN_ARGS}") set(CONAN_ARGS_ARGS "--args=${l_CONAN_ARGS}") endif() diff --git a/cmake/fuzzing_build.cmake b/cmake/fuzzing_build.cmake new file mode 100644 index 000000000..43f367001 --- /dev/null +++ b/cmake/fuzzing_build.cmake @@ -0,0 +1,153 @@ +# Fuzzing configuration +# Supports both local fuzzing and OSS-Fuzz integration + +# Detect if we're running in OSS-Fuzz environment +if(DEFINED ENV{LIB_FUZZING_ENGINE}) + set(OSS_FUZZ ON) + message(STATUS "OSS-Fuzz environment detected") +else() + set(OSS_FUZZ OFF) +endif() + +# Auto-detect AFL++ compiler if not in OSS-Fuzz mode +if(NOT OSS_FUZZ AND (CMAKE_C_COMPILER MATCHES ".*afl-.*" OR CMAKE_CXX_COMPILER MATCHES ".*afl-.*")) + set(USE_AFLPLUSPLUS ON CACHE BOOL "Use AFL++ instead of libFuzzer" FORCE) + message(STATUS "AFL++ compiler detected - automatically enabling AFL++ mode") +endif() + +# When building for fuzzing, we want static library by default +set(BTCPP_SHARED_LIBS OFF CACHE BOOL "Build static library for fuzzing" FORCE) + +# Only apply static linking settings if explicitly requested +if(FORCE_STATIC_LINKING) + set(CMAKE_FIND_LIBRARY_SUFFIXES .a ${CMAKE_FIND_LIBRARY_SUFFIXES}) + set(BUILD_SHARED_LIBS OFF) + + # Force static linking for dependencies + if(BTCPP_GROOT_INTERFACE) + set(ZeroMQ_USE_STATIC_LIBS ON) + set(ZEROMQ_STATIC_LIBRARY ON) + endif() + + if(BTCPP_SQLITE_LOGGING) + set(SQLite3_USE_STATIC_LIBS ON) + endif() +endif() + +# Set up flags for local fuzzing (not used for OSS-Fuzz) +if(NOT OSS_FUZZ) + list(APPEND BASE_FLAGS -O2) + + if(USE_AFLPLUSPLUS) + set(SANITIZER_FLAGS + -fsanitize=address,undefined + ) + else() + # For libFuzzer, use fuzzer-no-link for the library + set(SANITIZER_FLAGS + -fsanitize=address,undefined,fuzzer-no-link + ) + endif() + + # Apply sanitizer flags to the base library + list(APPEND BASE_FLAGS ${SANITIZER_FLAGS}) + + add_compile_options(${BASE_FLAGS}) + add_link_options(${BASE_FLAGS}) +endif() + +# Disable certain features during fuzzing +set(BTCPP_EXAMPLES OFF CACHE BOOL "Disable examples during fuzzing" FORCE) +set(BTCPP_BUILD_TOOLS OFF CACHE BOOL "Disable tools during fuzzing" FORCE) +set(BTCPP_UNIT_TESTS OFF CACHE BOOL "Disable tests during fuzzing" FORCE) +set(BTCPP_SHARED_LIBS OFF CACHE BOOL "Build static library for fuzzing" FORCE) + +# Function to apply fuzzing flags for local development builds +function(apply_local_fuzzing_flags target) + target_compile_options(${target} PRIVATE + ${BASE_FLAGS} + ${SANITIZER_FLAGS} + ) + + if(FORCE_STATIC_LINKING) + if(USE_AFLPLUSPLUS) + target_link_options(${target} PRIVATE + ${BASE_FLAGS} + ${SANITIZER_FLAGS} + -static-libstdc++ + -static-libgcc + -fsanitize=fuzzer + ) + else() + target_link_options(${target} PRIVATE + ${BASE_FLAGS} + -fsanitize=fuzzer + ${SANITIZER_FLAGS} + -static-libstdc++ + -static-libgcc + ) + endif() + else() + if(USE_AFLPLUSPLUS) + target_link_options(${target} PRIVATE + ${BASE_FLAGS} + ${SANITIZER_FLAGS} + -fsanitize=fuzzer + ) + else() + target_link_options(${target} PRIVATE + ${BASE_FLAGS} + -fsanitize=fuzzer + ${SANITIZER_FLAGS} + ) + endif() + endif() +endfunction() + +# Function to add fuzzing targets - compatible with both local and OSS-Fuzz builds +function(add_fuzzing_targets) + set(FUZZERS bt_fuzzer script_fuzzer bb_fuzzer) + + foreach(fuzzer ${FUZZERS}) + add_executable(${fuzzer} fuzzing/${fuzzer}.cpp) + + if(OSS_FUZZ) + # For OSS-Fuzz environment, we rely on environment variables + # like $CC, $CXX, $CFLAGS, $CXXFLAGS, and $LIB_FUZZING_ENGINE + target_link_libraries(${fuzzer} PRIVATE + ${BTCPP_LIBRARY} + ${BTCPP_EXTRA_LIBRARIES} + $ENV{LIB_FUZZING_ENGINE} + ) + else() + # For local development, use our own flags + apply_local_fuzzing_flags(${fuzzer}) + target_link_libraries(${fuzzer} PRIVATE + ${BTCPP_LIBRARY} + ${BTCPP_EXTRA_LIBRARIES} + ) + endif() + + # Setup corpus directories (useful for both environments) + set(CORPUS_DIR ${CMAKE_BINARY_DIR}/corpus/${fuzzer}) + file(MAKE_DIRECTORY ${CORPUS_DIR}) + endforeach() + + # Copy corpus files if they exist (useful for local testing) + # OSS-Fuzz provides its own corpus handling + if(NOT OSS_FUZZ) + file(GLOB BT_CORPUS_FILES "${CMAKE_SOURCE_DIR}/fuzzing/corpus/bt_corpus/*") + file(GLOB SCRIPT_CORPUS_FILES "${CMAKE_SOURCE_DIR}/fuzzing/corpus/script_corpus/*") + file(GLOB BB_CORPUS_FILES "${CMAKE_SOURCE_DIR}/fuzzing/corpus/bb_corpus/*") + + if(BT_CORPUS_FILES) + file(COPY ${BT_CORPUS_FILES} DESTINATION ${CMAKE_BINARY_DIR}/corpus/bt_fuzzer) + endif() + if(SCRIPT_CORPUS_FILES) + file(COPY ${SCRIPT_CORPUS_FILES} DESTINATION ${CMAKE_BINARY_DIR}/corpus/script_fuzzer) + endif() + if(BB_CORPUS_FILES) + file(COPY ${BB_CORPUS_FILES} DESTINATION ${CMAKE_BINARY_DIR}/corpus/bb_fuzzer) + endif() + endif() +endfunction() diff --git a/examples/t12_default_ports.cpp b/examples/t12_default_ports.cpp index 8fa866a93..91d2f72aa 100644 --- a/examples/t12_default_ports.cpp +++ b/examples/t12_default_ports.cpp @@ -22,7 +22,7 @@ struct Point2D } }; -// Allow bi-directional convertion to JSON +// Allow bi-directional conversion to JSON BT_JSON_CONVERTER(Point2D, point) { add_field("x", &point.x); diff --git a/examples/t15_nodes_mocking.cpp b/examples/t15_nodes_mocking.cpp index 28806da7e..caef9e224 100644 --- a/examples/t15_nodes_mocking.cpp +++ b/examples/t15_nodes_mocking.cpp @@ -97,7 +97,7 @@ int main(int argc, char** argv) // this will be synchronous (async_delay is 0) BT::TestNodeConfig counting_config; - test_config.return_status = BT::NodeStatus::SUCCESS; + counting_config.return_status = BT::NodeStatus::SUCCESS; //--------------------------------------------------------------- // Next, we want to substitute one or more of out Nodes with this mocks @@ -147,7 +147,7 @@ int main(int argc, char** argv) factory.loadSubstitutionRuleFromJSON(json_text); } //--------------------------------------------------------------- - // IMPORTANT: all substiutions must be done BEFORE creating the tree + // IMPORTANT: all substitutions must be done BEFORE creating the tree // During the construction phase of the tree, the substitution // rules will be used to instantiate the test nodes, instead of the // original ones. @@ -158,7 +158,7 @@ int main(int argc, char** argv) return 0; } -/* Expecte output: +/* Expected output: ----- Nodes fullPath() ------- Sequence::1 diff --git a/examples/t16_global_blackboard.cpp b/examples/t16_global_blackboard.cpp index 956bbe2c2..38bf35b14 100644 --- a/examples/t16_global_blackboard.cpp +++ b/examples/t16_global_blackboard.cpp @@ -97,7 +97,7 @@ int main() return 0; } -/* Expecte output: +/* Expected output: [main_print] val: 1 [sub_print] val: 1 diff --git a/fuzzing/README.md b/fuzzing/README.md new file mode 100644 index 000000000..e42a75bd0 --- /dev/null +++ b/fuzzing/README.md @@ -0,0 +1,21 @@ +# Fuzzing BehaviorTree.CPP + +You can build the existing harnesses either for libfuzzer or AFL++. +Building the fuzzers requires `clang` (libfuzzer) or an installed version +of [AFL++](https://github.com/AFLplusplus/AFLplusplus). + +## libfuzzer + +```bash +mkdir build_libfuzzer && cd build_libfuzzer +cmake -DENABLE_FUZZING=ON .. +``` + +## AFL++ + +```bash +export CC=afl-clang-fast +export CXX=afl-clang-fast++ +mkdir build_afl && cd build_afl +cmake -DENABLE_FUZZING=ON -DUSE_AFLPLUSPLUS=ON .. +``` diff --git a/fuzzing/bb_fuzzer.cpp b/fuzzing/bb_fuzzer.cpp new file mode 100644 index 000000000..5667d8ffb --- /dev/null +++ b/fuzzing/bb_fuzzer.cpp @@ -0,0 +1,270 @@ +#include "behaviortree_cpp/blackboard.h" +#include +#include +#include +#include +#include + +#include + +class ExceptionFilter +{ +public: + static bool isExpectedException(const std::exception& e) + { + const std::string what = e.what(); + const std::vector expected_patterns = { "Blackboard::set", + "once declared, the type of a " + "port shall not change", + "Missing key", + "hasn't been initialized", + "Missing parent blackboard", + "Floating point truncated", + "Value outside the max " + "numerical limit", + "Value outside the lovest " + "numerical limit", + "Value is negative and can't be " + "converted to unsigned", + "Implicit casting to bool is " + "not allowed" }; + + for(const auto& pattern : expected_patterns) + { + if(what.find(pattern) != std::string::npos) + { + return true; + } + } + return false; + } +}; + +class BlackboardFuzzer +{ +private: + std::vector blackboards_; + std::vector generated_keys_; + FuzzedDataProvider& fuzz_data_; + + std::string generateKey() + { + const std::string key_chars = "abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ01" + "23456789_@"; + size_t length = fuzz_data_.ConsumeIntegralInRange(1, 32); + std::string key; + for(size_t i = 0; i < length; ++i) + { + key += + key_chars[fuzz_data_.ConsumeIntegralInRange(0, key_chars.length() - 1)]; + } + generated_keys_.push_back(key); + return key; + } + + void fuzzSingleBB(BT::Blackboard::Ptr bb) + { + if(!bb) + return; + + try + { + // Create random entry + std::string key = generateKey(); + switch(fuzz_data_.ConsumeIntegralInRange(0, 6)) + { + case 0: + bb->set(key, fuzz_data_.ConsumeIntegral()); + break; + case 1: + bb->set(key, fuzz_data_.ConsumeFloatingPoint()); + break; + case 2: + bb->set(key, fuzz_data_.ConsumeRandomLengthString()); + break; + case 3: + bb->set(key, fuzz_data_.ConsumeBool()); + break; + case 4: + bb->set(key, fuzz_data_.ConsumeIntegral()); + break; + case 5: + bb->set(key, fuzz_data_.ConsumeFloatingPoint()); + break; + case 6: { + // Try to get non-existent key + bb->get(generateKey()); + break; + } + } + + // Random operations on existing keys + if(!generated_keys_.empty()) + { + const auto& existing_key = + generated_keys_[fuzz_data_.ConsumeIntegralInRange( + 0, generated_keys_.size() - 1)]; + + switch(fuzz_data_.ConsumeIntegralInRange(0, 4)) + { + case 0: + bb->unset(existing_key); + break; + case 1: + bb->getEntry(existing_key); + break; + case 2: + bb->get(existing_key); + break; + case 3: + bb->get(existing_key); + break; + case 4: + bb->get(existing_key); + break; + } + } + + // Random remapping operations + if(generated_keys_.size() >= 2) + { + size_t idx1 = + fuzz_data_.ConsumeIntegralInRange(0, generated_keys_.size() - 1); + size_t idx2 = + fuzz_data_.ConsumeIntegralInRange(0, generated_keys_.size() - 1); + bb->addSubtreeRemapping(generated_keys_[idx1], generated_keys_[idx2]); + } + } + catch(const std::exception& e) + { + if(!ExceptionFilter::isExpectedException(e)) + { + throw; + } + } + } + + void createBlackboardHierarchy() + { + if(blackboards_.empty()) + return; + + auto parent = blackboards_[fuzz_data_.ConsumeIntegralInRange( + 0, blackboards_.size() - 1)]; + + auto child = BT::Blackboard::create(parent); + if(fuzz_data_.ConsumeBool()) + { + child->enableAutoRemapping(true); + } + + blackboards_.push_back(child); + } + + void fuzzJsonOperations(BT::Blackboard::Ptr bb) + { + try + { + auto json = BT::ExportBlackboardToJSON(*bb); + if(fuzz_data_.ConsumeBool()) + { + std::string json_str = json.dump(); + size_t pos = fuzz_data_.ConsumeIntegralInRange(0, json_str.length()); + json_str.insert(pos, fuzz_data_.ConsumeRandomLengthString()); + json = nlohmann::json::parse(json_str); + } + BT::ImportBlackboardFromJSON(json, *bb); + } + catch(const std::exception& e) + { + if(!ExceptionFilter::isExpectedException(e)) + { + throw; + } + } + } + +public: + explicit BlackboardFuzzer(FuzzedDataProvider& provider) : fuzz_data_(provider) + { + blackboards_.push_back(BT::Blackboard::create()); + } + + void fuzz() + { + size_t num_operations = fuzz_data_.ConsumeIntegralInRange(50, 200); + + for(size_t i = 0; i < num_operations && !blackboards_.empty(); ++i) + { + try + { + // Randomly select a blackboard to operate on + size_t bb_idx = + fuzz_data_.ConsumeIntegralInRange(0, blackboards_.size() - 1); + auto bb = blackboards_[bb_idx]; + + switch(fuzz_data_.ConsumeIntegralInRange(0, 3)) + { + case 0: + // Fuzz single blackboard operations + fuzzSingleBB(bb); + break; + + case 1: + // Create new blackboards in hierarchy + if(fuzz_data_.ConsumeBool()) + { + createBlackboardHierarchy(); + } + break; + + case 2: + // JSON operations + fuzzJsonOperations(bb); + break; + + case 3: + // Cleanup operations + if(fuzz_data_.ConsumeBool() && blackboards_.size() > 1) + { + size_t remove_idx = + fuzz_data_.ConsumeIntegralInRange(0, blackboards_.size() - 1); + blackboards_.erase(blackboards_.begin() + remove_idx); + } + break; + } + } + catch(const std::exception& e) + { + if(!ExceptionFilter::isExpectedException(e)) + { + std::cerr << "Unexpected exception: " << e.what() << std::endl; + throw; + } + } + } + } +}; + +extern "C" int LLVMFuzzerTestOneInput(const uint8_t* data, size_t size) +{ + if(size < 64) + return 0; + + try + { + FuzzedDataProvider fuzz_data(data, size); + BlackboardFuzzer fuzzer(fuzz_data); + fuzzer.fuzz(); + } + catch(const std::exception& e) + { + if(!ExceptionFilter::isExpectedException(e)) + { + std::cerr << "Unexpected top-level exception: " << e.what() << std::endl; + return 1; + } + } + + return 0; +} diff --git a/fuzzing/bt_fuzzer.cpp b/fuzzing/bt_fuzzer.cpp new file mode 100644 index 000000000..7411109cc --- /dev/null +++ b/fuzzing/bt_fuzzer.cpp @@ -0,0 +1,125 @@ +#include +#include "behaviortree_cpp/bt_factory.h" +#include "behaviortree_cpp/xml_parsing.h" +#include + +// List of valid node types we can use to construct valid-ish XML +constexpr const char* NODE_TYPES[] = { + "Sequence", "Fallback", "ParallelAll", + "ReactiveSequence", "ReactiveFallback", "IfThenElse", + "WhileDoElse", "Inverter", "RetryUntilSuccessful", + "Repeat", "Timeout", "Delay", + "ForceSuccess", "ForceFailure", "AlwaysSuccess", + "AlwaysFailure", "SetBlackboard", "SubTree" +}; + +// Attributes that can be added to nodes +constexpr const char* NODE_ATTRIBUTES[] = { "name", "ID", "port_1", + "port_2", "timeout_ms", "delay_ms", + "threshold", "max_repeats" }; + +std::string generateFuzzedNodeXML(FuzzedDataProvider& fdp, int depth = 0) +{ + // Prevent stack overflow with max depth + if(depth > 6) + { // Reasonable limit for XML tree depth + return ""; + } + + std::string xml; + const std::string node_type = fdp.PickValueInArray(NODE_TYPES); + + xml += "<" + node_type; + + size_t num_attributes = fdp.ConsumeIntegralInRange(0, 3); + for(size_t i = 0; i < num_attributes; i++) + { + const std::string attr = fdp.PickValueInArray(NODE_ATTRIBUTES); + std::string value = fdp.ConsumeRandomLengthString(10); + xml += " " + attr + "=\"" + value + "\""; + } + + if(depth > 3 || fdp.ConsumeBool()) + { + xml += "/>"; + } + else + { + xml += ">"; + // Add some child nodes recursively with depth limit + size_t num_children = fdp.ConsumeIntegralInRange(0, 2); + for(size_t i = 0; i < num_children; i++) + { + xml += generateFuzzedNodeXML(fdp, depth + 1); + } + xml += ""; + } + + return xml; +} + +extern "C" int LLVMFuzzerTestOneInput(const uint8_t* data, size_t size) +{ + if(size < 4) + { + return 0; + } + + FuzzedDataProvider fdp(data, size); + BT::BehaviorTreeFactory factory; + + try + { + // Strategy 1: Test with completely random data + if(fdp.ConsumeBool()) + { + std::string random_xml = fdp.ConsumeRandomLengthString(size - 1); + try + { + factory.createTreeFromText(random_xml); + } + catch(const std::exception&) + {} + } + // Strategy 2: Generate semi-valid XML + else + { + std::string xml = R"( + + )"; + + size_t num_nodes = fdp.ConsumeIntegralInRange(1, 5); + for(size_t i = 0; i < num_nodes; i++) + { + xml += generateFuzzedNodeXML(fdp); + } + + xml += R"( + + )"; + + auto blackboard = BT::Blackboard::create(); + + switch(fdp.ConsumeIntegralInRange(0, 2)) + { + case 0: + factory.createTreeFromText(xml, blackboard); + break; + case 1: + BT::VerifyXML(xml, {}); + break; + case 2: + factory.registerBehaviorTreeFromText(xml); + if(!factory.registeredBehaviorTrees().empty()) + { + factory.createTree(factory.registeredBehaviorTrees().front(), blackboard); + } + break; + } + } + } + catch(const std::exception&) + {} + + return 0; +} diff --git a/fuzzing/corpus/bb_corpus/basic.json b/fuzzing/corpus/bb_corpus/basic.json new file mode 100644 index 000000000..9121b1350 --- /dev/null +++ b/fuzzing/corpus/bb_corpus/basic.json @@ -0,0 +1,6 @@ +{ + "int_key": 42, + "double_key": 3.14159, + "string_key": "test_string", + "bool_key": true +} diff --git a/fuzzing/corpus/bb_corpus/edge.json b/fuzzing/corpus/bb_corpus/edge.json new file mode 100644 index 000000000..8008ef811 --- /dev/null +++ b/fuzzing/corpus/bb_corpus/edge.json @@ -0,0 +1,7 @@ +{ + "max_int": 2147483647, + "min_int": -2147483648, + "zero": 0, + "empty_string": "", + "null_value": null +} diff --git a/fuzzing/corpus/bb_corpus/multiple.json b/fuzzing/corpus/bb_corpus/multiple.json new file mode 100644 index 000000000..cf5cfa76b --- /dev/null +++ b/fuzzing/corpus/bb_corpus/multiple.json @@ -0,0 +1,8 @@ +{ + "key1": 42, + "key2": "string", + "key3": 3.14, + "key4": true, + "key5": -123, + "key6": 99.99 +} diff --git a/fuzzing/corpus/bb_corpus/nested.json b/fuzzing/corpus/bb_corpus/nested.json new file mode 100644 index 000000000..39c4b000e --- /dev/null +++ b/fuzzing/corpus/bb_corpus/nested.json @@ -0,0 +1,11 @@ +{ + "outer_key": { + "inner_int": 100, + "inner_string": "nested" + }, + "array_key": [ + 1, + 2, + 3 + ] +} diff --git a/fuzzing/corpus/bb_corpus/special.json b/fuzzing/corpus/bb_corpus/special.json new file mode 100644 index 000000000..76a6a4b70 --- /dev/null +++ b/fuzzing/corpus/bb_corpus/special.json @@ -0,0 +1,6 @@ +{ + "special@key": 123, + "key_with_underscore": "value", + "KeyWithCaps": true, + "123numeric_start": 456 +} diff --git a/fuzzing/corpus/bt_corpus/corpus1.xml b/fuzzing/corpus/bt_corpus/corpus1.xml new file mode 100644 index 000000000..e625cb41b --- /dev/null +++ b/fuzzing/corpus/bt_corpus/corpus1.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/fuzzing/corpus/bt_corpus/corpus2.xml b/fuzzing/corpus/bt_corpus/corpus2.xml new file mode 100644 index 000000000..461e53c64 --- /dev/null +++ b/fuzzing/corpus/bt_corpus/corpus2.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/fuzzing/corpus/bt_corpus/corpus3.xml b/fuzzing/corpus/bt_corpus/corpus3.xml new file mode 100644 index 000000000..e21ea8adf --- /dev/null +++ b/fuzzing/corpus/bt_corpus/corpus3.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/fuzzing/corpus/bt_corpus/corpus4.xml b/fuzzing/corpus/bt_corpus/corpus4.xml new file mode 100644 index 000000000..3111d8be4 --- /dev/null +++ b/fuzzing/corpus/bt_corpus/corpus4.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/fuzzing/corpus/bt_corpus/sample1 b/fuzzing/corpus/bt_corpus/sample1 new file mode 100644 index 000000000..932d7e835 --- /dev/null +++ b/fuzzing/corpus/bt_corpus/sample1 @@ -0,0 +1 @@ + diff --git a/fuzzing/corpus/script_corpus/sample1 b/fuzzing/corpus/script_corpus/sample1 new file mode 100644 index 000000000..36c81d57f --- /dev/null +++ b/fuzzing/corpus/script_corpus/sample1 @@ -0,0 +1,3 @@ +a : = 1; +b : = 2; +a + b diff --git a/fuzzing/corpus/script_corpus/sample2 b/fuzzing/corpus/script_corpus/sample2 new file mode 100644 index 000000000..dc1d11e2c --- /dev/null +++ b/fuzzing/corpus/script_corpus/sample2 @@ -0,0 +1,3 @@ +x : = true; +y : = false; +x and y diff --git a/fuzzing/corpus/script_corpus/sample3 b/fuzzing/corpus/script_corpus/sample3 new file mode 100644 index 000000000..39ce18d0c --- /dev/null +++ b/fuzzing/corpus/script_corpus/sample3 @@ -0,0 +1,2 @@ +str : = 'hello'; +len(str) diff --git a/fuzzing/script_fuzzer.cpp b/fuzzing/script_fuzzer.cpp new file mode 100644 index 000000000..b507dcf17 --- /dev/null +++ b/fuzzing/script_fuzzer.cpp @@ -0,0 +1,70 @@ +#include +#include "behaviortree_cpp/scripting/script_parser.hpp" +#include "behaviortree_cpp/blackboard.h" +#include "behaviortree_cpp/basic_types.h" +#include +#include +#include +#include + +extern "C" int LLVMFuzzerTestOneInput(const uint8_t* data, size_t size) +{ + if(size < 4) + { + return 0; + } + + FuzzedDataProvider fuzz_data(data, size); + + try + { + BT::Ast::Environment env; + env.vars = BT::Blackboard::create(); + env.enums = std::make_shared(); + + // Add some test variables to the blackboard + env.vars->set("test_int", 42); + env.vars->set("test_double", 3.14); + env.vars->set("test_bool", true); + env.vars->set("test_string", std::string("test")); + + // Add some test enums + (*env.enums)["RUNNING"] = 0; + (*env.enums)["SUCCESS"] = 1; + (*env.enums)["FAILURE"] = 2; + + std::string script = fuzz_data.ConsumeRandomLengthString(); + + auto validation_result = BT::ValidateScript(script); + + if(!validation_result) + { + auto parsed_script = BT::ParseScript(script); + if(parsed_script) + { + try + { + auto result = parsed_script.value()(env); + + if(result.isNumber()) + { + volatile auto num = result.cast(); + } + + env.vars->set("result", result); + + BT::Any read_back; + env.vars->get("result", read_back); + } + catch(const BT::RuntimeError&) + {} + } + } + + BT::ParseScriptAndExecute(env, script); + } + catch(const std::exception&) + {} + + return 0; +} diff --git a/include/behaviortree_cpp/action_node.h b/include/behaviortree_cpp/action_node.h index 3f9b64bf4..409e57987 100644 --- a/include/behaviortree_cpp/action_node.h +++ b/include/behaviortree_cpp/action_node.h @@ -99,10 +99,10 @@ class SimpleActionNode : public SyncActionNode * IMPORTANT: this action is quite hard to implement correctly. * Please make sure that you know what you are doing. * - * - In your overriden tick() method, you must check periodically + * - In your overridden tick() method, you must check periodically * the result of the method isHaltRequested() and stop your execution accordingly. * - * - in the overriden halt() method, you can do some cleanup, but do not forget to + * - in the overridden halt() method, you can do some cleanup, but do not forget to * invoke the base class method ThreadedAction::halt(); * * - remember, with few exceptions, a halted ThreadedAction must return NodeStatus::IDLE. diff --git a/include/behaviortree_cpp/actions/pop_from_queue.hpp b/include/behaviortree_cpp/actions/pop_from_queue.hpp index a2ebb1fe1..34b905fde 100644 --- a/include/behaviortree_cpp/actions/pop_from_queue.hpp +++ b/include/behaviortree_cpp/actions/pop_from_queue.hpp @@ -20,7 +20,7 @@ /** * Template Action used in ex04_waypoints.cpp example. * - * Its purpose is to do make it easy to create while loops wich consume the elements of a queue. + * Its purpose is to do make it easy to create while loops which consume the elements of a queue. * * Note that modifying the queue is not thread safe, therefore the action that creates the queue * or push elements into it, must be Synchronous. @@ -47,7 +47,7 @@ struct ProtectedQueue * * We avoid this using reference semantic (wrapping the object in a shared_ptr). * Unfortunately, remember that this makes our access to the list not thread-safe! - * This is the reason why we add a mutex to be used when modyfying the ProtectedQueue::items + * This is the reason why we add a mutex to be used when modifying the ProtectedQueue::items * * */ @@ -95,7 +95,7 @@ class PopFromQueue : public SyncActionNode }; /** - * Get the size of a queue. Usefull is you want to write something like: + * Get the size of a queue. Useful when you want to write something like: * * * diff --git a/include/behaviortree_cpp/actions/set_blackboard_node.h b/include/behaviortree_cpp/actions/set_blackboard_node.h index 9882cea6f..05282c0c0 100644 --- a/include/behaviortree_cpp/actions/set_blackboard_node.h +++ b/include/behaviortree_cpp/actions/set_blackboard_node.h @@ -44,7 +44,7 @@ class SetBlackboardNode : public SyncActionNode static PortsList providedPorts() { - return { InputPort("value", "Value to be written int othe output_key"), + return { InputPort("value", "Value to be written into the output_key"), BidirectionalPort("output_key", "Name of the blackboard entry where the " "value should be written") }; } @@ -61,13 +61,16 @@ class SetBlackboardNode : public SyncActionNode const std::string value_str = config().input_ports.at("value"); StringView stripped_key; + BT::Any out_value; + + std::shared_ptr dst_entry = + config().blackboard->getEntry(output_key); + if(isBlackboardPointer(value_str, &stripped_key)) { const auto input_key = std::string(stripped_key); std::shared_ptr src_entry = config().blackboard->getEntry(input_key); - std::shared_ptr dst_entry = - config().blackboard->getEntry(output_key); if(!src_entry) { @@ -78,13 +81,35 @@ class SetBlackboardNode : public SyncActionNode config().blackboard->createEntry(output_key, src_entry->info); dst_entry = config().blackboard->getEntry(output_key); } - dst_entry->value = src_entry->value; + + out_value = src_entry->value; } else { - config().blackboard->set(output_key, value_str); + out_value = BT::Any(value_str); + } + + if(out_value.empty()) + return NodeStatus::FAILURE; + + // avoid type issues when port is remapped: current implementation of the set might be a little bit problematic for initialized on the fly values + // this still does not attack math issues + if(dst_entry && dst_entry->info.type() != typeid(std::string) && out_value.isString()) + { + try + { + out_value = dst_entry->info.parseString(out_value.cast()); + } + catch(const std::exception& e) + { + throw LogicError("Can't convert string [", out_value.cast(), + "] to type [", BT::demangle(dst_entry->info.type()), + "]: ", e.what()); + } } + config().blackboard->set(output_key, out_value); + return NodeStatus::SUCCESS; } }; diff --git a/include/behaviortree_cpp/actions/test_node.h b/include/behaviortree_cpp/actions/test_node.h index c144fd43a..9aaabb829 100644 --- a/include/behaviortree_cpp/actions/test_node.h +++ b/include/behaviortree_cpp/actions/test_node.h @@ -37,9 +37,9 @@ struct TestNodeConfig /// if async_delay > 0, this action become asynchronous and wait this amount of time std::chrono::milliseconds async_delay = std::chrono::milliseconds(0); - /// Function invoked when the action is completed. By default just return [return_status] - /// Override it to intorduce more comple cases - std::function complete_func = [this]() { return return_status; }; + /// Function invoked when the action is completed. + /// If not specified, the node will return [return_status] + std::function complete_func; }; /** @@ -50,21 +50,28 @@ struct TestNodeConfig * 3. Either complete immediately (synchronous action), or after a * given period of time (asynchronous action) * - * This behavior is changed by the parameters pased with TestNodeConfig. + * This behavior is changed by the parameters passed with TestNodeConfig. * * This particular node is created by the factory when TestNodeConfig is * added as a substitution rule: * - * TestNodeConfig test_config; + * auto test_config = std::make_shared(); * // change fields of test_config * factory.addSubstitutionRule(pattern, test_config); * - * See tutorial 11 for more details. + * See tutorial 15 for more details. */ class TestNode : public BT::StatefulActionNode { public: - TestNode(const std::string& name, const NodeConfig& config, TestNodeConfig test_config); + // This constructor is deprecated, because it may cause problems if TestNodeConfig::complete_func is capturing + // a reference to the TestNode, i.e. [this]. Use the constructor with std::shared_ptr instead. + // For more details, see https://github.com/BehaviorTree/BehaviorTree.CPP/pull/967 + [[deprecated("prefer the constructor with std::shared_ptr")]] TestNode( + const std::string& name, const NodeConfig& config, TestNodeConfig test_config); + + TestNode(const std::string& name, const NodeConfig& config, + std::shared_ptr test_config); static PortsList providedPorts() { @@ -80,7 +87,7 @@ class TestNode : public BT::StatefulActionNode NodeStatus onCompleted(); - TestNodeConfig _test_config; + std::shared_ptr _config; ScriptFunction _success_executor; ScriptFunction _failure_executor; ScriptFunction _post_executor; diff --git a/include/behaviortree_cpp/basic_types.h b/include/behaviortree_cpp/basic_types.h index 244f4b2a3..bceef4fd9 100644 --- a/include/behaviortree_cpp/basic_types.h +++ b/include/behaviortree_cpp/basic_types.h @@ -342,6 +342,8 @@ struct Timestamp [[nodiscard]] bool IsAllowedPortName(StringView str); +[[nodiscard]] bool IsReservedAttribute(StringView str); + class TypeInfo { public: diff --git a/include/behaviortree_cpp/bt_factory.h b/include/behaviortree_cpp/bt_factory.h index f7d7a8b1c..020c9ea1d 100644 --- a/include/behaviortree_cpp/bt_factory.h +++ b/include/behaviortree_cpp/bt_factory.h @@ -109,8 +109,8 @@ class Tree Tree(const Tree&) = delete; Tree& operator=(const Tree&) = delete; - Tree(Tree&& other); - Tree& operator=(Tree&& other); + Tree(Tree&& other) = default; + Tree& operator=(Tree&& other) = default; void initialize(); @@ -149,7 +149,7 @@ class Tree [[nodiscard]] Blackboard::Ptr rootBlackboard(); //Call the visitor for each node of the tree. - void applyVisitor(const std::function& visitor); + void applyVisitor(const std::function& visitor) const; //Call the visitor for each node of the tree. void applyVisitor(const std::function& visitor); @@ -215,8 +215,8 @@ class BehaviorTreeFactory BehaviorTreeFactory(const BehaviorTreeFactory& other) = delete; BehaviorTreeFactory& operator=(const BehaviorTreeFactory& other) = delete; - BehaviorTreeFactory(BehaviorTreeFactory&& other) noexcept; - BehaviorTreeFactory& operator=(BehaviorTreeFactory&& other) noexcept; + BehaviorTreeFactory(BehaviorTreeFactory&& other) noexcept = default; + BehaviorTreeFactory& operator=(BehaviorTreeFactory&& other) noexcept = default; /// Remove a registered ID. bool unregisterBuilder(const std::string& ID); @@ -279,9 +279,8 @@ class BehaviorTreeFactory /** * @brief registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp, and calls registerFromPlugin for each library. * @throws If not compiled with ROS support or if the library cannot load for any reason - * */ - void registerFromROSPlugins(); + [[deprecated("Removed support for ROS1")]] void registerFromROSPlugins(); /** * @brief registerBehaviorTreeFromFile. @@ -470,12 +469,13 @@ class BehaviorTreeFactory void clearSubstitutionRules(); - using SubstitutionRule = std::variant; + using SubstitutionRule = + std::variant>; /** * @brief addSubstitutionRule replace a node with another one when the tree is * created. - * If the rule ia a string, we will use a diferent node type (already registered) + * If the rule ia a string, we will use a different node type (already registered) * instead. * If the rule is a TestNodeConfig, a test node with that configuration will be created instead. * @@ -526,7 +526,7 @@ std::vector BlackboardBackup(const BT::Tree& tree); * @brief BlackboardRestore uses Blackboard::cloneInto to restore * all the blackboards of the tree * - * @param backup a vectror of blackboards + * @param backup a vector of blackboards * @param tree the destination */ void BlackboardRestore(const std::vector& backup, BT::Tree& tree); diff --git a/include/behaviortree_cpp/decorators/loop_node.h b/include/behaviortree_cpp/decorators/loop_node.h index 9d210ca56..18240c504 100644 --- a/include/behaviortree_cpp/decorators/loop_node.h +++ b/include/behaviortree_cpp/decorators/loop_node.h @@ -60,7 +60,8 @@ class LoopNode : public DecoratorNode // special case: the port contains a string that was converted to SharedQueue if(static_queue_) { - current_queue_ = static_queue_; + current_queue_ = std::make_shared>(); + *current_queue_ = *static_queue_; } } diff --git a/include/behaviortree_cpp/decorators/run_once_node.h b/include/behaviortree_cpp/decorators/run_once_node.h index a40d86cdb..a3083d97e 100644 --- a/include/behaviortree_cpp/decorators/run_once_node.h +++ b/include/behaviortree_cpp/decorators/run_once_node.h @@ -42,7 +42,7 @@ class RunOnceNode : public DecoratorNode { return { InputPort("then_skip", true, "If true, skip after the first execution, " - "otherwise return the same NodeStatus returned once bu the " + "otherwise return the same NodeStatus returned once by the " "child.") }; } diff --git a/include/behaviortree_cpp/decorators/script_precondition.h b/include/behaviortree_cpp/decorators/script_precondition.h index 4fa50b717..e244c7a50 100644 --- a/include/behaviortree_cpp/decorators/script_precondition.h +++ b/include/behaviortree_cpp/decorators/script_precondition.h @@ -48,20 +48,23 @@ class PreconditionNode : public DecoratorNode throw RuntimeError("Missing parameter [else] in Precondition"); } + // Only check the 'if' script if we haven't started ticking the children yet. Ast::Environment env = { config().blackboard, config().enums }; - if(_executor(env).cast()) + bool tick_children = + _children_running || (_children_running = _executor(env).cast()); + + if(!tick_children) { - auto const child_status = child_node_->executeTick(); - if(isStatusCompleted(child_status)) - { - resetChild(); - } - return child_status; + return else_return; } - else + + auto const child_status = child_node_->executeTick(); + if(isStatusCompleted(child_status)) { - return else_return; + resetChild(); + _children_running = false; } + return child_status; } void loadExecutor() @@ -89,6 +92,7 @@ class PreconditionNode : public DecoratorNode std::string _script; ScriptFunction _executor; + bool _children_running = false; }; } // namespace BT diff --git a/include/behaviortree_cpp/flatbuffers/bt_flatbuffer_helper.h b/include/behaviortree_cpp/flatbuffers/bt_flatbuffer_helper.h index 426ccbe2d..6629cdf54 100644 --- a/include/behaviortree_cpp/flatbuffers/bt_flatbuffer_helper.h +++ b/include/behaviortree_cpp/flatbuffers/bt_flatbuffer_helper.h @@ -136,7 +136,7 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde builder.Finish(behavior_tree); } -/** Serialize manually the informations about state transition +/** Serialize manually the information about state transition * No flatbuffer serialization here */ inline SerializedTransition SerializeTransition(uint16_t UID, Duration timestamp, diff --git a/include/behaviortree_cpp/json_export.h b/include/behaviortree_cpp/json_export.h index 9274ad788..dfe9b0fee 100644 --- a/include/behaviortree_cpp/json_export.h +++ b/include/behaviortree_cpp/json_export.h @@ -11,7 +11,7 @@ namespace BT { /** -* To add new type to the JSON library, you should follow these isntructions: +* To add new type to the JSON library, you should follow these instructions: * https://json.nlohmann.me/features/arbitrary_types/ * * Considering for instance the type: @@ -51,6 +51,10 @@ class JsonExporter public: static JsonExporter& get(); + // Delete copy constructors as can only be this one global instance. + JsonExporter& operator=(JsonExporter&&) = delete; + JsonExporter& operator=(JsonExporter&) = delete; + /** * @brief toJson adds the content of "any" to the JSON "destination". * @@ -80,22 +84,31 @@ class JsonExporter template Expected fromJson(const nlohmann::json& source) const; - /// Register new JSON converters with addConverter(). - /// You should have used first the macro BT_JSON_CONVERTER + /** + * @brief Register new JSON converters with addConverter(). + * You should used first the macro BT_JSON_CONVERTER. + * The conversions from/to vector are automatically registered. + */ template void addConverter(); /** * @brief addConverter register a to_json function that converts a json to a type T. + * The conversion to std:vector is automatically registered. * * @param to_json the function with signature void(const T&, nlohmann::json&) - * @param add_type if true, add a field called [__type] with the name ofthe type. - * */ + * @param add_type if true, add a field called [__type] with the name of the type. + */ template void addConverter(std::function to_json, bool add_type = true); - /// Register custom from_json converter directly. + /** + * @brief addConverter register a from_json function that converts a json to a type T. + * The conversions from std::vector is automatically registered. + * + * @param from_json the function with signature void(const nlohmann::json&, T&) + */ template void addConverter(std::function from_json); @@ -105,6 +118,7 @@ class JsonExporter std::unordered_map to_json_converters_; std::unordered_map from_json_converters_; + std::unordered_map from_json_array_converters_; std::unordered_map type_names_; }; @@ -114,12 +128,12 @@ inline Expected JsonExporter::fromJson(const nlohmann::json& source) const auto res = fromJson(source); if(!res) { - return nonstd::expected_lite::make_unexpected(res.error()); + return nonstd::make_unexpected(res.error()); } auto casted = res->first.tryCast(); if(!casted) { - return nonstd::expected_lite::make_unexpected(casted.error()); + return nonstd::make_unexpected(casted.error()); } return *casted; } @@ -129,6 +143,15 @@ inline Expected JsonExporter::fromJson(const nlohmann::json& source) const template inline void JsonExporter::addConverter() { + // we need to get the name of the type + nlohmann::json const js = T{}; + // we insert both the name obtained from JSON and demangle + if(js.contains("__type")) + { + type_names_.insert({ std::string(js["__type"]), BT::TypeInfo::Create() }); + } + type_names_.insert({ BT::demangle(typeid(T)), BT::TypeInfo::Create() }); + ToJonConverter to_converter = [](const BT::Any& entry, nlohmann::json& dst) { dst = *const_cast(entry).castPtr(); }; @@ -139,16 +162,23 @@ inline void JsonExporter::addConverter() return { BT::Any(value), BT::TypeInfo::Create() }; }; - // we need to get the name of the type - nlohmann::json const js = T{}; - // we insert both the name obtained from JSON and demangle - if(js.contains("__type")) - { - type_names_.insert({ std::string(js["__type"]), BT::TypeInfo::Create() }); - } - type_names_.insert({ BT::demangle(typeid(T)), BT::TypeInfo::Create() }); - from_json_converters_.insert({ typeid(T), from_converter }); + + //---- include vectors of T + ToJonConverter to_array_converter = [](const BT::Any& entry, nlohmann::json& dst) { + dst = *const_cast(entry).castPtr>(); + }; + to_json_converters_.insert({ typeid(std::vector), to_array_converter }); + + FromJonConverter from_array_converter = [](const nlohmann::json& src) -> Entry { + std::vector value; + for(const auto& item : src) + { + value.push_back(item.get()); + } + return { BT::Any(value), BT::TypeInfo::Create>() }; + }; + from_json_array_converters_.insert({ typeid(T), from_array_converter }); } template @@ -163,6 +193,18 @@ inline void JsonExporter::addConverter( } }; to_json_converters_.insert({ typeid(T), std::move(converter) }); + //--------------------------------------------- + // add the vector converter + auto vector_converter = [converter](const BT::Any& entry, nlohmann::json& json) { + auto& vec = *const_cast(entry).castPtr>(); + for(const auto& item : vec) + { + nlohmann::json item_json; + converter(BT::Any(item), item_json); + json.push_back(item_json); + } + }; + to_json_converters_.insert({ typeid(std::vector), std::move(vector_converter) }); } template @@ -176,6 +218,19 @@ JsonExporter::addConverter(std::function func) }; type_names_.insert({ BT::demangle(typeid(T)), BT::TypeInfo::Create() }); from_json_converters_.insert({ typeid(T), std::move(converter) }); + //--------------------------------------------- + // add the vector converter + auto vector_converter = [func](const nlohmann::json& json) -> Entry { + std::vector tmp; + for(const auto& item : json) + { + T item_tmp; + func(item, item_tmp); + tmp.push_back(item_tmp); + } + return { BT::Any(tmp), BT::TypeInfo::Create>() }; + }; + from_json_array_converters_.insert({ typeid(T), std::move(vector_converter) }); } template diff --git a/include/behaviortree_cpp/loggers/groot2_protocol.h b/include/behaviortree_cpp/loggers/groot2_protocol.h index 507f2a00a..5c27b5cb5 100644 --- a/include/behaviortree_cpp/loggers/groot2_protocol.h +++ b/include/behaviortree_cpp/loggers/groot2_protocol.h @@ -27,11 +27,11 @@ namespace BT::Monitor enum RequestType : uint8_t { - // Request the entire tree defintion as XML + // Request the entire tree definition as XML FULLTREE = 'T', - // Request the staus of all the nodes + // Request the status of all the nodes STATUS = 'S', - // retrieve the valus in a set of blackboards + // retrieve the values in a set of blackboards BLACKBOARD = 'B', // Groot requests the insertion of a hook diff --git a/include/behaviortree_cpp/scripting/operators.hpp b/include/behaviortree_cpp/scripting/operators.hpp index f44b0d4ea..4d41b6a88 100644 --- a/include/behaviortree_cpp/scripting/operators.hpp +++ b/include/behaviortree_cpp/scripting/operators.hpp @@ -27,7 +27,7 @@ using SimpleString = SafeAny::SimpleString; using expr_ptr = std::shared_ptr; -// extended strin to number that consider enums and booleans +// extended string to number that consider enums and booleans inline double StringToDouble(const Any& value, const Environment& env) { const auto str = value.cast(); @@ -129,6 +129,11 @@ struct ExprUnaryArithmetic : ExprBase case negate: return Any(-rv); case complement: + if(rv > static_cast(std::numeric_limits::max()) || + rv < static_cast(std::numeric_limits::min())) + { + throw RuntimeError("Number out of range for bitwise operation"); + } return Any(static_cast(~static_cast(rv))); case logical_not: return Any(static_cast(!static_cast(rv))); diff --git a/include/behaviortree_cpp/tree_node.h b/include/behaviortree_cpp/tree_node.h index 537176519..0087ce210 100644 --- a/include/behaviortree_cpp/tree_node.h +++ b/include/behaviortree_cpp/tree_node.h @@ -41,6 +41,7 @@ struct TreeNodeManifest }; using PortsRemapping = std::unordered_map; +using NonPortAttributes = std::unordered_map; enum class PreCond { @@ -52,6 +53,10 @@ enum class PreCond COUNT_ }; +static const std::array PreCondNames = { // + "_failureIf", "_successIf", "_skipIf", "_while" +}; + enum class PostCond { // order of the enums also tell us the execution order @@ -62,11 +67,15 @@ enum class PostCond COUNT_ }; +static const std::array PostCondNames = { // + "_onHalted", "_onFailure", "_onSuccess", "_post" +}; + template <> -[[nodiscard]] std::string toStr(const BT::PostCond& status); +[[nodiscard]] std::string toStr(const BT::PostCond& cond); template <> -[[nodiscard]] std::string toStr(const BT::PreCond& status); +[[nodiscard]] std::string toStr(const BT::PreCond& cond); using ScriptingEnumsRegistry = std::unordered_map; @@ -84,9 +93,13 @@ struct NodeConfig // output ports PortsRemapping output_ports; + // Any other attributes found in the xml that are not parsed as ports + // or built-in identifier (e.g. anything with a leading '_') + NonPortAttributes other_attributes; + const TreeNodeManifest* manifest = nullptr; - // Numberic unique identifier + // Numeric unique identifier uint16_t uid = 0; // Unique human-readable name, that encapsulate the subtree // hierarchy, for instance, given 2 nested trees, it should be: @@ -196,7 +209,7 @@ class TreeNode * NodeStatus myCallback(TreeNode& node, NodeStatus status) * * This callback is executed AFTER the tick() and, if it returns SUCCESS or FAILURE, - * the value returned by the actual tick() is overriden with this one. + * the value returned by the actual tick() is overridden with this one. */ void setPostTickFunction(PostTickCallback callback); @@ -238,7 +251,7 @@ class TreeNode /** * @brief getInputStamped is similar to getInput(dey, destination), - * but it returne also the Timestamp object, that can be used to check if + * but it returns also the Timestamp object, that can be used to check if * a value was updated and when. * * @param key the name of the port. @@ -285,7 +298,7 @@ class TreeNode * @brief setOutput modifies the content of an Output port * @param key the name of the port. * @param value new value - * @return valid Result, if succesful. + * @return valid Result, if successful. */ template Result setOutput(const std::string& key, const T& value); @@ -585,7 +598,8 @@ inline Result TreeNode::setOutput(const std::string& key, const T& value) if constexpr(std::is_same_v) { - if(config().manifest->ports.at(key).type() != typeid(BT::Any)) + auto port_type = config().manifest->ports.at(key).type(); + if(port_type != typeid(BT::Any) && port_type != typeid(BT::AnyTypeAllowed)) { throw LogicError("setOutput is not allowed, unless the port " "was declared using OutputPort"); diff --git a/include/behaviortree_cpp/utils/convert_impl.hpp b/include/behaviortree_cpp/utils/convert_impl.hpp index 7aef50259..6baaa03fd 100644 --- a/include/behaviortree_cpp/utils/convert_impl.hpp +++ b/include/behaviortree_cpp/utils/convert_impl.hpp @@ -13,6 +13,7 @@ #pragma once #include +#include #include "simple_string.hpp" #undef max @@ -88,9 +89,51 @@ inline void checkLowerLimit(const From& from) template inline void checkTruncation(const From& from) { - if(from != static_cast(static_cast(from))) + // Handle integer to floating point + if constexpr(std::is_integral_v && std::is_floating_point_v) { - throw std::runtime_error("Floating point truncated"); + // Check if value can be represented exactly in the target type + constexpr uint64_t max_exact = (1LL << std::numeric_limits::digits) - 1; + bool doesnt_fit = false; + if constexpr(!std::is_signed_v) + { + doesnt_fit = static_cast(from) > max_exact; + } + else + { + doesnt_fit = std::abs(static_cast(from)) > static_cast(max_exact); + } + if(doesnt_fit) + { + throw std::runtime_error("Loss of precision when converting a large integer number " + "to floating point:" + + std::to_string(from)); + } + } + // Handle floating point to integer + else if constexpr(std::is_floating_point_v && std::is_integral_v) + { + if(from > static_cast(std::numeric_limits::max()) || + from < static_cast(std::numeric_limits::lowest()) || + from != std::nearbyint(from)) + { + throw std::runtime_error("Invalid floating point to integer conversion"); + } + } + // Handle other conversions + else + { + if(from > static_cast(std::numeric_limits::max()) || + from < static_cast(std::numeric_limits::lowest())) + { + throw std::runtime_error("Value outside numeric limits"); + } + To as_target = static_cast(from); + From back_to_source = static_cast(as_target); + if(from != back_to_source) + { + throw std::runtime_error("Value truncated in conversion"); + } } } diff --git a/include/behaviortree_cpp/utils/safe_any.hpp b/include/behaviortree_cpp/utils/safe_any.hpp index 721fe54f5..ce94b2eb7 100644 --- a/include/behaviortree_cpp/utils/safe_any.hpp +++ b/include/behaviortree_cpp/utils/safe_any.hpp @@ -134,7 +134,7 @@ class Any } // copy the value (casting into dst). We preserve the destination type. - void copyInto(Any& dst); + void copyInto(Any& dst) const; // this is different from any_cast, because if allows safe // conversions between arithmetic values and from/to string. @@ -162,32 +162,7 @@ class Any [[nodiscard]] T* castPtr() { static_assert(!std::is_same_v, "The value has been casted internally to " - "[double]. " - "Use that instead"); - static_assert(!SafeAny::details::is_integer() || std::is_same_v, "The" - " va" - "lue" - " ha" - "s " - "bee" - "n " - "cas" - "ted" - " in" - "ter" - "nal" - "ly " - "to " - "[in" - "t64" - "_t]" - ". " - "Use" - " th" - "at " - "ins" - "tea" - "d"); + "[double]. Use that instead"); return _any.empty() ? nullptr : linb::any_cast(&_any); } @@ -245,7 +220,34 @@ class Any template inline bool ValidCast(const SRC& val) { - return (val == static_cast(static_cast(val))); + // First check numeric limits + if constexpr(std::is_arithmetic_v && std::is_arithmetic_v) + { + // Handle conversion to floating point + if constexpr(std::is_floating_point_v) + { + if constexpr(std::is_integral_v) + { + // For integral to float, check if we can represent the value exactly + TO as_float = static_cast(val); + SRC back_conv = static_cast(as_float); + return back_conv == val; + } + } + // Handle conversion to integral + else if constexpr(std::is_integral_v) + { + if(val > static_cast(std::numeric_limits::max()) || + val < static_cast(std::numeric_limits::lowest())) + { + return false; + } + } + } + + TO as_target = static_cast(val); + SRC back_to_source = static_cast(as_target); + return val == back_to_source; } template @@ -319,7 +321,7 @@ inline bool Any::isIntegral() const return _any.type() == typeid(int64_t) || _any.type() == typeid(uint64_t); } -inline void Any::copyInto(Any& dst) +inline void Any::copyInto(Any& dst) const { if(dst.empty()) { @@ -492,7 +494,7 @@ inline nonstd::expected Any::tryCast() const } // special case when the output is an enum. - // We will try first a int convertion + // We will try first a int conversion if constexpr(std::is_enum_v) { if(isNumber()) diff --git a/package.xml b/package.xml index c4cb75729..1d245b625 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp - 4.6.2 + 4.7.2 This package provides the Behavior Trees core library. @@ -14,21 +14,19 @@ ros_environment - catkin - roslib + git + ament_cmake - ament_cmake - rclcpp - ament_index_cpp + rclcpp + ament_index_cpp libsqlite3-dev libzmq3-dev - ament_cmake_gtest + ament_cmake_gtest - catkin - ament_cmake + ament_cmake diff --git a/pixi.lock b/pixi.lock index 4e6708ac4..df4979941 100644 --- a/pixi.lock +++ b/pixi.lock @@ -1,4 +1,4 @@ -version: 4 +version: 5 environments: default: channels: @@ -7,112 +7,128 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.40-hf600244_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-hd590300_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.27.0-hd590300_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2024.2.2-hbcca054_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cffi-1.16.0-py311hb3a22ac_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-3.28.4-hcfe8598_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.8-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.13.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.2.0-hd6cf55c_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.2.0-h338b0a0_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.12.1-hf52228f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.12.1-hf52228f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.2.0-hd6cf55c_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.2.0-h338b0a0_5.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.5.35-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-2.6.32-he073ed8_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.43-h4852527_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2024.12.14-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cffi-1.17.1-py311hf29c0ef_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-3.31.5-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.17.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.14.0-ha770c72_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.14.0-h434a139_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hdbfa832_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_7.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.6-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/keyutils-1.6.1-h166bdaf_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.2-h659d440_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.40-h41732ed_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.6.0-hca28451_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20191231-he28a2e2_2.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.11.1-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20240808-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.6.2-h59595ed_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.6.4-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.2-h7f98852_5.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.2.0-ha9c7c90_105.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-13.2.0-h807b86a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-13.2.0-h807b86a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.58.0-h47da74e_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h77fa898_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-h84ea5a7_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h77fa898_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.3-hb9d3cd8_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.3-hb9d3cd8_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.2.0-h7e041cc_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.18-h36c2ea0_1.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-heb74ff8_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.40.0-h753d276_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.0-h0841786_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.2.0-ha9c7c90_105.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-13.2.0-h7e041cc_5.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-hc0a3c3a_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-h84ea5a7_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.48.0-hd590300_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.2.13-hd590300_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/make-4.3-hd18ef5c_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.4.20240210-h59595ed_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.8.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.2.1-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.2.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-3.6.2-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.21-pyhd8ed1ab_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/make-4.4.1-hb9d3cd8_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.0-h7b32b05_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.1.0-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.11.3-h2755cc3_0_cpython.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.11-4_cp311.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.1-py311h459d7ec_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.11-5_cp311.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py311h2dc5d0c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8228510_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.4-hd590300_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-69.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/sqlite-3.40.0-h4ff8645_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.12-he073ed8_17.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2024a-h0c530f3_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ukkonen-1.0.1-py311h9547e67_4.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.25.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ukkonen-1.0.1-py311hd18a35c_5.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.29.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.3-hbcc6ac9_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.3-hbcc6ac9_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.3-hb9d3cd8_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h59595ed_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.5-hfc55251_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda win-64: - - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-hcfcfb64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2024.2.2-h56e8100_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cffi-1.16.0-py311ha68e1ae_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-3.28.4-hf0feee3_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.8-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.13.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/gmock-1.12.1-h91493d7_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/gtest-1.12.1-h91493d7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.5.35-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.2-heb0366b_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.6.0-hd5e4a3a_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.6.2-h63175ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2024.12.14-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cffi-1.17.1-py311he736701_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-3.31.5-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.17.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/gmock-1.14.0-h57928b3_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/gtest-1.14.0-hc790b64_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.6-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.11.1-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.6.4-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.2-h8ffe710_5.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.18-h8d14728_1.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.3-h2466b09_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-devel-5.6.3-h2466b09_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.40.0-hcfcfb64_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.0-h7dfc565_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.48.0-hcfcfb64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.2.13-hcfcfb64_5.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.8.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.2.1-hcfcfb64_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.2.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-3.6.2-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.21-pyhd8ed1ab_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.0-ha4e3fda_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.1.0-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.11.3-h2628c8c_0_cpython.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.11-4_cp311.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.1-py311ha68e1ae_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-69.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.11-5_cp311.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py311h5082efb_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/sqlite-3.40.0-hcfcfb64_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2024a-h0c530f3_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ukkonen-1.0.1-py311h005e61a_4.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-hcf57466_18.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.38.33130-h82b7239_18.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.25.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.38.33130-hcb4865c_18.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vs2022_win-64-19.38.33130-h0bfb142_18.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.4-h57928b3_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/xz-5.2.6-h8d14728_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ukkonen-1.0.1-py311h3257749_5.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h5fd82a7_24.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34433-h6356254_24.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.29.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34433-hfef2bbc_24.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_24.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/xz-5.6.3-h208afaa_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/xz-tools-5.6.3-h2466b09_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/yaml-0.2.5-h8ffe710_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-h63175ca_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/zstd-1.5.5-h12be248_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-ha9f60a1_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/zstd-1.5.6-h0ea2cb4_0.conda packages: - kind: conda name: _libgcc_mutex @@ -143,97 +159,146 @@ packages: license_family: BSD size: 23621 timestamp: 1650670423406 +- kind: conda + name: binutils + version: '2.43' + build: h4852527_2 + build_number: 2 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_2.conda + sha256: 92be0f8ccd501ceeb3c782e2182e6ea04dca46799038176de40a57bca45512c5 + md5: 348619f90eee04901f4a70615efff35b + depends: + - binutils_impl_linux-64 >=2.43,<2.44.0a0 + license: GPL-3.0-only + license_family: GPL + size: 33876 + timestamp: 1729655402186 - kind: conda name: binutils_impl_linux-64 - version: '2.40' - build: hf600244_0 + version: '2.43' + build: h4bf12b8_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.40-hf600244_0.conda - sha256: a7e0ea2b71a5b03d82e5a58fb6b612ab1c44d72ce161f9aa441f7ba467cd4c8d - md5: 33084421a8c0af6aef1b439707f7662a + url: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_2.conda + sha256: 267e78990247369b13234bda270f31beb56a600b4851a8244e31dd9ad85b3b17 + md5: cf0c5521ac2a20dfa6c662a4009eeef6 depends: - - ld_impl_linux-64 2.40 h41732ed_0 + - ld_impl_linux-64 2.43 h712a8e2_2 - sysroot_linux-64 license: GPL-3.0-only license_family: GPL - size: 5414922 - timestamp: 1674833958334 + size: 5682777 + timestamp: 1729655371045 +- kind: conda + name: binutils_linux-64 + version: '2.43' + build: h4852527_2 + build_number: 2 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.43-h4852527_2.conda + sha256: df52bd8b8b2a20a0c529d9ad08aaf66093ac318aa8a33d270f18274341a77062 + md5: 18aba879ddf1f8f28145ca6fcb873d8c + depends: + - binutils_impl_linux-64 2.43 h4bf12b8_2 + license: GPL-3.0-only + license_family: GPL + size: 34945 + timestamp: 1729655404893 - kind: conda name: bzip2 version: 1.0.8 - build: hcfcfb64_5 - build_number: 5 + build: h2466b09_7 + build_number: 7 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-hcfcfb64_5.conda - sha256: ae5f47a5c86fd6db822931255dcf017eb12f60c77f07dc782ccb477f7808aab2 - md5: 26eb8ca6ea332b675e11704cce84a3be + url: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda + sha256: 35a5dad92e88fdd7fc405e864ec239486f4f31eec229e31686e61a140a8e573b + md5: 276e7ffe9ffe39688abc665ef0f45596 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: bzip2-1.0.6 license_family: BSD - size: 124580 - timestamp: 1699280668742 + size: 54927 + timestamp: 1720974860185 - kind: conda name: bzip2 version: 1.0.8 - build: hd590300_5 - build_number: 5 + build: h4bc722e_7 + build_number: 7 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-hd590300_5.conda - sha256: 242c0c324507ee172c0e0dd2045814e746bb303d1eb78870d182ceb0abc726a8 - md5: 69b8b6202a07720f448be700e300ccf4 + url: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda + sha256: 5ced96500d945fb286c9c838e54fa759aa04a7129c59800f0846b4335cee770d + md5: 62ee74e96c5ebb0af99386de58cf9553 depends: + - __glibc >=2.17,<3.0.a0 - libgcc-ng >=12 license: bzip2-1.0.6 license_family: BSD - size: 254228 - timestamp: 1699279927352 + size: 252783 + timestamp: 1720974456583 - kind: conda name: c-ares - version: 1.27.0 - build: hd590300_0 + version: 1.34.4 + build: hb9d3cd8_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.27.0-hd590300_0.conda - sha256: 2a5866b19d28cb963fab291a62ff1c884291b9d6f59de14643e52f103e255749 - md5: f6afff0e9ee08d2f1b897881a4f38cdb + url: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + sha256: d4f28d87b6339b94f74762c0076e29c8ef8ddfff51a564a92da2843573c18320 + md5: e2775acf57efd5af15b8e3d1d74d72d3 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 license: MIT license_family: MIT - size: 163578 - timestamp: 1708684786032 + size: 206085 + timestamp: 1734208189009 +- kind: conda + name: c-compiler + version: 1.9.0 + build: h2b85faf_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda + sha256: 1e4b86b0f3d4ce9f3787b8f62e9f2c5683287f19593131640eed01cbdad38168 + md5: 3cb814f83f1f71ac1985013697f80cc1 + depends: + - binutils + - gcc + - gcc_linux-64 13.* + license: BSD-3-Clause + license_family: BSD + size: 6196 + timestamp: 1736437002021 - kind: conda name: ca-certificates - version: 2024.2.2 + version: 2024.12.14 build: h56e8100_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2024.2.2-h56e8100_0.conda - sha256: 4d587088ecccd393fec3420b64f1af4ee1a0e6897a45cfd5ef38055322cea5d0 - md5: 63da060240ab8087b60d1357051ea7d6 + url: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2024.12.14-h56e8100_0.conda + sha256: 424d82db36cd26234bc4772426170efd60e888c2aed0099a257a95e131683a5e + md5: cb2eaeb88549ddb27af533eccf9a45c1 license: ISC - size: 155886 - timestamp: 1706843918052 + size: 157422 + timestamp: 1734208404685 - kind: conda name: ca-certificates - version: 2024.2.2 + version: 2024.12.14 build: hbcca054_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2024.2.2-hbcca054_0.conda - sha256: 91d81bfecdbb142c15066df70cc952590ae8991670198f92c66b62019b251aeb - md5: 2f4327a1cbe7f022401b236e915a5fef + url: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2024.12.14-hbcca054_0.conda + sha256: 1afd7274cbc9a334d6d0bc62fa760acc7afdaceb0b91a8df370ec01fd75dc7dd + md5: 720523eb0d6a9b0f6120c16b2aa4e7de license: ISC - size: 155432 - timestamp: 1706843687645 + size: 157088 + timestamp: 1734208393264 - kind: conda name: cffi - version: 1.16.0 - build: py311ha68e1ae_0 + version: 1.17.1 + build: py311he736701_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/cffi-1.16.0-py311ha68e1ae_0.conda - sha256: eb7463fe3785dd9ac0b3b1e5fea3b721d20eb082e194cab0af8d9ff28c28934f - md5: d109d6e767c4890ea32880b8bfa4a3b6 + url: https://conda.anaconda.org/conda-forge/win-64/cffi-1.17.1-py311he736701_0.conda + sha256: 9689fbd8a31fdf273f826601e90146006f6631619767a67955048c7ad7798a1d + md5: e1c69be23bd05471a6c623e91680ad59 depends: - pycparser - python >=3.11,<3.12.0a0 @@ -243,285 +308,355 @@ packages: - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 297043 - timestamp: 1696002186279 + size: 297627 + timestamp: 1725561079708 - kind: conda name: cffi - version: 1.16.0 - build: py311hb3a22ac_0 + version: 1.17.1 + build: py311hf29c0ef_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/cffi-1.16.0-py311hb3a22ac_0.conda - sha256: b71c94528ca0c35133da4b7ef69b51a0b55eeee570376057f3d2ad60c3ab1444 - md5: b3469563ac5e808b0cd92810d0697043 + url: https://conda.anaconda.org/conda-forge/linux-64/cffi-1.17.1-py311hf29c0ef_0.conda + sha256: bc47aa39c8254e9e487b8bcd74cfa3b4a3de3648869eb1a0b89905986b668e35 + md5: 55553ecd5328336368db611f350b7039 depends: + - __glibc >=2.17,<3.0.a0 - libffi >=3.4,<4.0a0 - - libgcc-ng >=12 + - libgcc >=13 - pycparser - python >=3.11,<3.12.0a0 - python_abi 3.11.* *_cp311 license: MIT license_family: MIT - size: 300207 - timestamp: 1696001873452 + size: 302115 + timestamp: 1725560701719 - kind: conda name: cfgv version: 3.3.1 - build: pyhd8ed1ab_0 + build: pyhd8ed1ab_1 + build_number: 1 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_0.tar.bz2 - sha256: fbc03537a27ef756162c49b1d0608bf7ab12fa5e38ceb8563d6f4859e835ac5c - md5: ebb5f5f7dc4f1a3780ef7ea7738db08c + url: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda + sha256: d5696636733b3c301054b948cdd793f118efacce361d9bd4afb57d5980a9064f + md5: 57df494053e17dce2ac3a0b33e1b2a2e depends: - - python >=3.6.1 + - python >=3.9 license: MIT license_family: MIT - size: 10788 - timestamp: 1629909423398 + size: 12973 + timestamp: 1734267180483 - kind: conda name: cmake - version: 3.28.4 - build: hcfe8598_0 + version: 3.31.5 + build: h74e3db0_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/cmake-3.28.4-hcfe8598_0.conda - sha256: 6c7d7552e0ce3b142d0f18de64b6d9f1eccc8825aa3b7127a4000e539d73a9f7 - md5: 8f3da5e9e920897a86ce0abece94935b + url: https://conda.anaconda.org/conda-forge/linux-64/cmake-3.31.5-h74e3db0_0.conda + sha256: e9c3cb0dde572670b334e5b753264af96c957dba6c9fda4725ba9594eab0dabf + md5: 9913704374f264a9880af3fbaf99f7f1 depends: + - __glibc >=2.17,<3.0.a0 - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.6.0,<9.0a0 - - libexpat >=2.6.2,<3.0a0 - - libgcc-ng >=12 - - libstdcxx-ng >=12 - - libuv >=1.48.0,<2.0a0 - - libzlib >=1.2.13,<1.3.0a0 - - ncurses >=6.4.20240210,<7.0a0 - - rhash >=1.4.4,<2.0a0 - - xz >=5.2.6,<6.0a0 - - zstd >=1.5.5,<1.6.0a0 + - libcurl >=8.11.1,<9.0a0 + - libexpat >=2.6.4,<3.0a0 + - libgcc >=13 + - liblzma >=5.6.3,<6.0a0 + - libstdcxx >=13 + - libuv >=1.50.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - ncurses >=6.5,<7.0a0 + - rhash >=1.4.5,<2.0a0 + - zstd >=1.5.6,<1.6.0a0 license: BSD-3-Clause license_family: BSD - size: 18695647 - timestamp: 1710960841751 + size: 20374668 + timestamp: 1737767797766 - kind: conda name: cmake - version: 3.28.4 - build: hf0feee3_0 + version: 3.31.5 + build: hff78f93_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/cmake-3.28.4-hf0feee3_0.conda - sha256: 793677299ffd26ea6fcd142a52136e5dc15b30059c8240d29c3dc95467923fe8 - md5: 53ae1dbb7b800e771b5182e3c641d207 + url: https://conda.anaconda.org/conda-forge/win-64/cmake-3.31.5-hff78f93_0.conda + sha256: c18dbfcdb40fb6510db4324196484da99b2828e5f57f58b18bbfb2003bc87677 + md5: a9a4fe562f0825874acf3818ed2eb431 depends: - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.6.0,<9.0a0 - - libexpat >=2.6.2,<3.0a0 - - libuv >=1.48.0,<2.0a0 - - libzlib >=1.2.13,<1.3.0a0 + - libcurl >=8.11.1,<9.0a0 + - libexpat >=2.6.4,<3.0a0 + - liblzma >=5.6.3,<6.0a0 + - libuv >=1.50.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 - vc14_runtime >=14.29.30139 - - xz >=5.2.6,<6.0a0 - - zstd >=1.5.5,<1.6.0a0 + - zstd >=1.5.6,<1.6.0a0 + license: BSD-3-Clause + license_family: BSD + size: 14586939 + timestamp: 1737768623461 +- kind: conda + name: cxx-compiler + version: 1.9.0 + build: h1a2810e_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda + sha256: 5efc51b8e7d87fc5380f00ace9f9c758142eade520a63d3631d2616d1c1b25f9 + md5: 1ce8b218d359d9ed0ab481f2a3f3c512 + depends: + - c-compiler 1.9.0 h2b85faf_0 + - gxx + - gxx_linux-64 13.* license: BSD-3-Clause license_family: BSD - size: 13871194 - timestamp: 1710961869326 + size: 6168 + timestamp: 1736437002465 +- kind: conda + name: cxx-compiler + version: 1.9.0 + build: h91493d7_0 + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda + sha256: b7ebc992f8ff3d5f9f40ea3555534440a0438fead4dd5d1dea60113ce224b487 + md5: 6c4b643c7dd8f13dafc8679ffc5671eb + depends: + - vs2019_win-64 + license: BSD-3-Clause + license_family: BSD + size: 6528 + timestamp: 1736437098756 - kind: conda name: distlib - version: 0.3.8 - build: pyhd8ed1ab_0 + version: 0.3.9 + build: pyhd8ed1ab_1 + build_number: 1 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.8-pyhd8ed1ab_0.conda - sha256: 3ff11acdd5cc2f80227682966916e878e45ced94f59c402efb94911a5774e84e - md5: db16c66b759a64dc5183d69cc3745a52 + url: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda + sha256: 0e160c21776bd881b79ce70053e59736f51036784fa43a50da10a04f0c1b9c45 + md5: 8d88f4a2242e6b96f9ecff9a6a05b2f1 depends: - - python 2.7|>=3.6 + - python >=3.9 license: Apache-2.0 license_family: APACHE - size: 274915 - timestamp: 1702383349284 + size: 274151 + timestamp: 1733238487461 - kind: conda name: filelock - version: 3.13.1 + version: 3.17.0 build: pyhd8ed1ab_0 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/filelock-3.13.1-pyhd8ed1ab_0.conda - sha256: 4d742d91412d1f163e5399d2b50c5d479694ebcd309127abb549ca3977f89d2b - md5: 0c1729b74a8152fde6a38ba0a2ab9f45 + url: https://conda.anaconda.org/conda-forge/noarch/filelock-3.17.0-pyhd8ed1ab_0.conda + sha256: 006d7e5a0c17a6973596dd86bfc80d74ce541144d2aee2d22d46fd41df560a63 + md5: 7f402b4a1007ee355bc50ce4d24d4a57 depends: - - python >=3.7 + - python >=3.9 license: Unlicense - size: 15605 - timestamp: 1698715139726 + size: 17544 + timestamp: 1737517924333 - kind: conda name: gcc - version: 13.2.0 - build: hd6cf55c_3 - build_number: 3 + version: 13.3.0 + build: h9576a4e_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.2.0-hd6cf55c_3.conda - sha256: 7438ff57cf37cca306db8b70d25b6eb144bc70339dd375afac8beb3a3b6495f5 - md5: 78ece817e46368937ea2827b8b625eca + url: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda + sha256: d0161362430183cbdbc3db9cf95f9a1af1793027f3ab8755b3d3586deb28bf84 + md5: 606924335b5bcdf90e9aed9a2f5d22ed depends: - - gcc_impl_linux-64 13.2.0.* + - gcc_impl_linux-64 13.3.0.* license: BSD-3-Clause license_family: BSD - size: 27439 - timestamp: 1710259879706 + size: 53864 + timestamp: 1724801360210 - kind: conda name: gcc_impl_linux-64 - version: 13.2.0 - build: h338b0a0_5 - build_number: 5 + version: 13.3.0 + build: hfea6d02_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.2.0-h338b0a0_5.conda - sha256: baab8f8b9af54959735e629cf6d5ec9378166aa4c68ba8dc98dc0a781d548409 - md5: a6be13181cb66a78544b1d5f7bac97d0 - depends: - - binutils_impl_linux-64 >=2.39 - - libgcc-devel_linux-64 13.2.0 ha9c7c90_105 - - libgcc-ng >=13.2.0 - - libgomp >=13.2.0 - - libsanitizer 13.2.0 h7e041cc_5 - - libstdcxx-ng >=13.2.0 + url: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda + sha256: 998ade1d487e93fc8a7a16b90e2af69ebb227355bf4646488661f7ae5887873c + md5: 0d043dbc126b64f79d915a0e96d3a1d5 + depends: + - binutils_impl_linux-64 >=2.40 + - libgcc >=13.3.0 + - libgcc-devel_linux-64 13.3.0 h84ea5a7_101 + - libgomp >=13.3.0 + - libsanitizer 13.3.0 heb74ff8_1 + - libstdcxx >=13.3.0 - sysroot_linux-64 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 53318565 - timestamp: 1706819323755 + size: 67464415 + timestamp: 1724801227937 +- kind: conda + name: gcc_linux-64 + version: 13.3.0 + build: hc28eda2_7 + build_number: 7 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_7.conda + sha256: 1e5ac50580a68fdc7d2f5722abcf1a87898c24b1ab6eb5ecd322634742d93645 + md5: ac23afbf5805389eb771e2ad3b476f75 + depends: + - binutils_linux-64 + - gcc_impl_linux-64 13.3.0.* + - sysroot_linux-64 + license: BSD-3-Clause + license_family: BSD + size: 32005 + timestamp: 1731939593317 - kind: conda name: gmock - version: 1.12.1 - build: h91493d7_0 + version: 1.14.0 + build: h57928b3_2 + build_number: 2 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/gmock-1.12.1-h91493d7_0.conda - sha256: d73f5769f81bee19b2328ac1a8a70d7a4029f354b952daf5982691e17e0500d1 - md5: fb3cd0c6db137c027c069928d407a80d + url: https://conda.anaconda.org/conda-forge/win-64/gmock-1.14.0-h57928b3_2.conda + sha256: 8fd092e41478fc81b96c5001093abf78967853a1b29fde7aab31074152ce81be + md5: 4b757bae22f0d4ea6fc9d203ab079baa depends: - - gtest 1.12.1 h91493d7_0 - - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vs2015_runtime >=14.29.30139 + - gtest 1.14.0 hc790b64_2 license: BSD-3-Clause license_family: BSD - size: 5479845 - timestamp: 1674025431241 + size: 7460 + timestamp: 1720632002212 - kind: conda name: gmock - version: 1.12.1 - build: hf52228f_0 + version: 1.14.0 + build: ha770c72_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.12.1-hf52228f_0.conda - sha256: 3b0e8020bf8dfe48fa41b796131ce085fab5a33d0bc9e3337d15be986d062be1 - md5: 7be98dcbb1648d0bebf57848ed13d50c + url: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.14.0-ha770c72_2.conda + sha256: 72c3f3d77a7dfdc3fdf220d5c1d8c14235690894c83d076ec940881d9858f92f + md5: e94757978620b8969ae68a8503f1390e depends: - - gtest 1.12.1 hf52228f_0 - - libgcc-ng >=12 - - libstdcxx-ng >=12 + - gtest 1.14.0 h434a139_2 license: BSD-3-Clause license_family: BSD - size: 143428 - timestamp: 1674024011073 + size: 6987 + timestamp: 1720631604275 - kind: conda name: gtest - version: 1.12.1 - build: h91493d7_0 - subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/gtest-1.12.1-h91493d7_0.conda - sha256: cf724e19be93231a192126bc7f0adc3ab4fa87e357f9bb02a339cbf057efbc5e - md5: 11e1eadb67bd706007093c98bbbabb67 + version: 1.14.0 + build: h434a139_2 + build_number: 2 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.14.0-h434a139_2.conda + sha256: ab0e85e60f03c97802437c93577d03f5352dc0cde3f38abefda41dae99a576b0 + md5: 89971b339bb4dfbf3759f1f2528d81b1 depends: - - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vs2015_runtime >=14.29.30139 + - __glibc >=2.17,<3.0.a0 + - libgcc-ng >=12 + - libstdcxx-ng >=12 constrains: - - gmock 1.12.1 + - gmock 1.14.0 license: BSD-3-Clause license_family: BSD - size: 3491342 - timestamp: 1674025366743 + size: 403573 + timestamp: 1720631583903 - kind: conda name: gtest - version: 1.12.1 - build: hf52228f_0 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.12.1-hf52228f_0.conda - sha256: 0cbcf769905a7bd782f2cc277154df6207fcdb678be9eb2232ec81bd8ff65eeb - md5: d4c0791266a18618786961ef67817cbc + version: 1.14.0 + build: hc790b64_2 + build_number: 2 + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/gtest-1.14.0-hc790b64_2.conda + sha256: 12cec84fe8c3b72763d8fd7e7cc9aa0be7dabfdce8d1ce248e736a15f3fe01be + md5: 23fe596fed2f1c087d0e80a98560f025 depends: - - libgcc-ng >=12 - - libstdcxx-ng >=12 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 constrains: - - gmock 1.12.1 + - gmock 1.14.0 license: BSD-3-Clause license_family: BSD - size: 284354 - timestamp: 1674023994746 + size: 491884 + timestamp: 1720631969753 - kind: conda name: gxx - version: 13.2.0 - build: hd6cf55c_3 - build_number: 3 + version: 13.3.0 + build: h9576a4e_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.2.0-hd6cf55c_3.conda - sha256: 433ea239bca69f64c4262d4d660f7511a925b7a2819d096554c9788e35d46371 - md5: 8988c1eaea17d0cec6af9da7b6241e3b + url: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_1.conda + sha256: 5446f5d1d609d996579f706d2020e83ef48e086d943bfeef7ab807ea246888a0 + md5: 209182ca6b20aeff62f442e843961d81 depends: - - gcc 13.2.0.* - - gxx_impl_linux-64 13.2.0.* + - gcc 13.3.0.* + - gxx_impl_linux-64 13.3.0.* license: BSD-3-Clause license_family: BSD - size: 26970 - timestamp: 1710260263832 + size: 53338 + timestamp: 1724801498389 - kind: conda name: gxx_impl_linux-64 - version: 13.2.0 - build: h338b0a0_5 - build_number: 5 + version: 13.3.0 + build: hdbfa832_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.2.0-h338b0a0_5.conda - sha256: 9049d84fef7526e1dde8311acd2a592bf1d6f16453e68087c17d1bda01eb7867 - md5: 88d0ccab114eb0e837725bd48cdddae5 + url: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hdbfa832_1.conda + sha256: 746dff24bb1efc89ab0ec108838d0711683054e3bbbcb94d042943410a98eca1 + md5: 806367e23a0a6ad21e51875b34c57d7e depends: - - gcc_impl_linux-64 13.2.0 h338b0a0_5 - - libstdcxx-devel_linux-64 13.2.0 ha9c7c90_105 + - gcc_impl_linux-64 13.3.0 hfea6d02_1 + - libstdcxx-devel_linux-64 13.3.0 h84ea5a7_101 - sysroot_linux-64 + - tzdata license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 13582212 - timestamp: 1706819574801 + size: 13337720 + timestamp: 1724801455825 +- kind: conda + name: gxx_linux-64 + version: 13.3.0 + build: h6834431_7 + build_number: 7 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_7.conda + sha256: a9b1ffea76f2cc5aedeead4793fcded7a687cce9d5e3f4fe93629f1b1d5043a6 + md5: 7c82ca9bda609b6f72f670e4219d3787 + depends: + - binutils_linux-64 + - gcc_linux-64 13.3.0 hc28eda2_7 + - gxx_impl_linux-64 13.3.0.* + - sysroot_linux-64 + license: BSD-3-Clause + license_family: BSD + size: 30356 + timestamp: 1731939612705 - kind: conda name: identify - version: 2.5.35 + version: 2.6.6 build: pyhd8ed1ab_0 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/identify-2.5.35-pyhd8ed1ab_0.conda - sha256: 971683b13d1b820157bef9993c63dd8b0611d2d60fc4b522da163aee2e70e518 - md5: 9472bfd206a2b7bb8143835e37667054 + url: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.6-pyhd8ed1ab_0.conda + sha256: bb7483a113966d3d10b6e91edb79e7006f050fd40a842935848c15d12eff56d3 + md5: d751c3b4a973ed15b57be90d68c716d1 depends: - - python >=3.6 + - python >=3.9 - ukkonen license: MIT license_family: MIT - size: 78364 - timestamp: 1708283690891 + size: 78562 + timestamp: 1737421654786 - kind: conda name: kernel-headers_linux-64 - version: 2.6.32 - build: he073ed8_17 - build_number: 17 + version: 3.10.0 + build: he073ed8_18 + build_number: 18 subdir: noarch noarch: generic - url: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-2.6.32-he073ed8_17.conda - sha256: fb39d64b48f3d9d1acc3df208911a41f25b6a00bd54935d5973b4739a9edd5b6 - md5: d731b543793afc0433c4fd593e693fce + url: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda + sha256: a922841ad80bd7b222502e65c07ecb67e4176c4fa5b03678a005f39fcc98be4b + md5: ad8527bf134a90e1c9ed35fa0b64318c constrains: - - sysroot_linux-64 ==2.12 + - sysroot_linux-64 ==2.17 license: LGPL-2.0-or-later AND LGPL-2.0-or-later WITH exceptions AND GPL-2.0-or-later AND MPL-2.0 license_family: GPL - size: 710627 - timestamp: 1708000830116 + size: 943486 + timestamp: 1729794504440 - kind: conda name: keyutils version: 1.6.1 @@ -537,109 +672,114 @@ packages: timestamp: 1646151697040 - kind: conda name: krb5 - version: 1.21.2 - build: h659d440_0 + version: 1.21.3 + build: h659f571_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.2-h659d440_0.conda - sha256: 259bfaae731989b252b7d2228c1330ef91b641c9d68ff87dae02cbae682cb3e4 - md5: cd95826dbd331ed1be26bdf401432844 + url: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda + sha256: 99df692f7a8a5c27cd14b5fb1374ee55e756631b9c3d659ed3ee60830249b238 + md5: 3f43953b7d3fb3aaa1d0d0723d91e368 depends: - keyutils >=1.6.1,<2.0a0 - libedit >=3.1.20191231,<3.2.0a0 - libedit >=3.1.20191231,<4.0a0 - libgcc-ng >=12 - libstdcxx-ng >=12 - - openssl >=3.1.2,<4.0a0 + - openssl >=3.3.1,<4.0a0 license: MIT license_family: MIT - size: 1371181 - timestamp: 1692097755782 + size: 1370023 + timestamp: 1719463201255 - kind: conda name: krb5 - version: 1.21.2 - build: heb0366b_0 + version: 1.21.3 + build: hdf4eb48_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.2-heb0366b_0.conda - sha256: 6002adff9e3dcfc9732b861730cb9e33d45fd76b2035b2cdb4e6daacb8262c0b - md5: 6e8b0f22b4eef3b3cb3849bb4c3d47f9 + url: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda + sha256: 18e8b3430d7d232dad132f574268f56b3eb1a19431d6d5de8c53c29e6c18fa81 + md5: 31aec030344e962fbd7dbbbbd68e60a9 depends: - - openssl >=3.1.2,<4.0a0 + - openssl >=3.3.1,<4.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 710894 - timestamp: 1692098129546 + size: 712034 + timestamp: 1719463874284 - kind: conda name: ld_impl_linux-64 - version: '2.40' - build: h41732ed_0 + version: '2.43' + build: h712a8e2_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.40-h41732ed_0.conda - sha256: f6cc89d887555912d6c61b295d398cff9ec982a3417d38025c45d5dd9b9e79cd - md5: 7aca3059a1729aa76c597603f10b0dd3 + url: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_2.conda + sha256: 7c91cea91b13f4314d125d1bedb9d03a29ebbd5080ccdea70260363424646dbe + md5: 048b02e3962f066da18efe3a21b77672 + depends: + - __glibc >=2.17,<3.0.a0 constrains: - - binutils_impl_linux-64 2.40 + - binutils_impl_linux-64 2.43 license: GPL-3.0-only license_family: GPL - size: 704696 - timestamp: 1674833944779 + size: 669211 + timestamp: 1729655358674 - kind: conda name: libcurl - version: 8.6.0 - build: hca28451_0 + version: 8.11.1 + build: h332b0f4_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.6.0-hca28451_0.conda - sha256: 357ce806adf1818dc8dccdcd64627758e1858eb0d8a9c91aae4a0eeee2a44608 - md5: 704739398d858872cb91610f49f0ef29 - depends: - - krb5 >=1.21.2,<1.22.0a0 - - libgcc-ng >=12 - - libnghttp2 >=1.58.0,<2.0a0 - - libssh2 >=1.11.0,<2.0a0 - - libzlib >=1.2.13,<1.3.0a0 - - openssl >=3.2.1,<4.0a0 - - zstd >=1.5.5,<1.6.0a0 + url: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.11.1-h332b0f4_0.conda + sha256: 3cd4075b2a7b5562e46c8ec626f6f9ca57aeecaa94ff7df57eca26daa94c9906 + md5: 2b3e0081006dc21e8bf53a91c83a055c + depends: + - __glibc >=2.17,<3.0.a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - libnghttp2 >=1.64.0,<2.0a0 + - libssh2 >=1.11.1,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.4.0,<4.0a0 + - zstd >=1.5.6,<1.6.0a0 license: curl license_family: MIT - size: 391187 - timestamp: 1710590979402 + size: 423011 + timestamp: 1733999897624 - kind: conda name: libcurl - version: 8.6.0 - build: hd5e4a3a_0 + version: 8.11.1 + build: h88aaa65_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.6.0-hd5e4a3a_0.conda - sha256: 49904a3c1ede193cf9044e8379067bf56850fb03f64abbf57ca45f7e6d2d3888 - md5: 9cc8dea844a89245dfe8618521ef8d6a + url: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.11.1-h88aaa65_0.conda + sha256: 1a67f01da0e35296c6d1fdf6baddc45ad3cc2114132ff4638052eb7cf258aab2 + md5: 071d3f18dba5a6a13c6bb70cdb42678f depends: - - krb5 >=1.21.2,<1.22.0a0 - - libssh2 >=1.11.0,<2.0a0 - - libzlib >=1.2.13,<1.3.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libssh2 >=1.11.1,<2.0a0 + - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: curl license_family: MIT - size: 325841 - timestamp: 1710591351093 + size: 349553 + timestamp: 1734000095720 - kind: conda name: libedit - version: 3.1.20191231 - build: he28a2e2_2 - build_number: 2 + version: 3.1.20240808 + build: pl5321h7949ede_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20191231-he28a2e2_2.tar.bz2 - sha256: a57d37c236d8f7c886e01656f4949d9dcca131d2a0728609c6f7fa338b65f1cf - md5: 4d331e44109e3f0e19b4cb8f9b82f3e1 - depends: - - libgcc-ng >=7.5.0 - - ncurses >=6.2,<7.0.0a0 + url: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20240808-pl5321h7949ede_0.conda + sha256: 4d0d69ddf9cc7d724a1ccf3a9852e44c8aea9825692582bac2c4e8d21ec95ccd + md5: 8247f80f3dc464d9322e85007e307fe8 + depends: + - ncurses + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - ncurses >=6.5,<7.0a0 license: BSD-2-Clause license_family: BSD - size: 123878 - timestamp: 1597616541093 + size: 134657 + timestamp: 1736191912705 - kind: conda name: libev version: '4.33' @@ -657,34 +797,39 @@ packages: timestamp: 1702146165126 - kind: conda name: libexpat - version: 2.6.2 - build: h59595ed_0 + version: 2.6.4 + build: h5888daf_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.6.2-h59595ed_0.conda - sha256: 331bb7c7c05025343ebd79f86ae612b9e1e74d2687b8f3179faec234f986ce19 - md5: e7ba12deb7020dd080c6c70e7b6f6a3d + url: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.6.4-h5888daf_0.conda + sha256: 56541b98447b58e52d824bd59d6382d609e11de1f8adf20b23143e353d2b8d26 + md5: db833e03127376d461e1e13e76f09b6c depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 constrains: - - expat 2.6.2.* + - expat 2.6.4.* license: MIT license_family: MIT - size: 73730 - timestamp: 1710362120304 + size: 73304 + timestamp: 1730967041968 - kind: conda name: libexpat - version: 2.6.2 - build: h63175ca_0 + version: 2.6.4 + build: he0c23c2_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.6.2-h63175ca_0.conda - sha256: 79f612f75108f3e16bbdc127d4885bb74729cf66a8702fca0373dad89d40c4b7 - md5: bc592d03f62779511d392c175dcece64 + url: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.6.4-he0c23c2_0.conda + sha256: 0c0447bf20d1013d5603499de93a16b6faa92d7ead870d96305c0f065b6a5a12 + md5: eb383771c680aa792feb529eaf9df82f + depends: + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 constrains: - - expat 2.6.2.* + - expat 2.6.4.* license: MIT license_family: MIT - size: 139224 - timestamp: 1710362609641 + size: 139068 + timestamp: 1730967442102 - kind: conda name: libffi version: 3.4.2 @@ -716,74 +861,160 @@ packages: license_family: MIT size: 42063 timestamp: 1636489106777 +- kind: conda + name: libgcc + version: 14.2.0 + build: h77fa898_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h77fa898_1.conda + sha256: 53eb8a79365e58849e7b1a068d31f4f9e718dc938d6f2c03e960345739a03569 + md5: 3cb76c3f10d3bc7f1105b2fc9db984df + depends: + - _libgcc_mutex 0.1 conda_forge + - _openmp_mutex >=4.5 + constrains: + - libgomp 14.2.0 h77fa898_1 + - libgcc-ng ==14.2.0=*_1 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 848745 + timestamp: 1729027721139 - kind: conda name: libgcc-devel_linux-64 - version: 13.2.0 - build: ha9c7c90_105 - build_number: 105 + version: 13.3.0 + build: h84ea5a7_101 + build_number: 101 subdir: noarch noarch: generic - url: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.2.0-ha9c7c90_105.conda - sha256: 858029ad4d66869c533bb5a22e95e7c044ca66c61d6f403f10d9ae074a0e360e - md5: 3bc29a967fee57e193ce51f51c598bca + url: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-h84ea5a7_101.conda + sha256: 027cfb011328a108bc44f512a2dec6d954db85709e0b79b748c3392f85de0c64 + md5: 0ce69d40c142915ac9734bc6134e514a + depends: + - __unix license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 2578210 - timestamp: 1706819085946 + size: 2598313 + timestamp: 1724801050802 - kind: conda name: libgcc-ng - version: 13.2.0 - build: h807b86a_5 - build_number: 5 + version: 14.2.0 + build: h69a702a_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-13.2.0-h807b86a_5.conda - sha256: d32f78bfaac282cfe5205f46d558704ad737b8dbf71f9227788a5ca80facaba4 - md5: d4ff227c46917d3b4565302a2bbb276b + url: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_1.conda + sha256: 3a76969c80e9af8b6e7a55090088bc41da4cffcde9e2c71b17f44d37b7cb87f7 + md5: e39480b9ca41323497b05492a63bc35b depends: - - _libgcc_mutex 0.1 conda_forge - - _openmp_mutex >=4.5 - constrains: - - libgomp 13.2.0 h807b86a_5 + - libgcc 14.2.0 h77fa898_1 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 770506 - timestamp: 1706819192021 + size: 54142 + timestamp: 1729027726517 - kind: conda name: libgomp - version: 13.2.0 - build: h807b86a_5 - build_number: 5 + version: 14.2.0 + build: h77fa898_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libgomp-13.2.0-h807b86a_5.conda - sha256: 0d3d4b1b0134283ea02d58e8eb5accf3655464cf7159abf098cc694002f8d34e - md5: d211c42b9ce49aee3734fdc828731689 + url: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h77fa898_1.conda + sha256: 1911c29975ec99b6b906904040c855772ccb265a1c79d5d75c8ceec4ed89cd63 + md5: cc3573974587f12dda90d96e3e55a702 depends: - _libgcc_mutex 0.1 conda_forge license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 419751 - timestamp: 1706819107383 + size: 460992 + timestamp: 1729027639220 - kind: conda - name: libnghttp2 - version: 1.58.0 - build: h47da74e_1 + name: liblzma + version: 5.6.3 + build: h2466b09_1 + build_number: 1 + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.3-h2466b09_1.conda + sha256: 24d04bd55adfa44c421c99ce169df38cb1ad2bba5f43151bc847fc802496a1fa + md5: 015b9c0bd1eef60729ab577a38aaf0b5 + depends: + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + constrains: + - xz ==5.6.3=*_1 + license: 0BSD + size: 104332 + timestamp: 1733407872569 +- kind: conda + name: liblzma + version: 5.6.3 + build: hb9d3cd8_1 build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.58.0-h47da74e_1.conda - sha256: 1910c5306c6aa5bcbd623c3c930c440e9c77a5a019008e1487810e3c1d3716cb - md5: 700ac6ea6d53d5510591c4344d5c989a + url: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.3-hb9d3cd8_1.conda + sha256: e6e425252f3839e2756e4af1ea2074dffd3396c161bf460629f9dfd6a65f15c6 + md5: 2ecf2f1c7e4e21fcfe6423a51a992d84 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + constrains: + - xz ==5.6.3=*_1 + license: 0BSD + size: 111132 + timestamp: 1733407410083 +- kind: conda + name: liblzma-devel + version: 5.6.3 + build: h2466b09_1 + build_number: 1 + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/liblzma-devel-5.6.3-h2466b09_1.conda + sha256: 771a99f8cd58358fe38192fc0df679cf6276facb8222016469693de7b0c8ff47 + md5: 5f9978adba7aa8aa7d237cdb8b542537 depends: - - c-ares >=1.23.0,<2.0a0 + - liblzma 5.6.3 h2466b09_1 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + license: 0BSD + size: 125790 + timestamp: 1733407900270 +- kind: conda + name: liblzma-devel + version: 5.6.3 + build: hb9d3cd8_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.3-hb9d3cd8_1.conda + sha256: ca17f037a0a7137874597866a171166677e4812a9a8a853007f0f582e3ff6d1d + md5: cc4687e1814ed459f3bd6d8e05251ab2 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - liblzma 5.6.3 hb9d3cd8_1 + license: 0BSD + size: 376794 + timestamp: 1733407421190 +- kind: conda + name: libnghttp2 + version: 1.64.0 + build: h161d5f1_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda + sha256: b0f2b3695b13a989f75d8fd7f4778e1c7aabe3b36db83f0fe80b2cd812c0e975 + md5: 19e57602824042dfd0446292ef90488b + depends: + - __glibc >=2.17,<3.0.a0 + - c-ares >=1.32.3,<2.0a0 - libev >=4.33,<4.34.0a0 - libev >=4.33,<5.0a0 - - libgcc-ng >=12 - - libstdcxx-ng >=12 - - libzlib >=1.2.13,<1.3.0a0 - - openssl >=3.2.0,<4.0a0 + - libgcc >=13 + - libstdcxx >=13 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.3.2,<4.0a0 license: MIT license_family: MIT - size: 631936 - timestamp: 1702130036271 + size: 647599 + timestamp: 1729571887612 - kind: conda name: libnsl version: 2.0.1 @@ -800,48 +1031,48 @@ packages: timestamp: 1697359010159 - kind: conda name: libsanitizer - version: 13.2.0 - build: h7e041cc_5 - build_number: 5 + version: 13.3.0 + build: heb74ff8_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.2.0-h7e041cc_5.conda - sha256: 97ecdab7e4e96400d712c2d6ba2b7c30a97278e9f4470ea0ff36bf4f1447b3b9 - md5: 3f686300a92604d1bdff9a29dd4a6639 + url: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-heb74ff8_1.conda + sha256: c86d130f0a3099e46ff51aa7ffaab73cb44fc420d27a96076aab3b9a326fc137 + md5: c4cb22f270f501f5c59a122dc2adf20a depends: - - libgcc-ng >=13.2.0 + - libgcc >=13.3.0 + - libstdcxx >=13.3.0 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 4114208 - timestamp: 1706819228913 + size: 4133922 + timestamp: 1724801171589 - kind: conda name: libsodium - version: 1.0.18 - build: h36c2ea0_1 - build_number: 1 + version: 1.0.20 + build: h4ab18f5_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.18-h36c2ea0_1.tar.bz2 - sha256: 53da0c8b79659df7b53eebdb80783503ce72fb4b10ed6e9e05cc0e9e4207a130 - md5: c3788462a6fbddafdb413a9f9053e58d + url: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda + sha256: 0105bd108f19ea8e6a78d2d994a6d4a8db16d19a41212070d2d1d48a63c34161 + md5: a587892d3c13b6621a6091be690dbca2 depends: - - libgcc-ng >=7.5.0 + - libgcc-ng >=12 license: ISC - size: 374999 - timestamp: 1605135674116 + size: 205978 + timestamp: 1716828628198 - kind: conda name: libsodium - version: 1.0.18 - build: h8d14728_1 - build_number: 1 + version: 1.0.20 + build: hc70643c_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.18-h8d14728_1.tar.bz2 - sha256: ecc463f0ab6eaf6bc5bd6ff9c17f65595de6c7a38db812222ab8ffde0d3f4bc2 - md5: 5c1fb45b5e2912c19098750ae8a32604 + url: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda + sha256: 7bcb3edccea30f711b6be9601e083ecf4f435b9407d70fc48fbcf9e5d69a0fc6 + md5: 198bb594f202b205c7d18b936fa4524f depends: - - vc >=14.1,<15.0a0 - - vs2015_runtime >=14.16.27012 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 license: ISC - size: 713431 - timestamp: 1605135918736 + size: 202344 + timestamp: 1716828757533 - kind: conda name: libsqlite version: 3.40.0 @@ -853,7 +1084,7 @@ packages: md5: 32565f92ca100184c67509d1d91c858a depends: - libgcc-ng >=12 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 license: Unlicense size: 804156 timestamp: 1682197905901 @@ -875,65 +1106,85 @@ packages: timestamp: 1682198555134 - kind: conda name: libssh2 - version: 1.11.0 - build: h0841786_0 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.0-h0841786_0.conda - sha256: 50e47fd9c4f7bf841a11647ae7486f65220cfc988ec422a4475fe8d5a823824d - md5: 1f5a58e686b13bcfde88b93f547d23fe - depends: - - libgcc-ng >=12 - - libzlib >=1.2.13,<1.3.0a0 - - openssl >=3.1.1,<4.0a0 - license: BSD-3-Clause - license_family: BSD - size: 271133 - timestamp: 1685837707056 -- kind: conda - name: libssh2 - version: 1.11.0 - build: h7dfc565_0 + version: 1.11.1 + build: he619c9f_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.0-h7dfc565_0.conda - sha256: 813fd04eed2a2d5d9c36e53c554f9c1f08e9324e2922bd60c9c52dbbed2dbcec - md5: dc262d03aae04fe26825062879141a41 + url: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda + sha256: 4b3256bd2b4e4b3183005d3bd8826d651eccd1a4740b70625afa2b7e7123d191 + md5: af0cbf037dd614c34399b3b3e568c557 depends: - - libzlib >=1.2.13,<1.3.0a0 - - openssl >=3.1.1,<4.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.4.0,<4.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: BSD-3-Clause license_family: BSD - size: 266806 - timestamp: 1685838242099 + size: 291889 + timestamp: 1732349796504 +- kind: conda + name: libssh2 + version: 1.11.1 + build: hf672d98_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + sha256: 0407ac9fda2bb67e11e357066eff144c845801d00b5f664efbc48813af1e7bb9 + md5: be2de152d8073ef1c01b7728475f2fe7 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.4.0,<4.0a0 + license: BSD-3-Clause + license_family: BSD + size: 304278 + timestamp: 1732349402869 +- kind: conda + name: libstdcxx + version: 14.2.0 + build: hc0a3c3a_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-hc0a3c3a_1.conda + sha256: 4661af0eb9bdcbb5fb33e5d0023b001ad4be828fccdcc56500059d56f9869462 + md5: 234a5554c53625688d51062645337328 + depends: + - libgcc 14.2.0 h77fa898_1 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 3893695 + timestamp: 1729027746910 - kind: conda name: libstdcxx-devel_linux-64 - version: 13.2.0 - build: ha9c7c90_105 - build_number: 105 + version: 13.3.0 + build: h84ea5a7_101 + build_number: 101 subdir: noarch noarch: generic - url: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.2.0-ha9c7c90_105.conda - sha256: 67e999ee56481844ca4ce2e61132c5c16f3f00a05daa1d0ea4b2c684eea5de5a - md5: 66383205c2e1bdf013df52fa9e3e6763 + url: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-h84ea5a7_101.conda + sha256: 0a9226c1b994f996229ffb54fa40d608cd4e4b48e8dc73a66134bea8ce949412 + md5: 29b5a4ed4613fa81a07c21045e3f5bf6 + depends: + - __unix license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 13020920 - timestamp: 1706819128553 + size: 14074676 + timestamp: 1724801075448 - kind: conda name: libstdcxx-ng - version: 13.2.0 - build: h7e041cc_5 - build_number: 5 + version: 14.2.0 + build: h4852527_1 + build_number: 1 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-13.2.0-h7e041cc_5.conda - sha256: a56c5b11f1e73a86e120e6141a42d9e935a99a2098491ac9e15347a1476ce777 - md5: f6f6600d18a4047b54f803cf708b868a + url: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_1.conda + sha256: 25bb30b827d4f6d6f0522cc0579e431695503822f144043b93c50237017fffd8 + md5: 8371ac6457591af2cf6159439c1fd051 + depends: + - libstdcxx 14.2.0 hc0a3c3a_1 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 3834139 - timestamp: 1706819252496 + size: 54105 + timestamp: 1729027780628 - kind: conda name: libuuid version: 2.38.1 @@ -950,176 +1201,180 @@ packages: timestamp: 1680112270483 - kind: conda name: libuv - version: 1.48.0 - build: hcfcfb64_0 + version: 1.50.0 + build: h2466b09_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libuv-1.48.0-hcfcfb64_0.conda - sha256: 6151c51857c2407139ce22fdc956022353e675b2bc96991a9201d51cceaa90b4 - md5: 485e49e1d500d996844df14cabf64d73 + url: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda + sha256: aeb71b2a2973ffed6d639ace6c1afef1a337836425e637d2320f3166dbaa5c80 + md5: a63a1ec1e8d017d1b9894aed98c419da depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 289753 - timestamp: 1709913743184 + size: 291944 + timestamp: 1737017103042 - kind: conda name: libuv - version: 1.48.0 - build: hd590300_0 + version: 1.50.0 + build: hb9d3cd8_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.48.0-hd590300_0.conda - sha256: b7c0e8a0c93c2621be7645b37123d4e8d27e8a974da26a3fba47a9c37711aa7f - md5: 7e8b914b1062dd4386e3de4d82a3ead6 + url: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda + sha256: b4a8890023902aef9f1f33e3e35603ad9c2f16c21fdb58e968fa6c1bd3e94c0b + md5: 771ee65e13bc599b0b62af5359d80169 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 license: MIT license_family: MIT - size: 899979 - timestamp: 1709913354710 + size: 891272 + timestamp: 1737016632446 - kind: conda name: libzlib - version: 1.2.13 - build: hcfcfb64_5 - build_number: 5 + version: 1.3.1 + build: h2466b09_2 + build_number: 2 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.2.13-hcfcfb64_5.conda - sha256: c161822ee8130b71e08b6d282b9919c1de2c5274b29921a867bca0f7d30cad26 - md5: 5fdb9c6a113b6b6cb5e517fd972d5f41 + url: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda + sha256: ba945c6493449bed0e6e29883c4943817f7c79cbff52b83360f7b341277c6402 + md5: 41fbfac52c601159df6c01f875de31b9 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 constrains: - - zlib 1.2.13 *_5 + - zlib 1.3.1 *_2 license: Zlib license_family: Other - size: 55800 - timestamp: 1686575452215 + size: 55476 + timestamp: 1727963768015 - kind: conda name: libzlib - version: 1.2.13 - build: hd590300_5 - build_number: 5 + version: 1.3.1 + build: hb9d3cd8_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.2.13-hd590300_5.conda - sha256: 370c7c5893b737596fd6ca0d9190c9715d89d888b8c88537ae1ef168c25e82e4 - md5: f36c115f1ee199da648e0597ec2047ad + url: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda + sha256: d4bfe88d7cb447768e31650f06257995601f89076080e76df55e3112d4e47dc4 + md5: edb0dca6bc32e4f4789199455a1dbeb8 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 constrains: - - zlib 1.2.13 *_5 + - zlib 1.3.1 *_2 license: Zlib license_family: Other - size: 61588 - timestamp: 1686575217516 + size: 60963 + timestamp: 1727963148474 - kind: conda name: make - version: '4.3' - build: hd18ef5c_1 - build_number: 1 + version: 4.4.1 + build: hb9d3cd8_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/make-4.3-hd18ef5c_1.tar.bz2 - sha256: 4a5fe7c80bb0de0015328e2d3fc8db1736f528cb1fd53cd0d5527e24269a4f7c - md5: 4049ebfd3190b580dffe76daed26155a + url: https://conda.anaconda.org/conda-forge/linux-64/make-4.4.1-hb9d3cd8_2.conda + sha256: d652c7bd4d3b6f82b0f6d063b0d8df6f54cc47531092d7ff008e780f3261bdda + md5: 33405d2a66b1411db9f7242c8b97c9e7 depends: - - libgcc-ng >=7.5.0 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 license: GPL-3.0-or-later license_family: GPL - size: 518896 - timestamp: 1602706451788 + size: 513088 + timestamp: 1727801714848 - kind: conda name: ncurses - version: 6.4.20240210 - build: h59595ed_0 + version: '6.5' + build: h2d0b736_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.4.20240210-h59595ed_0.conda - sha256: aa0f005b6727aac6507317ed490f0904430584fa8ca722657e7f0fb94741de81 - md5: 97da8860a0da5413c7c98a3b3838a645 + url: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_2.conda + sha256: 17fe6afd8a00446010220d52256bd222b1e4fcb93bd587e7784b03219f3dc358 + md5: 04b34b9a40cdc48cfdab261ab176ff74 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 license: X11 AND BSD-3-Clause - size: 895669 - timestamp: 1710866638986 + size: 894452 + timestamp: 1736683239706 - kind: conda name: nodeenv - version: 1.8.0 - build: pyhd8ed1ab_0 + version: 1.9.1 + build: pyhd8ed1ab_1 + build_number: 1 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.8.0-pyhd8ed1ab_0.conda - sha256: 1320306234552717149f36f825ddc7e27ea295f24829e9db4cc6ceaff0b032bd - md5: 2a75b296096adabbabadd5e9782e5fcc + url: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda + sha256: 3636eec0e60466a00069b47ce94b6d88b01419b6577d8e393da44bb5bc8d3468 + md5: 7ba3f09fceae6a120d664217e58fe686 depends: - - python 2.7|>=3.7 + - python >=3.9 - setuptools license: BSD-3-Clause license_family: BSD - size: 34358 - timestamp: 1683893151613 + size: 34574 + timestamp: 1734112236147 - kind: conda name: openssl - version: 3.2.1 - build: hcfcfb64_1 + version: 3.4.0 + build: h7b32b05_1 build_number: 1 - subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/openssl-3.2.1-hcfcfb64_1.conda - sha256: 61ce4e11c3c26ed4e4d9b7e7e2483121a1741ad0f9c8db0a91a28b6e05182ce6 - md5: 958e0418e93e50c575bff70fbcaa12d8 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.0-h7b32b05_1.conda + sha256: f62f6bca4a33ca5109b6d571b052a394d836956d21b25b7ffd03376abf7a481f + md5: 4ce6875f75469b2757a65e10a5d05e31 depends: + - __glibc >=2.17,<3.0.a0 - ca-certificates - - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vc14_runtime >=14.29.30139 - constrains: - - pyopenssl >=22.1 + - libgcc >=13 license: Apache-2.0 license_family: Apache - size: 8230112 - timestamp: 1710796158475 + size: 2937158 + timestamp: 1736086387286 - kind: conda name: openssl - version: 3.2.1 - build: hd590300_1 + version: 3.4.0 + build: ha4e3fda_1 build_number: 1 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.2.1-hd590300_1.conda - sha256: 2c689444ed19a603be457284cf2115ee728a3fafb7527326e96054dee7cdc1a7 - md5: 9d731343cff6ee2e5a25c4a091bf8e2a + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.0-ha4e3fda_1.conda + sha256: 519a06eaab7c878fbebb8cab98ea4a4465eafb1e9ed8c6ce67226068a80a92f0 + md5: fb45308ba8bfe1abf1f4a27bad24a743 depends: - ca-certificates - - libgcc-ng >=12 - constrains: - - pyopenssl >=22.1 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 license: Apache-2.0 license_family: Apache - size: 2865379 - timestamp: 1710793235846 + size: 8462960 + timestamp: 1736088436984 - kind: conda name: platformdirs - version: 4.2.0 - build: pyhd8ed1ab_0 + version: 4.3.6 + build: pyhd8ed1ab_1 + build_number: 1 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.2.0-pyhd8ed1ab_0.conda - sha256: 2ebfb971236ab825dd79dd6086ea742a9901008ffb9c6222c1f2b5172a8039d3 - md5: a0bc3eec34b0fab84be6b2da94e98e20 + url: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda + sha256: bb50f6499e8bc1d1a26f17716c97984671121608dc0c3ecd34858112bce59a27 + md5: 577852c7e53901ddccc7e6a9959ddebe depends: - - python >=3.8 + - python >=3.9 license: MIT license_family: MIT - size: 20210 - timestamp: 1706713564353 + size: 20448 + timestamp: 1733232756001 - kind: conda name: pre-commit - version: 3.6.2 + version: 4.1.0 build: pyha770c72_0 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/pre-commit-3.6.2-pyha770c72_0.conda - sha256: 8eb9f5965c37d2bbee9302e16cc7c5517ee06491986356112be13431a043681e - md5: 61534ee57ffdf26d7b1b514d33daccc4 + url: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.1.0-pyha770c72_0.conda + sha256: b260b4b47956b654232f698be1b757935268830a808040aff2006d08953e9e32 + md5: 5353f5eb201a9415b12385e35ed1148d depends: - cfgv >=2.0.0 - identify >=1.0.0 @@ -1129,23 +1384,25 @@ packages: - virtualenv >=20.10.0 license: MIT license_family: MIT - size: 179884 - timestamp: 1708284490635 + size: 195101 + timestamp: 1737408051494 - kind: conda name: pycparser - version: '2.21' - build: pyhd8ed1ab_0 + version: '2.22' + build: pyh29332c3_1 + build_number: 1 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.21-pyhd8ed1ab_0.tar.bz2 - sha256: 74c63fd03f1f1ea2b54e8bc529fd1a600aaafb24027b738d0db87909ee3a33dc - md5: 076becd9e05608f8dc72757d5f3a91ff + url: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda + sha256: 79db7928d13fab2d892592223d7570f5061c192f27b9febd1a418427b719acc6 + md5: 12c566707c80111f9799308d9e265aef depends: - - python ==2.7.*|>=3.4 + - python >=3.9 + - python license: BSD-3-Clause license_family: BSD - size: 102747 - timestamp: 1636257201998 + size: 110100 + timestamp: 1733195786147 - kind: conda name: python version: 3.11.3 @@ -1159,7 +1416,7 @@ packages: - libexpat >=2.5.0,<3.0a0 - libffi >=3.4,<4.0a0 - libsqlite >=3.40.0,<4.0a0 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 - openssl >=3.1.0,<4.0a0 - tk >=8.6.12,<8.7.0a0 - tzdata @@ -1189,7 +1446,7 @@ packages: - libnsl >=2.0.0,<2.1.0a0 - libsqlite >=3.40.0,<4.0a0 - libuuid >=2.38.1,<3.0a0 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 - ncurses >=6.3,<7.0a0 - openssl >=3.1.0,<4.0a0 - readline >=8.2,<9.0a0 @@ -1204,60 +1461,61 @@ packages: - kind: conda name: python_abi version: '3.11' - build: 4_cp311 - build_number: 4 + build: 5_cp311 + build_number: 5 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.11-4_cp311.conda - sha256: 0be3ac1bf852d64f553220c7e6457e9c047dfb7412da9d22fbaa67e60858b3cf - md5: d786502c97404c94d7d58d258a445a65 + url: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.11-5_cp311.conda + sha256: 2660b8059b3ee854bc5d3c6b1fce946e5bd2fe8fbca7827de2c5885ead6209de + md5: 139a8d40c8a2f430df31048949e450de constrains: - python 3.11.* *_cpython license: BSD-3-Clause license_family: BSD - size: 6385 - timestamp: 1695147338551 + size: 6211 + timestamp: 1723823324668 - kind: conda name: python_abi version: '3.11' - build: 4_cp311 - build_number: 4 + build: 5_cp311 + build_number: 5 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.11-4_cp311.conda - sha256: 67c2aade3e2160642eec0742384e766b20c766055e3d99335681e3e05d88ed7b - md5: 70513332c71b56eace4ee6441e66c012 + url: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.11-5_cp311.conda + sha256: 9b210e5807dd9c9ed71ff192a95f1872da597ddd10e7cefec93a922fe22e598a + md5: 895b873644c11ccc0ab7dba2d8513ae6 constrains: - python 3.11.* *_cpython license: BSD-3-Clause license_family: BSD - size: 6755 - timestamp: 1695147711935 + size: 6707 + timestamp: 1723823225752 - kind: conda name: pyyaml - version: 6.0.1 - build: py311h459d7ec_1 - build_number: 1 + version: 6.0.2 + build: py311h2dc5d0c_2 + build_number: 2 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.1-py311h459d7ec_1.conda - sha256: 28729ef1ffa7f6f9dfd54345a47c7faac5d34296d66a2b9891fb147f4efe1348 - md5: 52719a74ad130de8fb5d047dc91f247a + url: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py311h2dc5d0c_2.conda + sha256: d107ad62ed5c62764fba9400f2c423d89adf917d687c7f2e56c3bfed605fb5b3 + md5: 014417753f948da1f70d132b2de573be depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 - python >=3.11,<3.12.0a0 - python_abi 3.11.* *_cp311 - yaml >=0.2.5,<0.3.0a0 license: MIT license_family: MIT - size: 200626 - timestamp: 1695373818537 + size: 213136 + timestamp: 1737454846598 - kind: conda name: pyyaml - version: 6.0.1 - build: py311ha68e1ae_1 - build_number: 1 + version: 6.0.2 + build: py311h5082efb_2 + build_number: 2 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.1-py311ha68e1ae_1.conda - sha256: 4fb0770fc70381a8ab3ced33413ad9dc5e82d4c535b593edd580113ce8760298 - md5: 2b4128962cd665153e946f2a88667a3b + url: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py311h5082efb_2.conda + sha256: 6095e1d58c666f6a06c55338df09485eac34c76e43d92121d5786794e195aa4d + md5: e474ba674d780f0fa3b979ae9e81ba91 depends: - python >=3.11,<3.12.0a0 - python_abi 3.11.* *_cp311 @@ -1267,8 +1525,8 @@ packages: - yaml >=0.2.5,<0.3.0a0 license: MIT license_family: MIT - size: 175469 - timestamp: 1695374086205 + size: 187430 + timestamp: 1737454904007 - kind: conda name: readline version: '8.2' @@ -1287,33 +1545,34 @@ packages: timestamp: 1679532220005 - kind: conda name: rhash - version: 1.4.4 - build: hd590300_0 + version: 1.4.5 + build: hb9d3cd8_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.4-hd590300_0.conda - sha256: 12711d2d4a808a503c2e49b25d26ecb351435521e814c154e682dd2be71c2611 - md5: ec972a9a2925ac8d7a19eb9606561fff + url: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda + sha256: 04677caac29ec64a5d41d0cca8dbec5f60fa166d5458ff5a4393e4dc08a4799e + md5: 9af0e7981755f09c81421946c4bcea04 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 license: MIT license_family: MIT - size: 185144 - timestamp: 1693455923632 + size: 186921 + timestamp: 1728886721623 - kind: conda name: setuptools - version: 69.2.0 - build: pyhd8ed1ab_0 + version: 75.8.0 + build: pyhff2d567_0 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/setuptools-69.2.0-pyhd8ed1ab_0.conda - sha256: 78a75c75a5dacda6de5f4056c9c990141bdaf4f64245673a590594d00bc63713 - md5: da214ecd521a720a9d521c68047682dc + url: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda + sha256: e0778e4f276e9a81b51c56f51ec22a27b4d8fc955abc0be77ad09ca9bea06bb9 + md5: 8f28e299c11afdd79e0ec1e279dcdc52 depends: - - python >=3.8 + - python >=3.9 license: MIT license_family: MIT - size: 471183 - timestamp: 1710344615844 + size: 775598 + timestamp: 1736512753595 - kind: conda name: sqlite version: 3.40.0 @@ -1326,7 +1585,7 @@ packages: depends: - libgcc-ng >=12 - libsqlite 3.40.0 h753d276_1 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 - ncurses >=6.3,<7.0a0 - readline >=8.2,<9.0a0 license: Unlicense @@ -1351,20 +1610,21 @@ packages: timestamp: 1682198584526 - kind: conda name: sysroot_linux-64 - version: '2.12' - build: he073ed8_17 - build_number: 17 + version: '2.17' + build: h0157908_18 + build_number: 18 subdir: noarch noarch: generic - url: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.12-he073ed8_17.conda - sha256: b4e4d685e41cb36cfb16f0cb15d2c61f8f94f56fab38987a44eff95d8a673fb5 - md5: 595db67e32b276298ff3d94d07d47fbf + url: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda + sha256: 69ab5804bdd2e8e493d5709eebff382a72fab3e9af6adf93a237ccf8f7dbd624 + md5: 460eba7851277ec1fd80a1a24080787a depends: - - kernel-headers_linux-64 2.6.32 he073ed8_17 + - kernel-headers_linux-64 3.10.0 he073ed8_18 + - tzdata license: LGPL-2.0-or-later AND LGPL-2.0-or-later WITH exceptions AND GPL-2.0-or-later AND MPL-2.0 license_family: GPL - size: 15127123 - timestamp: 1708000843849 + size: 15166921 + timestamp: 1735290488259 - kind: conda name: tk version: 8.6.13 @@ -1393,46 +1653,46 @@ packages: md5: d453b98d9c83e71da0741bb0ff4d76bc depends: - libgcc-ng >=12 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 license: TCL license_family: BSD size: 3318875 timestamp: 1699202167581 - kind: conda name: tzdata - version: 2024a - build: h0c530f3_0 + version: 2025a + build: h78e105d_0 subdir: noarch noarch: generic - url: https://conda.anaconda.org/conda-forge/noarch/tzdata-2024a-h0c530f3_0.conda - sha256: 7b2b69c54ec62a243eb6fba2391b5e443421608c3ae5dbff938ad33ca8db5122 - md5: 161081fc7cec0bfda0d86d7cb595f8d8 + url: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda + sha256: c4b1ae8a2931fe9b274c44af29c5475a85b37693999f8c792dad0f8c6734b1de + md5: dbcace4706afdfb7eb891f7b37d07c04 license: LicenseRef-Public-Domain - size: 119815 - timestamp: 1706886945727 + size: 122921 + timestamp: 1737119101255 - kind: conda name: ucrt version: 10.0.22621.0 - build: h57928b3_0 + build: h57928b3_1 + build_number: 1 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_0.tar.bz2 - sha256: f29cdaf8712008f6b419b8b1a403923b00ab2504bfe0fb2ba8eb60e72d4f14c6 - md5: 72608f6cd3e5898229c3ea16deb1ac43 + url: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda + sha256: db8dead3dd30fb1a032737554ce91e2819b43496a0db09927edf01c32b577450 + md5: 6797b005cd0f439c4c5c9ac565783700 constrains: - vs2015_runtime >=14.29.30037 - license: LicenseRef-Proprietary - license_family: PROPRIETARY - size: 1283972 - timestamp: 1666630199266 + license: LicenseRef-MicrosoftWindowsSDK10 + size: 559710 + timestamp: 1728377334097 - kind: conda name: ukkonen version: 1.0.1 - build: py311h005e61a_4 - build_number: 4 + build: py311h3257749_5 + build_number: 5 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/ukkonen-1.0.1-py311h005e61a_4.conda - sha256: ef774047df25201a6425fe1ec194505a3cac9ba02e96953360442f59364d12b3 - md5: d9988836cc20c90e05901ab05962f496 + url: https://conda.anaconda.org/conda-forge/win-64/ukkonen-1.0.1-py311h3257749_5.conda + sha256: 7624abb32c075e234dad59acb5b580006adfef348cd1aefcbe0be31546aa5b73 + md5: 938a78ac20d6ed625b8d76015c6be88d depends: - cffi - python >=3.11,<3.12.0a0 @@ -1442,150 +1702,213 @@ packages: - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 17225 - timestamp: 1695549858085 + size: 17253 + timestamp: 1725784407361 - kind: conda name: ukkonen version: 1.0.1 - build: py311h9547e67_4 - build_number: 4 + build: py311hd18a35c_5 + build_number: 5 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/ukkonen-1.0.1-py311h9547e67_4.conda - sha256: c2d33e998f637b594632eba3727529171a06eb09896e36aa42f1ebcb03779472 - md5: 586da7df03b68640de14dc3e8bcbf76f + url: https://conda.anaconda.org/conda-forge/linux-64/ukkonen-1.0.1-py311hd18a35c_5.conda + sha256: 4542cc3093f480c7fa3e104bfd9e5b7daeff32622121be6847f9e839341b0790 + md5: 4e8447ca8558a203ec0577b4730073f3 depends: + - __glibc >=2.17,<3.0.a0 - cffi - - libgcc-ng >=12 - - libstdcxx-ng >=12 + - libgcc >=13 + - libstdcxx >=13 - python >=3.11,<3.12.0a0 - python_abi 3.11.* *_cp311 license: MIT license_family: MIT - size: 13961 - timestamp: 1695549513130 + size: 13858 + timestamp: 1725784165345 - kind: conda name: vc version: '14.3' - build: hcf57466_18 - build_number: 18 + build: h5fd82a7_24 + build_number: 24 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-hcf57466_18.conda - sha256: 447a8d8292a7b2107dcc18afb67f046824711a652725fc0f522c368e7a7b8318 - md5: 20e1e652a4c740fa719002a8449994a2 + url: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h5fd82a7_24.conda + sha256: 7ce178cf139ccea5079f9c353b3d8415d1d49b0a2f774662c355d3f89163d7b4 + md5: 00cf3a61562bd53bd5ea99e6888793d0 depends: - - vc14_runtime >=14.38.33130 + - vc14_runtime >=14.40.33810 track_features: - vc14 license: BSD-3-Clause license_family: BSD - size: 16977 - timestamp: 1702511255313 + size: 17693 + timestamp: 1737627189024 - kind: conda name: vc14_runtime - version: 14.38.33130 - build: h82b7239_18 - build_number: 18 + version: 14.42.34433 + build: h6356254_24 + build_number: 24 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.38.33130-h82b7239_18.conda - sha256: bf94c9af4b2e9cba88207001197e695934eadc96a5c5e4cd7597e950aae3d8ff - md5: 8be79fdd2725ddf7bbf8a27a4c1f79ba + url: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34433-h6356254_24.conda + sha256: abda97b8728cf6e3c37df8f1178adde7219bed38b96e392cb3be66336386d32e + md5: 2441e010ee255e6a38bf16705a756e94 depends: - ucrt >=10.0.20348.0 constrains: - - vs2015_runtime 14.38.33130.* *_18 - license: LicenseRef-ProprietaryMicrosoft + - vs2015_runtime 14.42.34433.* *_24 + license: LicenseRef-MicrosoftVisualCpp2015-2022Runtime license_family: Proprietary - size: 749868 - timestamp: 1702511239004 + size: 753531 + timestamp: 1737627061911 - kind: conda name: virtualenv - version: 20.25.1 + version: 20.29.1 build: pyhd8ed1ab_0 subdir: noarch noarch: python - url: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.25.1-pyhd8ed1ab_0.conda - sha256: 1ced4445cf72cd9dc344ad04bdaf703a08cc428c8c46e4bda928ad79786ee153 - md5: 8797a4e26be36880a603aba29c785352 - depends: - - distlib <1,>=0.3.7 - - filelock <4,>=3.12.2 - - platformdirs <5,>=3.9.1 - - python >=3.8 + url: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.29.1-pyhd8ed1ab_0.conda + sha256: f09a9f2034669762ae875858253d472588f03689843e5f0b8ddc5cc48a1d0e50 + md5: de06336c9833cffd2a4bd6f27c4cf8ea + depends: + - distlib >=0.3.7,<1 + - filelock >=3.12.2,<4 + - platformdirs >=3.9.1,<5 + - python >=3.9 license: MIT license_family: MIT - size: 3148218 - timestamp: 1708602229963 + size: 3501167 + timestamp: 1737145224475 - kind: conda name: vs2015_runtime - version: 14.38.33130 - build: hcb4865c_18 - build_number: 18 + version: 14.42.34433 + build: hfef2bbc_24 + build_number: 24 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.38.33130-hcb4865c_18.conda - sha256: a2fec221f361d6263c117f4ea6d772b21c90a2f8edc6f3eb0eadec6bfe8843db - md5: 10d42885e3ed84e575b454db30f1aa93 + url: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34433-hfef2bbc_24.conda + sha256: 09102e0bd283af65772c052d85028410b0c31989b3cd96c260485d28e270836e + md5: 117fcc5b86c48f3b322b0722258c7259 depends: - - vc14_runtime >=14.38.33130 + - vc14_runtime >=14.42.34433 license: BSD-3-Clause license_family: BSD - size: 16988 - timestamp: 1702511261442 + size: 17669 + timestamp: 1737627066773 - kind: conda - name: vs2022_win-64 - version: 19.38.33130 - build: h0bfb142_18 - build_number: 18 + name: vs2019_win-64 + version: 19.29.30139 + build: h7dcff83_24 + build_number: 24 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/vs2022_win-64-19.38.33130-h0bfb142_18.conda - sha256: 9b7107dcc5c4100c610d03f773dfc57b8fe4d92363dc8fa6b0c1e2a7887c1d1d - md5: b04b8f57f9c40f74329d277a8dcf68e7 + url: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_24.conda + sha256: 4125acd871ba3498f25799b1999bf0fa4d80b0b353eb56ac170809f9eda19dd1 + md5: 41aaa71a5d4f668f5795c0647eeea776 depends: - vswhere + constrains: + - vs_win-64 2019.11 track_features: - vc14 license: BSD-3-Clause license_family: BSD - size: 19529 - timestamp: 1702511248981 + size: 20377 + timestamp: 1737627273487 - kind: conda name: vswhere - version: 3.1.4 + version: 3.1.7 build: h57928b3_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.4-h57928b3_0.conda - sha256: 553c41fc1a883415a39444313f8d99236685529776fdd04e8d97288b73496002 - md5: b1d1d6a1f874d8c93a57b5efece52f03 + url: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + sha256: 8caeda9c0898cb8ee2cf4f45640dbbbdf772ddc01345cfb0f7b352c58b4d8025 + md5: ba83df93b48acfc528f5464c9a882baa license: MIT license_family: MIT - size: 218421 - timestamp: 1682376911339 + size: 219013 + timestamp: 1719460515960 - kind: conda name: xz - version: 5.2.6 - build: h166bdaf_0 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - sha256: 03a6d28ded42af8a347345f82f3eebdd6807a08526d47899a42d62d319609162 - md5: 2161070d867d1b1204ea749c8eec4ef0 + version: 5.6.3 + build: h208afaa_1 + build_number: 1 + subdir: win-64 + url: https://conda.anaconda.org/conda-forge/win-64/xz-5.6.3-h208afaa_1.conda + sha256: 636687c7ff74e37e464b57ddddc921016713f13fb48126ba8db426eb2d978392 + md5: fce59c05fc73134677e81b7b8184b397 depends: - - libgcc-ng >=12 - license: LGPL-2.1 and GPL-2.0 - size: 418368 - timestamp: 1660346797927 + - liblzma 5.6.3 h2466b09_1 + - liblzma-devel 5.6.3 h2466b09_1 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + - xz-tools 5.6.3 h2466b09_1 + license: 0BSD AND LGPL-2.1-or-later AND GPL-2.0-or-later + size: 23925 + timestamp: 1733407963901 - kind: conda name: xz - version: 5.2.6 - build: h8d14728_0 + version: 5.6.3 + build: hbcc6ac9_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.3-hbcc6ac9_1.conda + sha256: 9cef529dcff25222427c9d90b9fc376888a59e138794b4336bbcd3331a5eea22 + md5: 62aae173382a8aae284726353c6a6a24 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - liblzma 5.6.3 hb9d3cd8_1 + - liblzma-devel 5.6.3 hb9d3cd8_1 + - xz-gpl-tools 5.6.3 hbcc6ac9_1 + - xz-tools 5.6.3 hb9d3cd8_1 + license: 0BSD AND LGPL-2.1-or-later AND GPL-2.0-or-later + size: 23477 + timestamp: 1733407455801 +- kind: conda + name: xz-gpl-tools + version: 5.6.3 + build: hbcc6ac9_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.3-hbcc6ac9_1.conda + sha256: 4e104b7c75c2f26a96032a1c6cda51430da1dea318c74f9e3568902b2f5030e1 + md5: f529917bab7862aaad6867bf2ea47a99 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - liblzma 5.6.3 hb9d3cd8_1 + license: 0BSD AND LGPL-2.1-or-later AND GPL-2.0-or-later + size: 33354 + timestamp: 1733407444641 +- kind: conda + name: xz-tools + version: 5.6.3 + build: h2466b09_1 + build_number: 1 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/xz-5.2.6-h8d14728_0.tar.bz2 - sha256: 54d9778f75a02723784dc63aff4126ff6e6749ba21d11a6d03c1f4775f269fe0 - md5: 515d77642eaa3639413c6b1bc3f94219 + url: https://conda.anaconda.org/conda-forge/win-64/xz-tools-5.6.3-h2466b09_1.conda + sha256: 0cb621f748ec0b9b5edafb9a15e342f6f6f42a3f462ab0276c821a35e8bf39c0 + md5: 4100be41430c9b2310468d3489597071 + depends: + - liblzma 5.6.3 h2466b09_1 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + license: 0BSD AND LGPL-2.1-or-later + size: 63898 + timestamp: 1733407936888 +- kind: conda + name: xz-tools + version: 5.6.3 + build: hb9d3cd8_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.3-hb9d3cd8_1.conda + sha256: 6e80f838096345c35e8755b827814c083dd0274594006d6f76bff71bc969c3b8 + md5: de3f31a6eed01bc2b8c7dcad07ad9034 depends: - - vc >=14.1,<15 - - vs2015_runtime >=14.16.27033 - license: LGPL-2.1 and GPL-2.0 - size: 217804 - timestamp: 1660346976440 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - liblzma 5.6.3 hb9d3cd8_1 + license: 0BSD AND LGPL-2.1-or-later + size: 90354 + timestamp: 1733407433418 - kind: conda name: yaml version: 0.2.5 @@ -1620,68 +1943,71 @@ packages: - kind: conda name: zeromq version: 4.3.5 - build: h59595ed_1 - build_number: 1 + build: h3b0a872_7 + build_number: 7 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h59595ed_1.conda - sha256: 3bec658f5c23abf5e200d98418add7a20ff7b45c928ad4560525bef899496256 - md5: 7fc9d3288d2420bb3637647621018000 - depends: - - libgcc-ng >=12 - - libsodium >=1.0.18,<1.0.19.0a0 - - libstdcxx-ng >=12 + url: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda + sha256: a4dc72c96848f764bb5a5176aa93dd1e9b9e52804137b99daeebba277b31ea10 + md5: 3947a35e916fcc6b9825449affbf4214 + depends: + - __glibc >=2.17,<3.0.a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - libsodium >=1.0.20,<1.0.21.0a0 + - libstdcxx >=13 license: MPL-2.0 license_family: MOZILLA - size: 343438 - timestamp: 1709135220800 + size: 335400 + timestamp: 1731585026517 - kind: conda name: zeromq version: 4.3.5 - build: h63175ca_1 - build_number: 1 + build: ha9f60a1_7 + build_number: 7 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-h63175ca_1.conda - sha256: c9089e80a724a4d21f9df4bcc99ccbddb93c8cce3f6b0c9cb74b4f98b641dfc2 - md5: e8867cc4d023f41f54bd64a33436b0a1 + url: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-ha9f60a1_7.conda + sha256: 15cc8e2162d0a33ffeb3f7b7c7883fd830c54a4b1be6a4b8c7ee1f4fef0088fb + md5: e03f2c245a5ee6055752465519363b1c depends: - - libsodium >=1.0.18,<1.0.19.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libsodium >=1.0.20,<1.0.21.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MPL-2.0 license_family: MOZILLA - size: 4199151 - timestamp: 1709135717106 + size: 2527503 + timestamp: 1731585151036 - kind: conda name: zstd - version: 1.5.5 - build: h12be248_0 + version: 1.5.6 + build: h0ea2cb4_0 subdir: win-64 - url: https://conda.anaconda.org/conda-forge/win-64/zstd-1.5.5-h12be248_0.conda - sha256: d540dd56c5ec772b60e4ce7d45f67f01c6614942225885911964ea1e70bb99e3 - md5: 792bb5da68bf0a6cac6a6072ecb8dbeb + url: https://conda.anaconda.org/conda-forge/win-64/zstd-1.5.6-h0ea2cb4_0.conda + sha256: 768e30dc513568491818fb068ee867c57c514b553915536da09e5d10b4ebf3c3 + md5: 9a17230f95733c04dc40a2b1e5491d74 depends: - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: BSD-3-Clause license_family: BSD - size: 343428 - timestamp: 1693151615801 + size: 349143 + timestamp: 1714723445995 - kind: conda name: zstd - version: 1.5.5 - build: hfc55251_0 + version: 1.5.6 + build: ha6fb4c9_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.5-hfc55251_0.conda - sha256: 607cbeb1a533be98ba96cf5cdf0ddbb101c78019f1fda063261871dad6248609 - md5: 04b88013080254850d6c01ed54810589 + url: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda + sha256: c558b9cc01d9c1444031bd1ce4b9cff86f9085765f17627a6cd85fc623c8a02b + md5: 4d056880988120e29d75bfff282e0f45 depends: - libgcc-ng >=12 - libstdcxx-ng >=12 - - libzlib >=1.2.13,<1.3.0a0 + - libzlib >=1.2.13,<2.0.0a0 license: BSD-3-Clause license_family: BSD - size: 545199 - timestamp: 1693151163452 + size: 554846 + timestamp: 1714722996770 diff --git a/pixi.toml b/pixi.toml index 3fc203670..955d13ef8 100644 --- a/pixi.toml +++ b/pixi.toml @@ -17,16 +17,13 @@ build = "mkdir -p build && cd build && cmake ../ -DCMAKE_BUILD_TYPE=Release && c [dependencies] cmake = ">=3.16.3" -gmock = "1.12.*" +gmock = "1.14.*" sqlite = "3.40.*" zeromq = "4.3.*" -gtest = "1.12.*" +gtest = "1.14.*" +cxx-compiler = "*" pre-commit = "*" -[target.win-64.dependencies] -vs2022_win-64 = "19.*" - [target.linux-64.dependencies] -gxx = "13.*" make = "*" diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 000000000..3fc95ccc4 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,2 @@ +[tool.codespell] +ignore-words = ".codespell_ignore_words" diff --git a/sonar-project.properties b/sonar-project.properties new file mode 100644 index 000000000..31dc9a6d1 --- /dev/null +++ b/sonar-project.properties @@ -0,0 +1,14 @@ +sonar.projectKey=BehaviorTree_BehaviorTree.CPP +sonar.organization=behaviortree + +# This is the name and version displayed in the SonarCloud UI. +#sonar.projectName=BehaviorTree.CPP +#sonar.projectVersion=1.0 + + +# Path is relative to the sonar-project.properties file. Replace "\" by "/" on Windows. +#sonar.sources=. + +# Encoding of the source code. Default is default system encoding +#sonar.sourceEncoding=UTF-8 +sonar.exclusions=3rdparty/**/* diff --git a/src/actions/test_node.cpp b/src/actions/test_node.cpp index 19b70b1aa..f2471c085 100644 --- a/src/actions/test_node.cpp +++ b/src/actions/test_node.cpp @@ -1,12 +1,20 @@ #include "behaviortree_cpp/actions/test_node.h" -BT::TestNode::TestNode(const std::string& name, const NodeConfig& config, - TestNodeConfig test_config) - : StatefulActionNode(name, config), _test_config(std::move(test_config)) +namespace BT +{ + +TestNode::TestNode(const std::string& name, const NodeConfig& config, + TestNodeConfig test_config) + : TestNode(name, config, std::make_shared(std::move(test_config))) +{} + +TestNode::TestNode(const std::string& name, const NodeConfig& config, + std::shared_ptr test_config) + : StatefulActionNode(name, config), _config(std::move(test_config)) { setRegistrationID("TestNode"); - if(_test_config.return_status == NodeStatus::IDLE) + if(_config->return_status == NodeStatus::IDLE) { throw RuntimeError("TestNode can not return IDLE"); } @@ -22,21 +30,21 @@ BT::TestNode::TestNode(const std::string& name, const NodeConfig& config, executor = result.value(); } }; - prepareScript(_test_config.success_script, _success_executor); - prepareScript(_test_config.failure_script, _failure_executor); - prepareScript(_test_config.post_script, _post_executor); + prepareScript(_config->success_script, _success_executor); + prepareScript(_config->failure_script, _failure_executor); + prepareScript(_config->post_script, _post_executor); } -BT::NodeStatus BT::TestNode::onStart() +NodeStatus TestNode::onStart() { - if(_test_config.async_delay <= std::chrono::milliseconds(0)) + if(_config->async_delay <= std::chrono::milliseconds(0)) { return onCompleted(); } // convert this in an asynchronous operation. Use another thread to count // a certain amount of time. _completed = false; - _timer.add(std::chrono::milliseconds(_test_config.async_delay), [this](bool aborted) { + _timer.add(std::chrono::milliseconds(_config->async_delay), [this](bool aborted) { if(!aborted) { _completed.store(true); @@ -50,7 +58,7 @@ BT::NodeStatus BT::TestNode::onStart() return NodeStatus::RUNNING; } -BT::NodeStatus BT::TestNode::onRunning() +NodeStatus TestNode::onRunning() { if(_completed) { @@ -59,16 +67,18 @@ BT::NodeStatus BT::TestNode::onRunning() return NodeStatus::RUNNING; } -void BT::TestNode::onHalted() +void TestNode::onHalted() { _timer.cancelAll(); } -BT::NodeStatus BT::TestNode::onCompleted() +NodeStatus TestNode::onCompleted() { Ast::Environment env = { config().blackboard, config().enums }; - auto status = _test_config.complete_func(); + auto status = + (_config->complete_func) ? _config->complete_func() : _config->return_status; + if(status == NodeStatus::SUCCESS && _success_executor) { _success_executor(env); @@ -83,3 +93,5 @@ BT::NodeStatus BT::TestNode::onCompleted() } return status; } + +} // namespace BT diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 088a11015..6cc4bc668 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -1,4 +1,5 @@ #include "behaviortree_cpp/basic_types.h" +#include "behaviortree_cpp/tree_node.h" #include "behaviortree_cpp/json_export.h" #include @@ -420,10 +421,6 @@ const std::string& PortInfo::defaultValueString() const bool IsAllowedPortName(StringView str) { - if(str == "_autoremap") - { - return true; - } if(str.empty()) { return false; @@ -433,11 +430,26 @@ bool IsAllowedPortName(StringView str) { return false; } - if(str == "name" || str == "ID") + return !IsReservedAttribute(str); +} + +bool IsReservedAttribute(StringView str) +{ + for(const auto& name : PreCondNames) { - return false; + if(name == str) + { + return true; + } + } + for(const auto& name : PostCondNames) + { + if(name == str) + { + return true; + } } - return true; + return str == "name" || str == "ID" || str == "_autoremap"; } Any convertFromJSON(StringView json_text, std::type_index type) diff --git a/src/blackboard.cpp b/src/blackboard.cpp index 0f1f304db..3b1ba9844 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -143,6 +143,10 @@ void Blackboard::createEntry(const std::string& key, const TypeInfo& info) { if(StartWith(key, '@')) { + if(key.find('@', 1) != std::string::npos) + { + throw LogicError("Character '@' used multiple times in the key"); + } rootBlackboard()->createEntryImpl(key.substr(1, key.size() - 1), info); } else @@ -172,7 +176,7 @@ void Blackboard::cloneInto(Blackboard& dst) const auto it = dst_storage.find(src_key); if(it != dst_storage.end()) { - // overwite + // overwrite auto& dst_entry = it->second; dst_entry->string_converter = src_entry->string_converter; dst_entry->value = src_entry->value; diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index acf39492c..63f6652ef 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -13,14 +13,9 @@ #include #include "behaviortree_cpp/bt_factory.h" #include "behaviortree_cpp/utils/shared_library.h" -#include "behaviortree_cpp/contrib/json.hpp" #include "behaviortree_cpp/xml_parsing.h" #include "wildcards/wildcards.hpp" -#ifdef USING_ROS -#include -#endif - namespace BT { @@ -107,17 +102,6 @@ BehaviorTreeFactory::BehaviorTreeFactory() : _p(new PImpl) _p->scripting_enums = std::make_shared>(); } -BehaviorTreeFactory::BehaviorTreeFactory(BehaviorTreeFactory&& other) noexcept -{ - this->_p = std::move(other._p); -} - -BehaviorTreeFactory& BehaviorTreeFactory::operator=(BehaviorTreeFactory&& other) noexcept -{ - this->_p = std::move(other._p); - return *this; -} - BehaviorTreeFactory::~BehaviorTreeFactory() {} @@ -207,66 +191,12 @@ void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path) } } -#ifdef USING_ROS - -#ifdef _WIN32 -const char os_pathsep(';'); // NOLINT -#else -const char os_pathsep(':'); // NOLINT -#endif - -// This function is a copy from the one in class_loader_imp.hpp in ROS pluginlib -// package, licensed under BSD. -// https://github.com/ros/pluginlib -std::vector getCatkinLibraryPaths() -{ - std::vector lib_paths; - const char* env = std::getenv("CMAKE_PREFIX_PATH"); - if(env) - { - const std::string env_catkin_prefix_paths(env); - std::vector catkin_prefix_paths = - splitString(env_catkin_prefix_paths, os_pathsep); - for(BT::StringView catkin_prefix_path : catkin_prefix_paths) - { - std::filesystem::path path(static_cast(catkin_prefix_path)); - std::filesystem::path lib("lib"); - lib_paths.push_back((path / lib).string()); - } - } - return lib_paths; -} - -void BehaviorTreeFactory::registerFromROSPlugins() -{ - std::vector plugins; - ros::package::getPlugins("behaviortree_cpp", "bt_lib_plugin", plugins, true); - std::vector catkin_lib_paths = getCatkinLibraryPaths(); - - for(const auto& plugin : plugins) - { - auto filename = std::filesystem::path(plugin + BT::SharedLibrary::suffix()); - for(const auto& lib_path : catkin_lib_paths) - { - const auto full_path = std::filesystem::path(lib_path) / filename; - if(std::filesystem::exists(full_path)) - { - std::cout << "Registering ROS plugins from " << full_path.string() << std::endl; - registerFromPlugin(full_path.string()); - break; - } - } - } -} -#else - void BehaviorTreeFactory::registerFromROSPlugins() { throw RuntimeError("Using attribute [ros_pkg] in , but this library was " "compiled without ROS support. Recompile the BehaviorTree.CPP " "using catkin"); } -#endif void BehaviorTreeFactory::registerBehaviorTreeFromFile( const std::filesystem::path& filename) @@ -333,12 +263,22 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode( } else if(const auto test_config = std::get_if(&rule)) { - // second case, the varian is a TestNodeConfig - auto test_node = new TestNode(name, config, *test_config); - node.reset(test_node); + node = std::make_unique(name, config, + std::make_shared(*test_config)); + substituted = true; + break; + } + else if(const auto test_config = + std::get_if>(&rule)) + { + node = std::make_unique(name, config, *test_config); substituted = true; break; } + else + { + throw LogicError("Substitution rule is not a string or a TestNodeConfig"); + } } } @@ -531,22 +471,9 @@ BehaviorTreeFactory::substitutionRules() const return _p->substitution_rules; } -Tree& Tree::operator=(Tree&& other) -{ - subtrees = std::move(other.subtrees); - manifests = std::move(other.manifests); - wake_up_ = other.wake_up_; - return *this; -} - Tree::Tree() {} -Tree::Tree(Tree&& other) -{ - (*this) = std::move(other); -} - void Tree::initialize() { wake_up_ = std::make_shared(); @@ -621,7 +548,7 @@ Blackboard::Ptr Tree::rootBlackboard() return {}; } -void Tree::applyVisitor(const std::function& visitor) +void Tree::applyVisitor(const std::function& visitor) const { BT::applyRecursiveVisitor(static_cast(rootNode()), visitor); } diff --git a/src/controls/fallback_node.cpp b/src/controls/fallback_node.cpp index 1654e3f2a..4b8fb3afb 100644 --- a/src/controls/fallback_node.cpp +++ b/src/controls/fallback_node.cpp @@ -28,7 +28,7 @@ NodeStatus FallbackNode::tick() { const size_t children_count = children_nodes_.size(); - if(status() == NodeStatus::IDLE) + if(!isStatusActive(status())) { skipped_count_ = 0; } @@ -55,7 +55,7 @@ NodeStatus FallbackNode::tick() case NodeStatus::FAILURE: { current_child_idx_++; // Return the execution flow if the child is async, - // to make this interruptable. + // to make this interruptible. if(asynch_ && requiresWakeUp() && prev_status == NodeStatus::IDLE && current_child_idx_ < children_count) { @@ -77,19 +77,22 @@ NodeStatus FallbackNode::tick() } // end while loop // The entire while loop completed. This means that all the children returned FAILURE. + const bool all_children_skipped = (skipped_count_ == children_count); if(current_child_idx_ == children_count) { resetChildren(); current_child_idx_ = 0; + skipped_count_ = 0; } // Skip if ALL the nodes have been skipped - return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::FAILURE; + return (all_children_skipped) ? NodeStatus::SKIPPED : NodeStatus::FAILURE; } void FallbackNode::halt() { current_child_idx_ = 0; + skipped_count_ = 0; ControlNode::halt(); } diff --git a/src/controls/sequence_node.cpp b/src/controls/sequence_node.cpp index 708c18d18..483e66c5b 100644 --- a/src/controls/sequence_node.cpp +++ b/src/controls/sequence_node.cpp @@ -27,6 +27,7 @@ SequenceNode::SequenceNode(const std::string& name, bool make_async) void SequenceNode::halt() { current_child_idx_ = 0; + skipped_count_ = 0; ControlNode::halt(); } @@ -34,7 +35,7 @@ NodeStatus SequenceNode::tick() { const size_t children_count = children_nodes_.size(); - if(status() == NodeStatus::IDLE) + if(!isStatusActive(status())) { skipped_count_ = 0; } @@ -62,7 +63,7 @@ NodeStatus SequenceNode::tick() case NodeStatus::SUCCESS: { current_child_idx_++; // Return the execution flow if the child is async, - // to make this interruptable. + // to make this interruptible. if(asynch_ && requiresWakeUp() && prev_status == NodeStatus::IDLE && current_child_idx_ < children_count) { @@ -86,13 +87,15 @@ NodeStatus SequenceNode::tick() } // end while loop // The entire while loop completed. This means that all the children returned SUCCESS. + const bool all_children_skipped = (skipped_count_ == children_count); if(current_child_idx_ == children_count) { resetChildren(); current_child_idx_ = 0; + skipped_count_ = 0; } // Skip if ALL the nodes have been skipped - return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS; + return (all_children_skipped) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS; } } // namespace BT diff --git a/src/controls/sequence_with_memory_node.cpp b/src/controls/sequence_with_memory_node.cpp index f47c798b6..3031de9b2 100644 --- a/src/controls/sequence_with_memory_node.cpp +++ b/src/controls/sequence_with_memory_node.cpp @@ -25,7 +25,7 @@ NodeStatus SequenceWithMemory::tick() { const size_t children_count = children_nodes_.size(); - if(status() == NodeStatus::IDLE) + if(!isStatusActive(status())) { skipped_count_ = 0; } @@ -55,7 +55,7 @@ NodeStatus SequenceWithMemory::tick() case NodeStatus::SUCCESS: { current_child_idx_++; // Return the execution flow if the child is async, - // to make this interruptable. + // to make this interruptible. if(requiresWakeUp() && prev_status == NodeStatus::IDLE && current_child_idx_ < children_count) { @@ -79,13 +79,15 @@ NodeStatus SequenceWithMemory::tick() } // end while loop // The entire while loop completed. This means that all the children returned SUCCESS. + const bool all_children_skipped = (skipped_count_ == children_count); if(current_child_idx_ == children_count) { resetChildren(); current_child_idx_ = 0; + skipped_count_ = 0; } // Skip if ALL the nodes have been skipped - return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS; + return (all_children_skipped) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS; } void SequenceWithMemory::halt() diff --git a/src/decorators/repeat_node.cpp b/src/decorators/repeat_node.cpp index d6b6f7c68..9ea023ee1 100644 --- a/src/decorators/repeat_node.cpp +++ b/src/decorators/repeat_node.cpp @@ -59,7 +59,7 @@ NodeStatus RepeatNode::tick() resetChild(); // Return the execution flow if the child is async, - // to make this interruptable. + // to make this interruptible. if(requiresWakeUp() && prev_status == NodeStatus::IDLE && do_loop) { emitWakeUpSignal(); diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index 81b2bb6ec..d8c689c78 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -67,12 +67,14 @@ NodeStatus RetryNode::tick() case NodeStatus::FAILURE: { try_count_++; + // Refresh max_attempts_ in case it changed in one of the child nodes + getInput(NUM_ATTEMPTS, max_attempts_); do_loop = try_count_ < max_attempts_ || max_attempts_ == -1; resetChild(); // Return the execution flow if the child is async, - // to make this interruptable. + // to make this interruptible. if(requiresWakeUp() && prev_status == NodeStatus::IDLE && do_loop) { emitWakeUpSignal(); diff --git a/src/json_export.cpp b/src/json_export.cpp index 1baac478a..2ad648f3e 100644 --- a/src/json_export.cpp +++ b/src/json_export.cpp @@ -30,6 +30,22 @@ bool JsonExporter::toJson(const Any& any, nlohmann::json& dst) const { dst = any.cast(); } + else if(type == typeid(std::vector)) + { + dst = any.cast>(); + } + else if(type == typeid(std::vector)) + { + dst = any.cast>(); + } + else if(type == typeid(std::vector)) + { + dst = any.cast>(); + } + else if(type == typeid(std::vector)) + { + dst = any.cast>(); + } else { auto it = to_json_converters_.find(type); @@ -49,20 +65,17 @@ JsonExporter::ExpectedEntry JsonExporter::fromJson(const nlohmann::json& source) { if(source.is_null()) { - return nonstd::make_unexpected("json object is null"); + return Entry{ BT::Any(), BT::TypeInfo::Create() }; } + if(source.is_string()) { return Entry{ BT::Any(source.get()), BT::TypeInfo::Create() }; } - if(source.is_number_unsigned()) - { - return Entry{ BT::Any(source.get()), BT::TypeInfo::Create() }; - } if(source.is_number_integer()) { - return Entry{ BT::Any(source.get()), BT::TypeInfo::Create() }; + return Entry{ BT::Any(source.get()), BT::TypeInfo::Create() }; } if(source.is_number_float()) { @@ -73,17 +86,48 @@ JsonExporter::ExpectedEntry JsonExporter::fromJson(const nlohmann::json& source) return Entry{ BT::Any(source.get()), BT::TypeInfo::Create() }; } - if(!source.contains("__type")) + // basic vectors + if(source.is_array() && source.size() > 0 && !source.contains("__type")) + { + auto first_element = source[0]; + if(first_element.is_string()) + { + return Entry{ BT::Any(source.get>()), + BT::TypeInfo::Create>() }; + } + if(first_element.is_number_integer()) + { + return Entry{ BT::Any(source.get>()), + BT::TypeInfo::Create>() }; + } + if(first_element.is_number_float()) + { + return Entry{ BT::Any(source.get>()), + BT::TypeInfo::Create>() }; + } + if(first_element.is_boolean()) + { + return Entry{ BT::Any(source.get>()), + BT::TypeInfo::Create>() }; + } + } + + if(!source.contains("__type") && !source.is_array()) { return nonstd::make_unexpected("Missing field '__type'"); } - auto type_it = type_names_.find(source["__type"]); + + auto& from_converters = + source.is_array() ? from_json_array_converters_ : from_json_converters_; + auto type_field = source.is_array() ? source[0]["__type"] : source["__type"]; + + auto type_it = type_names_.find(type_field); if(type_it == type_names_.end()) { return nonstd::make_unexpected("Type not found in registered list"); } - auto func_it = from_json_converters_.find(type_it->second.type()); - if(func_it == from_json_converters_.end()) + auto func_it = from_converters.find(type_it->second.type()); + if(func_it == from_converters.end()) { return nonstd::make_unexpected("Type not found in registered list"); } diff --git a/src/loggers/zmq.hpp b/src/loggers/zmq.hpp index e029b88d8..26c2c6f42 100644 --- a/src/loggers/zmq.hpp +++ b/src/loggers/zmq.hpp @@ -439,7 +439,7 @@ class message_t // NOTE this constructor will include the null terminator // when called with a string literal. // An overload taking const char* can not be added because - // it would be preferred over this function and break compatiblity. + // it would be preferred over this function and break compatibility. template ::value>::type> ZMQ_DEPRECATED("from 4.7.0, use constructors taking iterators, (pointer, size) " diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 7b7a4ac88..0d4dd66bd 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -464,39 +464,23 @@ void TreeNode::modifyPortsRemapping(const PortsRemapping& new_remapping) } template <> -std::string toStr(const PreCond& pre) +std::string toStr(const PreCond& cond) { - switch(pre) + if(cond < PreCond::COUNT_) { - case PreCond::SUCCESS_IF: - return "_successIf"; - case PreCond::FAILURE_IF: - return "_failureIf"; - case PreCond::SKIP_IF: - return "_skipIf"; - case PreCond::WHILE_TRUE: - return "_while"; - default: - return "Undefined"; + return BT::PreCondNames[static_cast(cond)]; } + return "Undefined"; } template <> -std::string toStr(const PostCond& pre) +std::string toStr(const PostCond& cond) { - switch(pre) + if(cond < BT::PostCond::COUNT_) { - case PostCond::ON_SUCCESS: - return "_onSuccess"; - case PostCond::ON_FAILURE: - return "_onFailure"; - case PostCond::ALWAYS: - return "_post"; - case PostCond::ON_HALTED: - return "_onHalted"; - default: - return "Undefined"; + return BT::PostCondNames[static_cast(cond)]; } + return "Undefined"; } AnyPtrLocked BT::TreeNode::getLockedPortContent(const std::string& key) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 31e2f28f7..8b9ce95a1 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -18,6 +18,7 @@ #include #include #include +#include "behaviortree_cpp/basic_types.h" #if defined(_MSVC_LANG) && !defined(__clang__) #define __bt_cplusplus (_MSC_VER == 1900 ? 201103L : _MSVC_LANG) @@ -35,10 +36,6 @@ #include "tinyxml2/tinyxml2.h" #include -#ifdef USING_ROS -#include -#endif - #ifdef USING_ROS2 #include #endif @@ -241,6 +238,10 @@ void XMLParser::PImpl::loadDocImpl(XMLDocument* doc, bool add_includes) } const XMLElement* xml_root = doc->RootElement(); + if(!xml_root) + { + throw RuntimeError("Invalid XML: missing root element"); + } auto format = xml_root->Attribute("BTCPP_format"); if(!format) @@ -278,9 +279,7 @@ void XMLParser::PImpl::loadDocImpl(XMLDocument* doc, bool add_includes) else { std::string ros_pkg_path; -#ifdef USING_ROS - ros_pkg_path = ros::package::getPath(ros_pkg_relative_path); -#elif defined USING_ROS2 +#if defined USING_ROS2 ros_pkg_path = ament_index_cpp::get_package_share_directory(ros_pkg_relative_path); #else @@ -547,8 +546,13 @@ void VerifyXML(const std::string& xml_text, for(auto child = node->FirstChildElement(); child != nullptr; child = child->NextSiblingElement()) { - const std::string child_name = node->FirstChildElement()->Name(); + const std::string child_name = child->Name(); const auto child_search = registered_nodes.find(child_name); + if(child_search == registered_nodes.end()) + { + ThrowError(child->GetLineNum(), + std::string("Unknown node type: ") + child_name); + } const auto child_type = child_search->second; if(child_type == NodeType::CONTROL && ((child_name == "ThreadedAction") || @@ -677,9 +681,13 @@ TreeNode::Ptr XMLParser::PImpl::createNodeFromXML(const XMLElement* element, } PortsRemapping port_remap; + NonPortAttributes other_attributes; + for(const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) { - if(IsAllowedPortName(att->Name())) + const std::string port_name = att->Name(); + const std::string port_value = att->Value(); + if(IsAllowedPortName(port_name)) { const std::string port_name = att->Name(); const std::string port_value = att->Value(); @@ -721,6 +729,10 @@ TreeNode::Ptr XMLParser::PImpl::createNodeFromXML(const XMLElement* element, port_remap[port_name] = port_value; } + else if(!IsReservedAttribute(port_name)) + { + other_attributes[port_name] = port_value; + } } NodeConfig config; @@ -738,6 +750,7 @@ TreeNode::Ptr XMLParser::PImpl::createNodeFromXML(const XMLElement* element, if(auto script = element->Attribute(attr_name)) { conditions.insert({ ID, std::string(script) }); + other_attributes.erase(attr_name); } }; @@ -752,6 +765,7 @@ TreeNode::Ptr XMLParser::PImpl::createNodeFromXML(const XMLElement* element, AddCondition(config.post_conditions, toStr(post).c_str(), post); } + config.other_attributes = other_attributes; //--------------------------------------------- TreeNode::Ptr new_node; diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 738f352e8..c4b982576 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -28,46 +28,33 @@ set(BT_TESTS gtest_tree.cpp gtest_updates.cpp gtest_wakeup.cpp + gtest_interface.cpp script_parser_test.cpp test_helper.hpp ) -set(TEST_DEPENDECIES - ${BTCPP_LIBRARY} - foonathan::lexy - bt_sample_nodes) - -if(ament_cmake_FOUND AND BUILD_TESTING) +if(ament_cmake_FOUND) find_package(ament_cmake_gtest REQUIRED) - ament_add_gtest(${BTCPP_LIBRARY}_test ${BT_TESTS}) - target_link_libraries(${BTCPP_LIBRARY}_test - ${TEST_DEPENDECIES} - ${ament_LIBRARIES}) - -elseif(catkin_FOUND AND CATKIN_ENABLE_TESTING) - - catkin_add_gtest(${BTCPP_LIBRARY}_test ${BT_TESTS}) - target_link_libraries(${BTCPP_LIBRARY}_test - ${TEST_DEPENDECIES} - Threads::Threads - ${catkin_LIBRARIES}) + ament_add_gtest(behaviortree_cpp_test ${BT_TESTS}) + target_link_libraries(behaviortree_cpp_test ${ament_LIBRARIES}) else() find_package(GTest REQUIRED) - enable_testing() - add_executable(${BTCPP_LIBRARY}_test ${BT_TESTS}) + enable_testing() + add_executable(behaviortree_cpp_test ${BT_TESTS}) + add_test(NAME btcpp_test COMMAND behaviortree_cpp_test) - target_link_libraries(${PROJECT_NAME}_test - ${TEST_DEPENDECIES} - Threads::Threads - GTest::gtest) + target_link_libraries(behaviortree_cpp_test + GTest::gtest + GTest::gtest_main) endif() -target_include_directories(${BTCPP_LIBRARY}_test PRIVATE include ${PROJECT_SOURCE_DIR}/3rdparty) -target_compile_definitions(${BTCPP_LIBRARY}_test PRIVATE BT_TEST_FOLDER="${CMAKE_CURRENT_SOURCE_DIR}") +target_link_libraries(behaviortree_cpp_test ${BTCPP_LIBRARY} bt_sample_nodes foonathan::lexy) +target_include_directories(behaviortree_cpp_test PRIVATE include ${PROJECT_SOURCE_DIR}/3rdparty) +target_compile_definitions(behaviortree_cpp_test PRIVATE BT_TEST_FOLDER="${CMAKE_CURRENT_SOURCE_DIR}") diff --git a/tests/gtest_async_action_node.cpp b/tests/gtest_async_action_node.cpp index 7e54384d0..fd19f05ee 100644 --- a/tests/gtest_async_action_node.cpp +++ b/tests/gtest_async_action_node.cpp @@ -70,7 +70,7 @@ TEST_P(NodeStatusFixture, normal_routine) TEST_F(MockedThreadedActionFixture, no_halt) { // Test verifies that halt returns immediately, if the node is idle. It - // further checks if the halt-flag is resetted correctly. + // further checks if the halt-flag is reset correctly. sn.halt(); ASSERT_TRUE(sn.isHaltRequested()); diff --git a/tests/gtest_blackboard.cpp b/tests/gtest_blackboard.cpp index fcbc272a3..35be37dab 100644 --- a/tests/gtest_blackboard.cpp +++ b/tests/gtest_blackboard.cpp @@ -458,6 +458,29 @@ struct Point double y; }; +// Template specialization to converts a string to Point. +namespace BT +{ +template <> +[[nodiscard]] Point convertFromString(StringView str) +{ + // We expect real numbers separated by semicolons + auto parts = splitString(str, ';'); + if(parts.size() != 2) + { + throw RuntimeError("invalid input)"); + } + else + { + Point output{ 0.0, 0.0 }; + output.x = convertFromString(parts[0]); + output.y = convertFromString(parts[1]); + // std::cout << "Building a position 2d object " << output.x << "; " << output.y << "\n" << std::flush; + return output; + } +} +} // end namespace BT + TEST(BlackboardTest, SetBlackboard_Issue725) { BT::BehaviorTreeFactory factory; @@ -654,3 +677,180 @@ TEST(BlackboardTest, TimestampedInterface) ASSERT_EQ(stamp_opt->seq, 2); ASSERT_GE(stamp_opt->time.count(), nsec_before); } + +TEST(BlackboardTest, SetBlackboard_Upd_Ts_SeqId) +{ + BT::BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + +