diff --git a/conda_build_config.yaml b/conda_build_config.yaml index 02b94261..1127cf7a 100644 --- a/conda_build_config.yaml +++ b/conda_build_config.yaml @@ -41,3 +41,8 @@ cxx_compiler: cxx_compiler_version: # [unix] - 13 # [linux] - 18 # [osx] + +libzenohc: + - 1.1.1 +libzenohcxx: + - 1.1.1 diff --git a/patch/dependencies.yaml b/patch/dependencies.yaml index 0a62cfe0..f545d18e 100644 --- a/patch/dependencies.yaml +++ b/patch/dependencies.yaml @@ -227,3 +227,11 @@ gz_ogre_next_vendor: add_run: ["ogre-next"] rosx_introspection: add_host: ["rapidjson"] +gz_ros2_control: + add_host: ["REQUIRE_OPENGL"] +gz_ros2_control_demos: + add_host: ["REQUIRE_OPENGL"] +zenoh_cpp_vendor: + add_host: ["libzenohc", "libzenohcxx"] +rmw_zenoh_cpp: + add_host: ["libzenohc", "libzenohcxx"] diff --git a/patch/ros-jazzy-ackermann-steering-controller.win.patch b/patch/ros-jazzy-ackermann-steering-controller.win.patch new file mode 100644 index 00000000..4ea8685f --- /dev/null +++ b/patch/ros-jazzy-ackermann-steering-controller.win.patch @@ -0,0 +1,12 @@ +diff --git a/ackermann_steering_controller/CMakeLists.txt b/ackermann_steering_controller/CMakeLists.txt +index 6ad0e9485f..874e9055b3 100644 +--- a/ackermann_steering_controller/CMakeLists.txt ++++ b/ackermann_steering_controller/CMakeLists.txt +@@ -4,6 +4,7 @@ project(ackermann_steering_controller LANGUAGES CXX) + if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Wpedantic -Wconversion) + endif() ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + # find dependencies + set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/patch/ros-jazzy-admittance-controller.win.patch b/patch/ros-jazzy-admittance-controller.win.patch new file mode 100644 index 00000000..651cd587 --- /dev/null +++ b/patch/ros-jazzy-admittance-controller.win.patch @@ -0,0 +1,14 @@ + +diff --git a/admittance_controller/CMakeLists.txt b/admittance_controller/CMakeLists.txt +index 884513deef..359e55b46d 100644 +--- a/admittance_controller/CMakeLists.txt ++++ b/admittance_controller/CMakeLists.txt +@@ -7,6 +7,8 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + -Werror=missing-braces) + endif() + ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++ + set(THIS_PACKAGE_INCLUDE_DEPENDS + angles + control_msgs diff --git a/patch/ros-jazzy-gz-ros2-control.osx.patch b/patch/ros-jazzy-gz-ros2-control.osx.patch new file mode 100644 index 00000000..b0c68645 --- /dev/null +++ b/patch/ros-jazzy-gz-ros2-control.osx.patch @@ -0,0 +1,17 @@ +diff --git a/gz_ros2_control/CMakeLists.txt b/gz_ros2_control/CMakeLists.txt +index 196f62d5..a7bdfd01 100644 +--- a/gz_ros2_control/CMakeLists.txt ++++ b/gz_ros2_control/CMakeLists.txt +@@ -24,6 +24,12 @@ find_package(pluginlib REQUIRED) + find_package(rclcpp REQUIRED) + find_package(yaml_cpp_vendor REQUIRED) + ++# Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 ++if(NOT TARGET TINYXML2::TINYXML2) ++ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) ++ set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) ++endif() ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + find_package(gz_sim_vendor REQUIRED) + find_package(gz-sim REQUIRED) + diff --git a/patch/ros-jazzy-gz-ros2-control.win.patch b/patch/ros-jazzy-gz-ros2-control.win.patch new file mode 100644 index 00000000..63c46ed8 --- /dev/null +++ b/patch/ros-jazzy-gz-ros2-control.win.patch @@ -0,0 +1,40 @@ +diff --git a/gz_ros2_control/CMakeLists.txt b/gz_ros2_control/CMakeLists.txt +index 196f62d5..a7bdfd01 100644 +--- a/gz_ros2_control/CMakeLists.txt ++++ b/gz_ros2_control/CMakeLists.txt +@@ -24,6 +24,12 @@ find_package(pluginlib REQUIRED) + find_package(rclcpp REQUIRED) + find_package(yaml_cpp_vendor REQUIRED) + ++# Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 ++if(NOT TARGET TINYXML2::TINYXML2) ++ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) ++ set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) ++endif() ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + find_package(gz_sim_vendor REQUIRED) + find_package(gz-sim REQUIRED) + +diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp +index d38ce556..333d42a5 100644 +--- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp ++++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp +@@ -15,5 +15,3 @@ +-#include +- + #include + #include + #include + +diff --git a/gz_ros2_control/src/gz_system.cpp b/gz_ros2_control/src/gz_system.cpp +index 5c9952b9..d5554d2c 100644 +--- a/gz_ros2_control/src/gz_system.cpp ++++ b/gz_ros2_control/src/gz_system.cpp +@@ -51,3 +51,7 @@ ++#ifdef ERROR ++#undef ERROR ++#endif ++ + struct jointData + { + /// \brief Joint's names. diff --git a/patch/ros-jazzy-joint-trajectory-controller.win.patch b/patch/ros-jazzy-joint-trajectory-controller.win.patch new file mode 100644 index 00000000..58efa6c2 --- /dev/null +++ b/patch/ros-jazzy-joint-trajectory-controller.win.patch @@ -0,0 +1,25 @@ +diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +index 111837cc17..df3b192c6d 100644 +--- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp ++++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +@@ -271,6 +271,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa + const rclcpp::Time & time, const JointTrajectoryPoint & desired_state, + const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error); + ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + void read_state_from_state_interfaces(JointTrajectoryPoint & state); + + /** Assign values from the command interfaces as state. +@@ -279,9 +280,12 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa + * @param[out] state to be filled with values from command interfaces. + * @return true if all interfaces exists and contain non-NaN values, false otherwise. + */ ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + bool read_state_from_command_interfaces(JointTrajectoryPoint & state); ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands); + ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + void query_state_service( + const std::shared_ptr request, + std::shared_ptr response); diff --git a/patch/ros-jazzy-kinematics-interface-kdl.win.patch b/patch/ros-jazzy-kinematics-interface-kdl.win.patch new file mode 100644 index 00000000..7a26c6c3 --- /dev/null +++ b/patch/ros-jazzy-kinematics-interface-kdl.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index afeadae..c1cc640 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -5,6 +5,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + ++# using this instead of visibility macros ++# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++ + set(THIS_PACKAGE_INCLUDE_DEPENDS + kdl_parser + kinematics_interface diff --git a/patch/ros-jazzy-kinematics-interface.win.patch b/patch/ros-jazzy-kinematics-interface.win.patch new file mode 100644 index 00000000..39610e2e --- /dev/null +++ b/patch/ros-jazzy-kinematics-interface.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 88eaf9e..f0dbffd 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -5,6 +5,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + ++# using this instead of visibility macros ++# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++ + set(THIS_PACKAGE_INCLUDE_DEPENDS + rclcpp + rclcpp_lifecycle diff --git a/patch/ros-jazzy-moveit-servo.win.patch b/patch/ros-jazzy-moveit-servo.win.patch new file mode 100644 index 00000000..31101065 --- /dev/null +++ b/patch/ros-jazzy-moveit-servo.win.patch @@ -0,0 +1,59 @@ + +diff --git a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp +index 8a6507c569..9c5d0805a6 100644 +--- a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp ++++ b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp +@@ -45,8 +45,12 @@ + #include + #include + #include ++#ifndef WIN32 + #include + #include ++#else ++#include ++#endif + + // Define used keys + namespace +@@ -88,6 +92,7 @@ class KeyboardReader + public: + KeyboardReader() : file_descriptor_(0) + { ++#ifndef WIN32 + // get the console in raw mode + tcgetattr(file_descriptor_, &cooked_); + struct termios raw; +@@ -97,23 +102,32 @@ class KeyboardReader + raw.c_cc[VEOL] = 1; + raw.c_cc[VEOF] = 2; + tcsetattr(file_descriptor_, TCSANOW, &raw); ++#endif + } + void readOne(char* c) + { ++#ifndef WIN32 + int rc = read(file_descriptor_, c, 1); + if (rc < 0) + { + throw std::runtime_error("read failed"); + } ++#else ++ *c = static_cast(_getch()); ++#endif + } + void shutdown() + { ++#ifndef WIN32 + tcsetattr(file_descriptor_, TCSANOW, &cooked_); ++#endif + } + + private: + int file_descriptor_; ++#ifndef WIN32 + struct termios cooked_; ++#endif + }; + + // Converts key-presses to Twist or Jog commands for Servo, in lieu of a controller diff --git a/patch/ros-jazzy-steering-controllers-library.win.patch b/patch/ros-jazzy-steering-controllers-library.win.patch new file mode 100644 index 00000000..2121ae43 --- /dev/null +++ b/patch/ros-jazzy-steering-controllers-library.win.patch @@ -0,0 +1,15 @@ +diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt +index fc79d54b7c..2e80ed198f 100644 +--- a/steering_controllers_library/CMakeLists.txt ++++ b/steering_controllers_library/CMakeLists.txt +@@ -7,6 +7,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + -Werror=missing-braces) + endif() + ++# using this instead of visibility macros ++# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++ + # find dependencies + set(THIS_PACKAGE_INCLUDE_DEPENDS + control_msgs diff --git a/patch/ros-jazzy-tinyxml2-vendor.patch b/patch/ros-jazzy-tinyxml2-vendor.patch new file mode 100644 index 00000000..8a8075dc --- /dev/null +++ b/patch/ros-jazzy-tinyxml2-vendor.patch @@ -0,0 +1,17 @@ +diff --git a/cmake/Modules/FindTinyXML2.cmake b/cmake/Modules/FindTinyXML2.cmake +index 87991be..5436d86 100644 +--- a/cmake/Modules/FindTinyXML2.cmake ++++ b/cmake/Modules/FindTinyXML2.cmake +@@ -67,6 +67,12 @@ else() + set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${TINYXML2_INCLUDE_DIR}) + list(APPEND TinyXML2_TARGETS tinyxml2::tinyxml2) + endif() ++ ++ # Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 ++ if(NOT TARGET TINYXML2::TINYXML2) ++ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) ++ set_property(TARGET TINYXML2::TINYXML2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) ++ endif() + endif() + + # Set mixed case INCLUDE_DIRS and LIBRARY variables from upper case ones. diff --git a/patch/ros-jazzy-ur-calibration.win.patch b/patch/ros-jazzy-ur-calibration.win.patch new file mode 100644 index 00000000..59340b8b --- /dev/null +++ b/patch/ros-jazzy-ur-calibration.win.patch @@ -0,0 +1,31 @@ +diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt +index 0b17e4d5f..31c63864f 100644 +--- a/ur_calibration/CMakeLists.txt ++++ b/ur_calibration/CMakeLists.txt +@@ -2,10 +2,9 @@ cmake_minimum_required(VERSION 3.5) + project(ur_calibration) + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") +- add_compile_options(-Wall -Wextra -Wpedantic) ++ add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter) + endif() +- +-add_compile_options(-Wno-unused-parameter) ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") + +diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt +index 0b17e4d5f..8b8bbf871 100644 +--- a/ur_calibration/CMakeLists.txt ++++ b/ur_calibration/CMakeLists.txt +@@ -37,7 +37,7 @@ target_include_directories(calibration + ${YAML_CPP_INCLUDE_DIRS} + ) + target_link_libraries(calibration +- ${YAML_CPP_LIBRARIES} ++ yaml-cpp::yaml-cpp + ) + ament_target_dependencies(calibration + rclcpp diff --git a/patch/ros-jazzy-ur-client-library.osx.patch b/patch/ros-jazzy-ur-client-library.osx.patch new file mode 100644 index 00000000..4f6cb0ec --- /dev/null +++ b/patch/ros-jazzy-ur-client-library.osx.patch @@ -0,0 +1,295 @@ +diff --git a/include/ur_client_library/portable_endian.h b/include/ur_client_library/portable_endian.h +new file mode 100644 +index 0000000..2b43378 +--- /dev/null ++++ b/include/ur_client_library/portable_endian.h +@@ -0,0 +1,118 @@ ++// "License": Public Domain ++// I, Mathias Panzenböck, place this file hereby into the public domain. Use it at your own risk for whatever you like. ++// In case there are jurisdictions that don't support putting things in the public domain you can also consider it to ++// be "dual licensed" under the BSD, MIT and Apache licenses, if you want to. This code is trivial anyway. Consider it ++// an example on how to get the endian conversion functions on different platforms. ++ ++#ifndef PORTABLE_ENDIAN_H__ ++#define PORTABLE_ENDIAN_H__ ++ ++#if (defined(_WIN16) || defined(_WIN32) || defined(_WIN64)) && !defined(__WINDOWS__) ++ ++# define __WINDOWS__ ++ ++#endif ++ ++#if defined(__linux__) || defined(__CYGWIN__) ++ ++# include ++ ++#elif defined(__APPLE__) ++ ++# include ++ ++# define htobe16(x) OSSwapHostToBigInt16(x) ++# define htole16(x) OSSwapHostToLittleInt16(x) ++# define be16toh(x) OSSwapBigToHostInt16(x) ++# define le16toh(x) OSSwapLittleToHostInt16(x) ++ ++# define htobe32(x) OSSwapHostToBigInt32(x) ++# define htole32(x) OSSwapHostToLittleInt32(x) ++# define be32toh(x) OSSwapBigToHostInt32(x) ++# define le32toh(x) OSSwapLittleToHostInt32(x) ++ ++# define htobe64(x) OSSwapHostToBigInt64(x) ++# define htole64(x) OSSwapHostToLittleInt64(x) ++# define be64toh(x) OSSwapBigToHostInt64(x) ++# define le64toh(x) OSSwapLittleToHostInt64(x) ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++ ++#elif defined(__OpenBSD__) ++ ++# include ++ ++#elif defined(__NetBSD__) || defined(__FreeBSD__) || defined(__DragonFly__) ++ ++# include ++ ++# define be16toh(x) betoh16(x) ++# define le16toh(x) letoh16(x) ++ ++# define be32toh(x) betoh32(x) ++# define le32toh(x) letoh32(x) ++ ++# define be64toh(x) betoh64(x) ++# define le64toh(x) letoh64(x) ++ ++#elif defined(__WINDOWS__) ++ ++# include ++# include ++ ++# if BYTE_ORDER == LITTLE_ENDIAN ++ ++# define htobe16(x) htons(x) ++# define htole16(x) (x) ++# define be16toh(x) ntohs(x) ++# define le16toh(x) (x) ++ ++# define htobe32(x) htonl(x) ++# define htole32(x) (x) ++# define be32toh(x) ntohl(x) ++# define le32toh(x) (x) ++ ++# define htobe64(x) htonll(x) ++# define htole64(x) (x) ++# define be64toh(x) ntohll(x) ++# define le64toh(x) (x) ++ ++# elif BYTE_ORDER == BIG_ENDIAN ++ ++ /* that would be xbox 360 */ ++# define htobe16(x) (x) ++# define htole16(x) __builtin_bswap16(x) ++# define be16toh(x) (x) ++# define le16toh(x) __builtin_bswap16(x) ++ ++# define htobe32(x) (x) ++# define htole32(x) __builtin_bswap32(x) ++# define be32toh(x) (x) ++# define le32toh(x) __builtin_bswap32(x) ++ ++# define htobe64(x) (x) ++# define htole64(x) __builtin_bswap64(x) ++# define be64toh(x) (x) ++# define le64toh(x) __builtin_bswap64(x) ++ ++# else ++ ++# error byte order not supported ++ ++# endif ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++ ++#else ++ ++# error platform not supported ++ ++#endif ++ ++#endif + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 878ffed..a1b176e 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -1,4 +1,4 @@ +-cmake_minimum_required(VERSION 3.0.2) ++cmake_minimum_required(VERSION 3.14.0) + project(ur_client_library) + + set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules/" ${CMAKE_MODULE_PATH}) +@@ -10,13 +10,6 @@ endif() + + option(WITH_ASAN "Compile with address sanitizer support" OFF) + +-## +-## Check C++11 support / enable global pedantic and Wall +-## +-include(DefineCXX17CompilerFlag) +-DEFINE_CXX_17_COMPILER_FLAG(CXX17_FLAG) +-set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") +- + add_library(urcl SHARED + src/comm/tcp_socket.cpp + src/comm/tcp_server.cpp +@@ -51,8 +44,11 @@ add_library(urcl SHARED + src/helpers.cpp + ) + add_library(ur_client_library::urcl ALIAS urcl) +-target_compile_options(urcl PRIVATE -Wall -Wextra -Wno-unused-parameter) +-target_compile_options(urcl PUBLIC ${CXX17_FLAG}) ++target_compile_options(urcl PRIVATE ++ $<$:/W4 /WX> ++ $<$>:-Wall -Wextra -Wno-unused-parameter> ++) ++target_compile_features(urcl PUBLIC cxx_std_17) + if(WITH_ASAN) + target_compile_options(urcl PUBLIC -fsanitize=address) + target_link_options(urcl PUBLIC -fsanitize=address) +@@ -69,6 +65,9 @@ endif() + if(CMAKE_THREAD_LIBS_INIT) + target_link_libraries(urcl PUBLIC "${CMAKE_THREAD_LIBS_INIT}") + endif() ++if(UNIX AND NOT APPLE) ++ target_link_libraries(urcl PUBLIC "rt") ++endif() + + ## + ## Build testing if enabled by option +diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt +index eb4c313..6972cf4 100644 +--- a/examples/CMakeLists.txt ++++ b/examples/CMakeLists.txt +@@ -3,13 +3,6 @@ project(ur_driver_examples) + + # find_package(ur_client_library REQUIRED) + +-# # +-# # Check C++11 support / enable global pedantic and Wall +-# # +-include(DefineCXX17CompilerFlag) +-DEFINE_CXX_17_COMPILER_FLAG(CXX17_FLAG) +-set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") +- + add_executable(driver_example + full_driver.cpp) + target_compile_options(driver_example PUBLIC ${CXX17_FLAG}) +diff --git a/include/ur_client_library/comm/bin_parser.h b/include/ur_client_library/comm/bin_parser.h +index e13aba6..83f8e6c 100644 +--- a/include/ur_client_library/comm/bin_parser.h ++++ b/include/ur_client_library/comm/bin_parser.h +@@ -21,7 +21,6 @@ + #pragma once + + #include +-#include + #include + #include + #include +@@ -29,6 +28,7 @@ + #include + #include + #include ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/log.h" + #include "ur_client_library/types.h" + #include "ur_client_library/exceptions.h" +diff --git a/include/ur_client_library/comm/package_serializer.h b/include/ur_client_library/comm/package_serializer.h +index 7745da9..ded500a 100644 +--- a/include/ur_client_library/comm/package_serializer.h ++++ b/include/ur_client_library/comm/package_serializer.h +@@ -29,8 +29,8 @@ + #ifndef UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + #define UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + +-#include + #include ++#include "ur_client_library/portable_endian.h" + + namespace urcl + { +diff --git a/include/ur_client_library/control/reverse_interface.h b/include/ur_client_library/control/reverse_interface.h +index 707c455..ee8c318 100644 +--- a/include/ur_client_library/control/reverse_interface.h ++++ b/include/ur_client_library/control/reverse_interface.h +@@ -35,8 +35,8 @@ + #include "ur_client_library/log.h" + #include "ur_client_library/ur/robot_receive_timeout.h" + #include +-#include + #include ++#include "ur_client_library/portable_endian.h" + + namespace urcl + { +diff --git a/include/ur_client_library/primary/package_header.h b/include/ur_client_library/primary/package_header.h +index cd64bda..440b2e4 100644 +--- a/include/ur_client_library/primary/package_header.h ++++ b/include/ur_client_library/primary/package_header.h +@@ -32,7 +32,7 @@ + + #include + #include +-#include ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/types.h" + + namespace urcl +diff --git a/include/ur_client_library/rtde/package_header.h b/include/ur_client_library/rtde/package_header.h +index f910a08..eb509ea 100644 +--- a/include/ur_client_library/rtde/package_header.h ++++ b/include/ur_client_library/rtde/package_header.h +@@ -31,7 +31,7 @@ + #define UR_CLIENT_LIBRARY_RTDE__HEADER_H_INCLUDED + + #include +-#include ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/types.h" + #include "ur_client_library/comm/package_serializer.h" + +diff --git a/src/comm/tcp_socket.cpp b/src/comm/tcp_socket.cpp +index 8803664..1d92880 100644 +--- a/src/comm/tcp_socket.cpp ++++ b/src/comm/tcp_socket.cpp +@@ -21,7 +21,6 @@ + */ + + #include +-#include + #include + #include + #include +@@ -29,6 +28,7 @@ + #include + #include + ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/log.h" + #include "ur_client_library/comm/tcp_socket.h" + +@@ -48,7 +48,9 @@ void TCPSocket::setupOptions() + { + int flag = 1; + setsockopt(socket_fd_, IPPROTO_TCP, TCP_NODELAY, &flag, sizeof(int)); ++#ifndef __APPLE__ + setsockopt(socket_fd_, IPPROTO_TCP, TCP_QUICKACK, &flag, sizeof(int)); ++#endif + + if (recv_timeout_ != nullptr) + { diff --git a/patch/ros-jazzy-ur-client-library.win.patch b/patch/ros-jazzy-ur-client-library.win.patch new file mode 100644 index 00000000..d4c06487 --- /dev/null +++ b/patch/ros-jazzy-ur-client-library.win.patch @@ -0,0 +1,1020 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 878ffede2..2ef4cf829 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -9,15 +9,16 @@ if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + endif() + + option(WITH_ASAN "Compile with address sanitizer support" OFF) ++option(BUILD_SHARED_LIBS "Build using shared libraries" ON) ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + ## + ## Check C++11 support / enable global pedantic and Wall + ## + include(DefineCXX17CompilerFlag) + DEFINE_CXX_17_COMPILER_FLAG(CXX17_FLAG) +-set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") + +-add_library(urcl SHARED ++add_library(urcl + src/comm/tcp_socket.cpp + src/comm/tcp_server.cpp + src/control/reverse_interface.cpp +@@ -51,12 +52,22 @@ add_library(urcl SHARED + src/helpers.cpp + ) + add_library(ur_client_library::urcl ALIAS urcl) +-target_compile_options(urcl PRIVATE -Wall -Wextra -Wno-unused-parameter) +-target_compile_options(urcl PUBLIC ${CXX17_FLAG}) +-if(WITH_ASAN) +- target_compile_options(urcl PUBLIC -fsanitize=address) +- target_link_options(urcl PUBLIC -fsanitize=address) ++ ++if(MSVC) ++ include_directories(${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/endian) ++ target_link_libraries(urcl ws2_32) ++else() ++ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") ++ target_compile_options(urcl PRIVATE -Wall -Wextra -Wno-unused-parameter) ++ ++ if(WITH_ASAN) ++ target_compile_options(urcl PUBLIC -fsanitize=address) ++ target_link_options(urcl PUBLIC -fsanitize=address) ++ endif() + endif() ++ ++target_compile_options(urcl PUBLIC ${CXX17_FLAG}) ++ + target_include_directories( urcl PUBLIC + $ + $ +@@ -87,6 +98,7 @@ include(GNUInstallDirs) + install(TARGETS urcl EXPORT urcl_targets + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ++ ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + ) + install(DIRECTORY include/ DESTINATION include) + +diff --git a/CMakeModules/DefineCXX17CompilerFlag.cmake b/CMakeModules/DefineCXX17CompilerFlag.cmake +index 37a6058b0..ad9992e65 100644 +--- a/CMakeModules/DefineCXX17CompilerFlag.cmake ++++ b/CMakeModules/DefineCXX17CompilerFlag.cmake +@@ -33,23 +33,26 @@ include(CheckCXXCompilerFlag) + macro (DEFINE_CXX_17_COMPILER_FLAG _RESULT) + if(NOT DEFINED "${_RESULT}") + +- if(NOT CMAKE_REQUIRED_QUIET) +- message(STATUS "Performing C++17 Test") +- endif() +- +- # Check for default argument (all newer compilers) +- CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) +- if(COMPILER_SUPPORTS_CXX17) +- set(${_RESULT} "-std=c++17" CACHE INTERNAL "C++17 flag") ++ if(MSVC AND MSVC_VERSION GREATER 1919) ++ set(${_RESULT} "/std:c++17" CACHE INTERNAL "C++17 flag") + else() +- # Check for older version (before 2017) +- CHECK_CXX_COMPILER_FLAG("-std=c++1z" COMPILER_SUPPORTS_CXX1Z) +- if(COMPILER_SUPPORTS_CXX1Z) +- set(${_RESULT} "-std=c++1z" CACHE INTERNAL "C++17 flag") ++ if(NOT CMAKE_REQUIRED_QUIET) ++ message(STATUS "Performing C++17 Test") ++ endif() ++ ++ # Check for default argument (all newer compilers) ++ CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) ++ if(COMPILER_SUPPORTS_CXX17) ++ set(${_RESULT} "-std=c++17" CACHE INTERNAL "C++17 flag") + else() +- message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++17 support. Please use a different C++ compiler.") ++ # Check for older version (before 2017) ++ CHECK_CXX_COMPILER_FLAG("-std=c++1z" COMPILER_SUPPORTS_CXX1Z) ++ if(COMPILER_SUPPORTS_CXX1Z) ++ set(${_RESULT} "-std=c++1z" CACHE INTERNAL "C++17 flag") ++ else() ++ message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++17 support. Please use a different C++ compiler.") ++ endif() + endif() + endif() +- + endif() + endmacro() +diff --git a/examples/dashboard_example.cpp b/examples/dashboard_example.cpp +index 81eda8cbe..dda78d761 100644 +--- a/examples/dashboard_example.cpp ++++ b/examples/dashboard_example.cpp +@@ -32,11 +32,11 @@ + + #include + #include ++#include + + #include + #include + #include +-#include + + using namespace urcl; + +@@ -97,7 +97,11 @@ int main(int argc, char* argv[]) + return 1; + } + ++#ifdef _WIN32 ++ ::Sleep(1000); ++#else // _WIN32 + sleep(1); ++#endif // _WIN32 + + // Play loaded program + if (!my_dashboard->commandPlay()) +diff --git a/include/ur_client_library/comm/bin_parser.h b/include/ur_client_library/comm/bin_parser.h +index e13aba6b9..5b968e5a6 100644 +--- a/include/ur_client_library/comm/bin_parser.h ++++ b/include/ur_client_library/comm/bin_parser.h +@@ -21,7 +21,6 @@ + #pragma once + + #include +-#include + #include + #include + #include +@@ -32,6 +31,7 @@ + #include "ur_client_library/log.h" + #include "ur_client_library/types.h" + #include "ur_client_library/exceptions.h" ++#include "ur_client_library/portable_endian.h" + + namespace urcl + { +diff --git a/include/ur_client_library/comm/package_serializer.h b/include/ur_client_library/comm/package_serializer.h +index 7745da9da..d941fdfe2 100644 +--- a/include/ur_client_library/comm/package_serializer.h ++++ b/include/ur_client_library/comm/package_serializer.h +@@ -29,7 +29,7 @@ + #ifndef UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + #define UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + +-#include ++#include "ur_client_library/portable_endian.h" + #include + + namespace urcl +diff --git a/include/ur_client_library/comm/socket_t.h b/include/ur_client_library/comm/socket_t.h +new file mode 100644 +index 000000000..c4fd3b56b +--- /dev/null ++++ b/include/ur_client_library/comm/socket_t.h +@@ -0,0 +1,63 @@ ++/* ++ * Copyright 2024, RoboDK Inc. ++ * ++ * Licensed under the Apache License, Version 2.0 (the "License"); ++ * you may not use this file except in compliance with the License. ++ * You may obtain a copy of the License at ++ * ++ * http://www.apache.org/licenses/LICENSE-2.0 ++ * ++ * Unless required by applicable law or agreed to in writing, software ++ * distributed under the License is distributed on an "AS IS" BASIS, ++ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. ++ * See the License for the specific language governing permissions and ++ * limitations under the License. ++ */ ++ ++#pragma once ++ ++#ifdef _WIN32 ++ ++#define NOMINMAX ++#define WIN32_LEAN_AND_MEAN ++#include ++#include ++ ++#ifndef TCP_QUICKACK ++#define TCP_QUICKACK 12 ++#endif ++ ++#ifdef ERROR ++#undef ERROR ++#endif // ERROR ++ ++typedef SOCKET socket_t; ++typedef SSIZE_T ssize_t; ++ ++static inline int ur_setsockopt(socket_t s, int level, int optname, const void* optval, unsigned int optlen) ++{ ++ return ::setsockopt(s, level, optname, reinterpret_cast(optval), static_cast(optlen)); ++} ++ ++static inline int ur_close(socket_t s) ++{ ++ return ::closesocket(s); ++} ++ ++#else // _WIN32 ++ ++#include ++#include ++#include ++#include ++ ++typedef int socket_t; ++ ++#ifndef INVALID_SOCKET ++#define INVALID_SOCKET (-1) ++#endif ++ ++#define ur_setsockopt setsockopt ++#define ur_close close ++ ++#endif // _WIN32 +diff --git a/include/ur_client_library/comm/stream.h b/include/ur_client_library/comm/stream.h +index d10114345..8a573492e 100644 +--- a/include/ur_client_library/comm/stream.h ++++ b/include/ur_client_library/comm/stream.h +@@ -19,9 +19,6 @@ + */ + + #pragma once +-#include +-#include +-#include + #include + #include + #include +diff --git a/include/ur_client_library/comm/tcp_server.h b/include/ur_client_library/comm/tcp_server.h +index 8cad8ddee..0863c8fc0 100644 +--- a/include/ur_client_library/comm/tcp_server.h ++++ b/include/ur_client_library/comm/tcp_server.h +@@ -29,16 +29,15 @@ + #ifndef UR_CLIENT_LIBRARY_TCP_SERVER_H_INCLUDED + #define UR_CLIENT_LIBRARY_TCP_SERVER_H_INCLUDED + +-#include +-#include +-#include +-#include + + #include + #include + #include + #include + ++#include "ur_client_library/comm/socket_t.h" ++ ++ + namespace urcl + { + namespace comm +@@ -178,25 +177,22 @@ class TCPServer + std::atomic keep_running_; + std::thread worker_thread_; + +- std::atomic listen_fd_; ++ std::atomic listen_fd_; + int port_; + +- int maxfd_; ++ socket_t maxfd_; + fd_set masterfds_; + fd_set tempfds_; + + uint32_t max_clients_allowed_; +- std::vector client_fds_; +- +- // Pipe for the self-pipe trick (https://cr.yp.to/docs/selfpipe.html) +- int self_pipe_[2]; ++ std::vector client_fds_; + + static const int INPUT_BUFFER_SIZE = 100; + char input_buffer_[INPUT_BUFFER_SIZE]; + +- std::function new_connection_callback_; +- std::function disconnect_callback_; +- std::function message_callback_; ++ std::function new_connection_callback_; ++ std::function disconnect_callback_; ++ std::function message_callback_; + }; + + } // namespace comm +diff --git a/include/ur_client_library/comm/tcp_socket.h b/include/ur_client_library/comm/tcp_socket.h +index 513648106..b1252b6e4 100644 +--- a/include/ur_client_library/comm/tcp_socket.h ++++ b/include/ur_client_library/comm/tcp_socket.h +@@ -19,15 +19,15 @@ + */ + + #pragma once +-#include +-#include +-#include + #include + #include + #include + #include + #include + ++#include "ur_client_library/comm/socket_t.h" ++ ++ + namespace urcl + { + namespace comm +@@ -49,7 +49,7 @@ enum class SocketState + class TCPSocket + { + private: +- std::atomic socket_fd_; ++ std::atomic socket_fd_; + std::atomic state_; + std::chrono::milliseconds reconnection_time_; + bool reconnection_time_modified_deprecated_ = false; +diff --git a/include/ur_client_library/control/reverse_interface.h b/include/ur_client_library/control/reverse_interface.h +index 707c4554b..ab4d2478a 100644 +--- a/include/ur_client_library/control/reverse_interface.h ++++ b/include/ur_client_library/control/reverse_interface.h +@@ -35,7 +35,7 @@ + #include "ur_client_library/log.h" + #include "ur_client_library/ur/robot_receive_timeout.h" + #include +-#include ++#include + #include + + namespace urcl +diff --git a/include/ur_client_library/exceptions.h b/include/ur_client_library/exceptions.h +index 5145a75d8..1ccdc4294 100644 +--- a/include/ur_client_library/exceptions.h ++++ b/include/ur_client_library/exceptions.h +@@ -34,6 +34,15 @@ + #include + #include "ur/version_information.h" + ++#ifdef _WIN32 ++#define NOMINMAX ++#define WIN32_LEAN_AND_MEAN ++#include ++#ifdef ERROR ++#undef ERROR ++#endif // ERROR ++#endif ++ + namespace urcl + { + /*! +diff --git a/include/ur_client_library/helpers.h b/include/ur_client_library/helpers.h +index ad070836e..7d542e804 100644 +--- a/include/ur_client_library/helpers.h ++++ b/include/ur_client_library/helpers.h +@@ -29,7 +29,37 @@ + #ifndef UR_CLIENT_LIBRARY_HELPERS_H_INCLUDED + #define UR_CLIENT_LIBRARY_HELPERS_H_INCLUDED + +-#include ++ ++#ifdef _WIN32 ++ ++#define NOMINMAX ++#define WIN32_LEAN_AND_MEAN ++#include ++ ++#ifdef ERROR ++#undef ERROR ++#endif // ERROR ++ ++#define SCHED_FIFO (1) ++ ++typedef HANDLE pthread_t; ++ ++ ++static inline pthread_t pthread_self() ++{ ++ return ::GetCurrentThread(); ++} ++ ++static inline int sched_get_priority_max(int policy) ++{ ++ return THREAD_PRIORITY_TIME_CRITICAL; ++} ++ ++#else // _WIN32 ++ ++#include ++ ++#endif // _WIN32 + + namespace urcl + { +diff --git a/include/ur_client_library/portable_endian.h b/include/ur_client_library/portable_endian.h +new file mode 100644 +index 000000000..3ed95719b +--- /dev/null ++++ b/include/ur_client_library/portable_endian.h +@@ -0,0 +1,103 @@ ++// ++// endian.h ++// ++// https://gist.github.com/panzi/6856583 ++// ++// I, Mathias Panzenböck, place this file hereby into the public domain. Use ++// it at your own risk for whatever you like. In case there are ++// jurisdictions that don't support putting things in the public domain you ++// can also consider it to be "dual licensed" under the BSD, MIT and Apache ++// licenses, if you want to. This code is trivial anyway. Consider it an ++// example on how to get the endian conversion functions on different ++// platforms. ++ ++#ifndef PORTABLE_ENDIAN_H__ ++#define PORTABLE_ENDIAN_H__ ++ ++// Byte order ++#if defined(linux) || defined(__linux) || defined(__linux__) || defined(__CYGWIN__) ++# include ++#elif defined(__APPLE__) ++# include ++ ++# define htobe16(x) OSSwapHostToBigInt16(x) ++# define htole16(x) OSSwapHostToLittleInt16(x) ++# define be16toh(x) OSSwapBigToHostInt16(x) ++# define le16toh(x) OSSwapLittleToHostInt16(x) ++ ++# define htobe32(x) OSSwapHostToBigInt32(x) ++# define htole32(x) OSSwapHostToLittleInt32(x) ++# define be32toh(x) OSSwapBigToHostInt32(x) ++# define le32toh(x) OSSwapLittleToHostInt32(x) ++ ++# define htobe64(x) OSSwapHostToBigInt64(x) ++# define htole64(x) OSSwapHostToLittleInt64(x) ++# define be64toh(x) OSSwapBigToHostInt64(x) ++# define le64toh(x) OSSwapLittleToHostInt64(x) ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++#elif defined(__OpenBSD__) ++# include ++#elif defined(__NetBSD__) || defined(__FreeBSD__) || defined(__DragonFly__) ++# include ++ ++# define be16toh(x) betoh16(x) ++# define le16toh(x) letoh16(x) ++ ++# define be32toh(x) betoh32(x) ++# define le32toh(x) letoh32(x) ++ ++# define be64toh(x) betoh64(x) ++# define le64toh(x) letoh64(x) ++#elif defined(_WIN32) ++# include ++# if BYTE_ORDER == LITTLE_ENDIAN ++# if defined(_MSC_VER) ++# define htobe16(x) _byteswap_ushort(x) ++# define htole16(x) (x) ++# define be16toh(x) _byteswap_ushort(x) ++# define le16toh(x) (x) ++ ++# define htobe32(x) _byteswap_ulong(x) ++# define htole32(x) (x) ++# define be32toh(x) _byteswap_ulong(x) ++# define le32toh(x) (x) ++ ++# define htobe64(x) _byteswap_uint64(x) ++# define htole64(x) (x) ++# define be64toh(x) _byteswap_uint64(x) ++# define le64toh(x) (x) ++# elif defined(__GNUC__) || defined(__clang__) ++# define htobe16(x) __builtin_bswap16(x) ++# define htole16(x) (x) ++# define be16toh(x) __builtin_bswap16(x) ++# define le16toh(x) (x) ++ ++# define htobe32(x) __builtin_bswap32(x) ++# define htole32(x) (x) ++# define be32toh(x) __builtin_bswap32(x) ++# define le32toh(x) (x) ++ ++# define htobe64(x) __builtin_bswap64(x) ++# define htole64(x) (x) ++# define be64toh(x) __builtin_bswap64(x) ++# define le64toh(x) (x) ++# else ++# error Compiler is not supported ++# endif ++# else ++# error Byte order is not supported ++# endif ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++#else ++# error Platform is not supported ++#endif ++ ++#endif // PORTABLE_ENDIAN_H__ +diff --git a/include/ur_client_library/rtde/package_header.h b/include/ur_client_library/rtde/package_header.h +index f910a0843..eb509ea54 100644 +--- a/include/ur_client_library/rtde/package_header.h ++++ b/include/ur_client_library/rtde/package_header.h +@@ -31,7 +31,7 @@ + #define UR_CLIENT_LIBRARY_RTDE__HEADER_H_INCLUDED + + #include +-#include ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/types.h" + #include "ur_client_library/comm/package_serializer.h" + +diff --git a/src/comm/tcp_server.cpp b/src/comm/tcp_server.cpp +index ea5122c7e..edf5b3214 100644 +--- a/src/comm/tcp_server.cpp ++++ b/src/comm/tcp_server.cpp +@@ -32,12 +32,12 @@ + #include + + #include +-#include + #include + #include + #include + #include + ++ + namespace urcl + { + namespace comm +@@ -45,6 +45,11 @@ namespace comm + TCPServer::TCPServer(const int port, const size_t max_num_tries, const std::chrono::milliseconds reconnection_time) + : port_(port), maxfd_(0), max_clients_allowed_(0) + { ++#ifdef _WIN32 ++ WSAData data; ++ ::WSAStartup(MAKEWORD(1, 1), &data); ++#endif // _WIN32 ++ + init(); + bind(max_num_tries, reconnection_time); + startListen(); +@@ -54,68 +59,56 @@ TCPServer::~TCPServer() + { + URCL_LOG_DEBUG("Destroying TCPServer object."); + shutdown(); +- close(listen_fd_); ++ ur_close(listen_fd_); + } + + void TCPServer::init() + { +- int err = (listen_fd_ = socket(AF_INET, SOCK_STREAM, 0)); +- if (err == -1) ++ socket_t err = (listen_fd_ = socket(AF_INET, SOCK_STREAM, 0)); ++ if (err < 0) + { + throw std::system_error(std::error_code(errno, std::generic_category()), "Failed to create socket endpoint"); + } + int flag = 1; +- setsockopt(listen_fd_, SOL_SOCKET, SO_REUSEADDR, &flag, sizeof(int)); +- setsockopt(listen_fd_, SOL_SOCKET, SO_KEEPALIVE, &flag, sizeof(int)); ++#ifndef _WIN32 ++ ur_setsockopt(listen_fd_, SOL_SOCKET, SO_REUSEADDR, &flag, sizeof(int)); ++#endif ++ ur_setsockopt(listen_fd_, SOL_SOCKET, SO_KEEPALIVE, &flag, sizeof(int)); + + URCL_LOG_DEBUG("Created socket with FD %d", (int)listen_fd_); + + FD_ZERO(&masterfds_); + FD_ZERO(&tempfds_); ++} + +- // Create self-pipe for interrupting the worker loop +- if (pipe(self_pipe_) == -1) +- { +- throw std::system_error(std::error_code(errno, std::generic_category()), "Error creating self-pipe"); +- } +- URCL_LOG_DEBUG("Created read pipe at FD %d", self_pipe_[0]); +- FD_SET(self_pipe_[0], &masterfds_); ++void TCPServer::shutdown() ++{ ++ keep_running_ = false; + +- // Make read and write ends of pipe nonblocking +- int flags; +- flags = fcntl(self_pipe_[0], F_GETFL); +- if (flags == -1) +- { +- throw std::system_error(std::error_code(errno, std::generic_category()), "fcntl-F_GETFL"); +- } +- flags |= O_NONBLOCK; // Make read end nonblocking +- if (fcntl(self_pipe_[0], F_SETFL, flags) == -1) ++ socket_t shutdown_socket = ::socket(AF_INET, SOCK_STREAM, 0); ++ if (shutdown_socket == INVALID_SOCKET) + { +- throw std::system_error(std::error_code(errno, std::generic_category()), "fcntl-F_SETFL"); ++ throw std::system_error(std::error_code(errno, std::generic_category()), "Unable to create shutdown socket."); + } + +- flags = fcntl(self_pipe_[1], F_GETFL); +- if (flags == -1) ++#ifdef _WIN32 ++ unsigned long mode = 1; ++ ::ioctlsocket(shutdown_socket, FIONBIO, &mode); ++#else ++ int flags = ::fcntl(shutdown_socket, F_GETFL, 0); ++ if (flags >= 0) + { +- throw std::system_error(std::error_code(errno, std::generic_category()), "fcntl-F_GETFL"); ++ ::fcntl(shutdown_socket, F_SETFL, flags | O_NONBLOCK); + } +- flags |= O_NONBLOCK; // Make write end nonblocking +- if (fcntl(self_pipe_[1], F_SETFL, flags) == -1) +- { +- throw std::system_error(std::error_code(errno, std::generic_category()), "fcntl-F_SETFL"); +- } +-} ++#endif + +-void TCPServer::shutdown() +-{ +- keep_running_ = false; ++ struct sockaddr_in address; ++ memset(&address, 0, sizeof(address)); ++ address.sin_family = AF_INET; ++ address.sin_addr.s_addr = htonl(INADDR_LOOPBACK); ++ address.sin_port = htons(port_); + +- // This is basically the self-pipe trick. Writing to the pipe will trigger an event for the event +- // handler which will stop the select() call from blocking. +- if (::write(self_pipe_[1], "x", 1) == -1 && errno != EAGAIN) +- { +- throw std::system_error(std::error_code(errno, std::generic_category()), "Writing to self-pipe failed."); +- } ++ ::connect(shutdown_socket, reinterpret_cast(&address), sizeof(address)); + + // After the event loop has finished the thread will be joinable. + if (worker_thread_.joinable()) +@@ -160,7 +153,7 @@ void TCPServer::bind(const size_t max_num_tries, const std::chrono::milliseconds + URCL_LOG_DEBUG("Bound %d:%d to FD %d", server_addr.sin_addr.s_addr, port_, (int)listen_fd_); + + FD_SET(listen_fd_, &masterfds_); +- maxfd_ = std::max((int)listen_fd_, self_pipe_[0]); ++ maxfd_ = listen_fd_; + } + + void TCPServer::startListen() +@@ -193,7 +186,7 @@ void TCPServer::handleConnect() + FD_SET(client_fd, &masterfds_); + if (client_fd > maxfd_) + { +- maxfd_ = std::max(client_fd, self_pipe_[0]); ++ maxfd_ = client_fd; + } + if (new_connection_callback_) + { +@@ -205,7 +198,7 @@ void TCPServer::handleConnect() + URCL_LOG_WARN("Connection attempt on port %d while maximum number of clients (%d) is already connected. Closing " + "connection.", + port_, max_clients_allowed_); +- close(client_fd); ++ ur_close(client_fd); + } + } + +@@ -222,30 +215,13 @@ void TCPServer::spin() + return; + } + +- // Read part if pipe-trick. This will help interrupting the event handler thread. +- if (FD_ISSET(self_pipe_[0], &masterfds_)) ++ if (!keep_running_) + { +- URCL_LOG_DEBUG("Activity on self-pipe"); +- char buffer; +- if (read(self_pipe_[0], &buffer, 1) == -1) +- { +- while (true) +- { +- if (errno == EAGAIN) +- break; +- else +- URCL_LOG_ERROR("read failed"); +- } +- } +- else +- { +- URCL_LOG_DEBUG("Self-pipe triggered"); +- return; +- } ++ return; + } + + // Check which fd has an activity +- for (int i = 0; i <= maxfd_; i++) ++ for (socket_t i = 0; i <= maxfd_; i++) + { + if (FD_ISSET(i, &tempfds_)) + { +@@ -266,7 +242,7 @@ void TCPServer::spin() + void TCPServer::handleDisconnect(const int fd) + { + URCL_LOG_DEBUG("%d disconnected.", fd); +- close(fd); ++ ur_close(fd); + if (disconnect_callback_) + { + disconnect_callback_(fd); +@@ -285,7 +261,7 @@ void TCPServer::handleDisconnect(const int fd) + + void TCPServer::readData(const int fd) + { +- bzero(&input_buffer_, INPUT_BUFFER_SIZE); // clear input buffer ++ memset(input_buffer_, 0, INPUT_BUFFER_SIZE); // clear input buffer + int nbytesrecv = recv(fd, input_buffer_, INPUT_BUFFER_SIZE, 0); + if (nbytesrecv > 0) + { +@@ -340,7 +316,7 @@ bool TCPServer::write(const int fd, const uint8_t* buf, const size_t buf_len, si + // handle partial sends + while (written < buf_len) + { +- ssize_t sent = ::send(fd, buf + written, remaining, 0); ++ ssize_t sent = ::send(fd, reinterpret_cast(buf + written), remaining, 0); + + if (sent <= 0) + { +diff --git a/src/comm/tcp_socket.cpp b/src/comm/tcp_socket.cpp +index 8803664a8..fe9a32980 100644 +--- a/src/comm/tcp_socket.cpp ++++ b/src/comm/tcp_socket.cpp +@@ -20,15 +20,17 @@ + * limitations under the License. + */ + +-#include +-#include +-#include +-#include ++#include + #include + #include + #include + #include + ++#ifndef _WIN32 ++#include ++#include ++#endif ++ + #include "ur_client_library/log.h" + #include "ur_client_library/comm/tcp_socket.h" + +@@ -36,8 +38,12 @@ namespace urcl + { + namespace comm + { +-TCPSocket::TCPSocket() : socket_fd_(-1), state_(SocketState::Invalid), reconnection_time_(std::chrono::seconds(10)) ++TCPSocket::TCPSocket() : socket_fd_(INVALID_SOCKET), state_(SocketState::Invalid), reconnection_time_(std::chrono::seconds(10)) + { ++#ifdef _WIN32 ++ WSAData data; ++ ::WSAStartup(MAKEWORD(1, 1), &data); ++#endif // _WIN32 + } + TCPSocket::~TCPSocket() + { +@@ -47,12 +53,18 @@ TCPSocket::~TCPSocket() + void TCPSocket::setupOptions() + { + int flag = 1; +- setsockopt(socket_fd_, IPPROTO_TCP, TCP_NODELAY, &flag, sizeof(int)); +- setsockopt(socket_fd_, IPPROTO_TCP, TCP_QUICKACK, &flag, sizeof(int)); ++ ur_setsockopt(socket_fd_, IPPROTO_TCP, TCP_NODELAY, &flag, sizeof(int)); ++ ur_setsockopt(socket_fd_, IPPROTO_TCP, TCP_QUICKACK, &flag, sizeof(int)); + + if (recv_timeout_ != nullptr) + { +- setsockopt(socket_fd_, SOL_SOCKET, SO_RCVTIMEO, recv_timeout_.get(), sizeof(timeval)); ++#ifdef _WIN32 ++ DWORD value = recv_timeout_->tv_sec * 1000; ++ value += recv_timeout_->tv_usec / 1000; ++ ur_setsockopt(socket_fd_, SOL_SOCKET, SO_RCVTIMEO, &value, sizeof(value)); ++#else ++ ur_setsockopt(socket_fd_, SOL_SOCKET, SO_RCVTIMEO, recv_timeout_.get(), sizeof(timeval)); ++#endif + } + } + +@@ -141,8 +153,8 @@ void TCPSocket::close() + if (socket_fd_ >= 0) + { + state_ = SocketState::Closed; +- ::close(socket_fd_); +- socket_fd_ = -1; ++ ::ur_close(socket_fd_); ++ socket_fd_ = INVALID_SOCKET; + } + } + +@@ -179,7 +191,7 @@ bool TCPSocket::read(uint8_t* buf, const size_t buf_len, size_t& read) + if (state_ != SocketState::Connected) + return false; + +- ssize_t res = ::recv(socket_fd_, buf, buf_len, 0); ++ ssize_t res = ::recv(socket_fd_, reinterpret_cast(buf), buf_len, 0); + + if (res == 0) + { +@@ -188,11 +200,20 @@ bool TCPSocket::read(uint8_t* buf, const size_t buf_len, size_t& read) + } + else if (res < 0) + { ++ res = 0; ++#ifdef _WIN32 ++ int code = ::WSAGetLastError(); ++ if (code != WSAETIMEDOUT && code != WSAEWOULDBLOCK) ++ { ++ state_ = SocketState::Disconnected; ++ } ++#else + if (!(errno == EAGAIN || errno == EWOULDBLOCK)) + { + // any permanent error should be detected early + state_ = SocketState::Disconnected; + } ++#endif + return false; + } + +@@ -215,7 +236,7 @@ bool TCPSocket::write(const uint8_t* buf, const size_t buf_len, size_t& written) + // handle partial sends + while (written < buf_len) + { +- ssize_t sent = ::send(socket_fd_, buf + written, remaining, 0); ++ ssize_t sent = ::send(socket_fd_, reinterpret_cast(buf + written), remaining, 0); + + if (sent <= 0) + { +@@ -223,7 +244,7 @@ bool TCPSocket::write(const uint8_t* buf, const size_t buf_len, size_t& written) + return false; + } + +- written += sent; ++ written += static_cast(sent); + remaining -= sent; + } + +diff --git a/src/helpers.cpp b/src/helpers.cpp +index 2cd1eab10..d08bd9cb0 100644 +--- a/src/helpers.cpp ++++ b/src/helpers.cpp +@@ -37,6 +37,9 @@ namespace urcl + { + bool setFiFoScheduling(pthread_t& thread, const int priority) + { ++#ifdef _WIN32 ++ return ::SetThreadPriority(thread, priority); ++#else // _WIN32 + struct sched_param params; + params.sched_priority = priority; + int ret = pthread_setschedparam(thread, SCHED_FIFO, ¶ms); +@@ -88,5 +91,6 @@ bool setFiFoScheduling(pthread_t& thread, const int priority) + } + } + return true; ++#endif + } + } // namespace urcl +diff --git a/src/ur/dashboard_client.cpp b/src/ur/dashboard_client.cpp +index 8469a766c..75650688f 100644 +--- a/src/ur/dashboard_client.cpp ++++ b/src/ur/dashboard_client.cpp +@@ -29,11 +29,15 @@ + #include + #include + #include +-#include + #include + #include + #include + ++#ifndef _WIN32 ++#include ++#endif // !_WIN32 ++ ++ + using namespace std::chrono_literals; + + namespace urcl +@@ -59,7 +63,7 @@ bool DashboardClient::connect(const size_t max_num_tries, const std::chrono::mil + timeval configured_tv = getConfiguredReceiveTimeout(); + timeval tv; + +- while (not ret_val) ++ while (!ret_val) + { + // The first read after connection can take more time. + tv.tv_sec = 10; +diff --git a/tests/test_pipeline.cpp b/tests/test_pipeline.cpp +index fccf0dd80..f7e0171d2 100644 +--- a/tests/test_pipeline.cpp ++++ b/tests/test_pipeline.cpp +@@ -60,7 +60,7 @@ class PipelineTest : public ::testing::Test + pipeline_->init(); + } + +- void Teardown() ++ void teardown() + { + // Clean up + pipeline_->stop(); +@@ -247,7 +247,7 @@ TEST_F(PipelineTest, connect_non_connected_robot) + auto end = std::chrono::system_clock::now(); + auto elapsed = end - start; + // This is only a rough estimate, obviously +- EXPECT_LT(elapsed, std::chrono::milliseconds(1500)); ++ EXPECT_LT(elapsed, std::chrono::milliseconds(7500)); + } + + int main(int argc, char* argv[]) +diff --git a/tests/test_producer.cpp b/tests/test_producer.cpp +index 15663cbb1..fbfecee95 100644 +--- a/tests/test_producer.cpp ++++ b/tests/test_producer.cpp +@@ -49,7 +49,7 @@ class ProducerTest : public ::testing::Test + server_->start(); + } + +- void Teardown() ++ void teardown() + { + // Clean up + server_.reset(); +@@ -133,7 +133,7 @@ TEST_F(ProducerTest, connect_non_connected_robot) + auto end = std::chrono::system_clock::now(); + auto elapsed = end - start; + // This is only a rough estimate, obviously +- EXPECT_LT(elapsed, std::chrono::milliseconds(1500)); ++ EXPECT_LT(elapsed, std::chrono::milliseconds(7500)); + } + + int main(int argc, char* argv[]) +diff --git a/tests/test_stream.cpp b/tests/test_stream.cpp +index d095b41d9..28448e3c5 100644 +--- a/tests/test_stream.cpp ++++ b/tests/test_stream.cpp +@@ -51,7 +51,7 @@ class StreamTest : public ::testing::Test + server_->start(); + } + +- void Teardown() ++ void teardown() + { + // Clean up + server_.reset(); +@@ -329,7 +329,7 @@ TEST_F(StreamTest, connect_non_connected_robot) + auto end = std::chrono::system_clock::now(); + auto elapsed = end - start; + // This is only a rough estimate, obviously +- EXPECT_LT(elapsed, std::chrono::milliseconds(1500)); ++ EXPECT_LT(elapsed, std::chrono::milliseconds(7500)); + } + + int main(int argc, char* argv[]) +diff --git a/tests/test_tcp_socket.cpp b/tests/test_tcp_socket.cpp +index a96b6595b..6241a8c8d 100644 +--- a/tests/test_tcp_socket.cpp ++++ b/tests/test_tcp_socket.cpp +@@ -351,7 +351,7 @@ TEST_F(TCPSocketTest, connect_non_running_robot) + auto end = std::chrono::system_clock::now(); + auto elapsed = end - start; + // This is only a rough estimate, obviously +- EXPECT_LT(elapsed, std::chrono::milliseconds(1500)); ++ EXPECT_LT(elapsed, std::chrono::milliseconds(7500)); + } + + TEST_F(TCPSocketTest, test_deprecated_reconnection_time_interface) +@@ -374,7 +374,7 @@ TEST_F(TCPSocketTest, test_read_on_socket_abruptly_closed) + server_->write(client_fd_, data, len, written); + + // Simulate socket failure +- close(client_->getSocketFD()); ++ ur_close(client_->getSocketFD()); + + char characters; + size_t read_chars = 0; + +diff --git a/include/ur_client_library/primary/package_header.h b/include/ur_client_library/primary/package_header.h +index cd64bdaf0..440b2e405 100644 +--- a/include/ur_client_library/primary/package_header.h ++++ b/include/ur_client_library/primary/package_header.h +@@ -35,4 +35,4 @@ +-#include ++#include "ur_client_library/portable_endian.h" + #include "ur_client_library/types.h" + diff --git a/patch/ros-jazzy-ur-controllers.win.patch b/patch/ros-jazzy-ur-controllers.win.patch new file mode 100644 index 00000000..3fefcac0 --- /dev/null +++ b/patch/ros-jazzy-ur-controllers.win.patch @@ -0,0 +1,23 @@ +diff --git a/ur_controllers/CMakeLists.txt b/ur_controllers/CMakeLists.txt +index 79a89acbd..9e4584419 100644 +--- a/ur_controllers/CMakeLists.txt ++++ b/ur_controllers/CMakeLists.txt +@@ -4,6 +4,7 @@ project(ur_controllers) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra) + endif() ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + find_package(ament_cmake REQUIRED) + find_package(angles REQUIRED) +@@ -111,7 +112,9 @@ ament_target_dependencies(${PROJECT_NAME} + ${THIS_PACKAGE_INCLUDE_DEPENDS} + ) + +-target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror=return-type) ++if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") ++ target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror=return-type) ++endif() + + # prevent pluginlib from using boost + target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") diff --git a/patch/ros-jazzy-ur-robot-driver.win.patch b/patch/ros-jazzy-ur-robot-driver.win.patch new file mode 100644 index 00000000..65510454 --- /dev/null +++ b/patch/ros-jazzy-ur-robot-driver.win.patch @@ -0,0 +1,41 @@ +diff --git a/ur_robot_driver/CMakeLists.txt b/ur_robot_driver/CMakeLists.txt +index 05b59e628..78a197a44 100644 +--- a/ur_robot_driver/CMakeLists.txt ++++ b/ur_robot_driver/CMakeLists.txt +@@ -9,9 +9,12 @@ option( + OFF + ) + +-add_compile_options(-Wall) +-add_compile_options(-Wextra) +-add_compile_options(-Wno-unused-parameter) ++if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") ++ add_compile_options(-Wall) ++ add_compile_options(-Wextra) ++ add_compile_options(-Wno-unused-parameter) ++endif() ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") + +diff --git a/ur_robot_driver/src/hardware_interface.cpp b/ur_robot_driver/src/hardware_interface.cpp +index 216d7d462..b500aadc7 100644 +--- a/ur_robot_driver/src/hardware_interface.cpp ++++ b/ur_robot_driver/src/hardware_interface.cpp +@@ -45,3 +45,4 @@ ++#include "ur_robot_driver/hardware_interface.hpp" + #include "ur_client_library/exceptions.h" + #include "ur_client_library/ur/tool_communication.h" + #include "ur_client_library/ur/version_information.h" + +diff --git a/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp b/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp +index 14bdd29ea..330e4161e 100644 +--- a/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp ++++ b/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp +@@ -66,3 +66,5 @@ ++typedef unsigned int uint; ++ + namespace ur_robot_driver + { + enum class PausingState diff --git a/patch/ros-jazzy-zenoh-cpp-vendor.patch b/patch/ros-jazzy-zenoh-cpp-vendor.patch new file mode 100644 index 00000000..85d229c0 --- /dev/null +++ b/patch/ros-jazzy-zenoh-cpp-vendor.patch @@ -0,0 +1,42 @@ +diff --git a/zenoh_cpp_vendor/CMakeLists.txt b/zenoh_cpp_vendor/CMakeLists.txt +index 2d3ae046..de971841 100644 +--- a/zenoh_cpp_vendor/CMakeLists.txt ++++ b/zenoh_cpp_vendor/CMakeLists.txt +@@ -10,35 +10,10 @@ endif() + find_package(ament_cmake REQUIRED) + find_package(ament_cmake_vendor_package REQUIRED) + +-# Disable default features and enable only the most useful ones. This reduces build time and footprint. +-# For a complete list of features see: https://github.com/eclipse-zenoh/zenoh/blob/main/zenoh/Cargo.toml +-# Note: We separate the two args needed for cargo with "$" and not ";" as the +-# latter is a list separater in cmake and hence the string will be split into two +-# when expanded. +-set(ZENOHC_CARGO_FLAGS "--no-default-features$--features=shared-memory zenoh/transport_compression zenoh/transport_tcp zenoh/transport_tls") +- +-ament_vendor(zenoh_c_vendor +- VCS_URL https://github.com/eclipse-zenoh/zenoh-c.git +- VCS_VERSION 57d5e4d31d9b38fef34d7bcad3d3e54869c4ce73 +- CMAKE_ARGS +- "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" +- "-DZENOHC_BUILD_WITH_UNSTABLE_API=TRUE" +- "-DZENOHC_CUSTOM_TARGET=${ZENOHC_CUSTOM_TARGET}" +-) +- ++find_package(zenohc REQUIRED) + ament_export_dependencies(zenohc) + +-# Set VCS_VERSION to include latest changes from zenoh-c to benefit from : +-# - https://github.com/eclipse-zenoh/zenoh-cpp/pull/342 (Fix include what you use) +-ament_vendor(zenoh_cpp_vendor +- VCS_URL https://github.com/eclipse-zenoh/zenoh-cpp +- VCS_VERSION 964b64dc8b935a43147287199e7bb12da7b141e6 +- CMAKE_ARGS +- -DZENOHCXX_ZENOHC=OFF +-) +- +-externalproject_add_stepdependencies(zenoh_cpp_vendor configure zenoh_c_vendor) +- ++find_package(zenohcxx REQUIRED) + ament_export_dependencies(zenohcxx) + + ament_package() diff --git a/pixi.lock b/pixi.lock index ccc7f2e4..fcc36d18 100644 --- a/pixi.lock +++ b/pixi.lock @@ -10,7 +10,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/brotli-python-1.1.0-py311hfdbb021_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/ca-certificates-2024.12.14-hbcca054_0.conda @@ -22,8 +22,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -37,14 +37,14 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-64/libgomp-14.2.0-h77fa898_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/liblzma-5.6.3-hb9d3cd8_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.47.2-hee588c1_0.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.48.0-hee588c1_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libstdcxx-14.2.0-hc0a3c3a_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-he02047a_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-h2d0b736_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/openssl-3.4.0-h7b32b05_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/patchelf-0.17.2-h58526e2_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda @@ -56,19 +56,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h9ecbd09_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h2dc5d0c_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/rattler-build-0.35.6-hff40e2b_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/readline-8.2-h8228510_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/rpds-py-0.22.3-py311h9e33e62_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -85,14 +86,14 @@ environments: - pypi: https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/19/71/39c7c0d87f8d4e6c020a393182060eaefeeae6c01dab6a84ec346f2567df/rich-13.9.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/22/32/d0fbc4383a6a213d315c39dda9107f81654d9941c43d6c687e61995ec388/rosdistro-1.0.1-py3-none-any.whl - - pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/68/6e/264c50ce2a31473a9fdbf4fa66ca9b2b17c7455b31ef585462343818bd6c/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl - - pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + - pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e linux-aarch64: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/brotli-python-1.1.0-py311h89d996e_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/bzip2-1.0.8-h68df207_7.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ca-certificates-2024.12.14-hcefe29a_0.conda @@ -104,8 +105,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -119,14 +120,14 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libgomp-14.2.0-he277a41_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/liblzma-5.6.3-h86ecc28_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libnsl-2.0.1-h31becfc_0.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.47.2-h5eb1b54_0.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.48.0-h5eb1b54_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libstdcxx-14.2.0-h3f4de04_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libstdcxx-ng-14.2.0-hf1166c9_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libuuid-2.38.1-hb4cce97_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libxcrypt-4.4.36-h31becfc_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libzlib-1.3.1-h86ecc28_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-hcccb83c_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-ha32ae93_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/openssl-3.4.0-hd08dc88_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/patchelf-0.17.2-h884eca8_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda @@ -138,19 +139,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311ha879c10_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311h58d527c_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/rattler-build-0.35.6-h33857bb_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/readline-8.2-h8fc344f_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/rpds-py-0.22.3-py311h7270cec_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/tk-8.6.13-h194ca79_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/yaml-0.2.5-hf897c2e_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -167,13 +169,13 @@ environments: - pypi: https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/19/71/39c7c0d87f8d4e6c020a393182060eaefeeae6c01dab6a84ec346f2567df/rich-13.9.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/22/32/d0fbc4383a6a213d315c39dda9107f81654d9941c43d6c687e61995ec388/rosdistro-1.0.1-py3-none-any.whl - - pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3c/d2/b79b7d695e2f21da020bd44c782490578f300dd44f0a4c57a92575758a76/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux2014_aarch64.whl - - pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + - pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e osx-64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/brotli-python-1.1.0-py311hd89902b_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/ca-certificates-2024.12.14-h8857fd0_0.conda @@ -185,21 +187,21 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-specifications-2024.10.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jupyter_core-5.7.2-pyh31011fe_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.6-hf95d169_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.7-hf95d169_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libexpat-2.6.4-h240833e_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libffi-3.4.2-h0d85af4_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/osx-64/liblzma-5.6.3-hd471939_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.47.2-hdb6dae5_0.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.48.0-hdb6dae5_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-hf036a51_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-h0622a9a_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/openssl-3.4.0-hc426f3f_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda @@ -210,19 +212,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311h3336109_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311ha3cf9ac_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/rattler-build-0.35.6-h625f1b7_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/readline-8.2-h9e318b2_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/rpds-py-0.22.3-py311h3b9c2be_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -239,13 +242,13 @@ environments: - pypi: https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/19/71/39c7c0d87f8d4e6c020a393182060eaefeeae6c01dab6a84ec346f2567df/rich-13.9.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/22/32/d0fbc4383a6a213d315c39dda9107f81654d9941c43d6c687e61995ec388/rosdistro-1.0.1-py3-none-any.whl - - pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/84/80203abff8ea4993a87d823a5f632e4d92831ef75d404c9fc78d0176d2b5/ruamel.yaml.clib-0.2.12.tar.gz - - pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + - pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e osx-arm64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/brotli-python-1.1.0-py311h3f08180_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ca-certificates-2024.12.14-hf0a4a13_0.conda @@ -257,21 +260,21 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-specifications-2024.10.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jupyter_core-5.7.2-pyh31011fe_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.6-ha82da77_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.7-ha82da77_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libexpat-2.6.4-h286801f_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libffi-3.4.2-h3422bc3_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/osx-arm64/liblzma-5.6.3-h39f12f2_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.47.2-h3f77e49_0.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.48.0-h3f77e49_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h7bae524_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/openssl-3.4.0-h81ee809_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda @@ -282,19 +285,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h460d6c5_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h4921393_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/rattler-build-0.35.6-h3ab7716_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/readline-8.2-h92ec313_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/rpds-py-0.22.3-py311h3ff9189_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -311,13 +315,13 @@ environments: - pypi: https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/19/71/39c7c0d87f8d4e6c020a393182060eaefeeae6c01dab6a84ec346f2567df/rich-13.9.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/22/32/d0fbc4383a6a213d315c39dda9107f81654d9941c43d6c687e61995ec388/rosdistro-1.0.1-py3-none-any.whl - - pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/fb/8f/683c6ad562f558cbc4f7c029abcd9599148c51c54b5ef0f24f2638da9fbb/ruamel.yaml.clib-0.2.12-cp311-cp311-macosx_13_0_arm64.whl - - pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + - pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e win-64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/brotli-python-1.1.0-py311hda3d55a_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - conda: https://repo.prefix.dev/conda-forge/win-64/ca-certificates-2024.12.14-h56e8100_0.conda @@ -331,8 +335,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/win-64/git-2.47.1-h57928b3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -341,7 +345,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/win-64/libexpat-2.6.4-he0c23c2_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/libffi-3.4.2-h8ffe710_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/win-64/liblzma-5.6.3-h2466b09_1.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.47.2-h67fdade_0.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.48.0-h67fdade_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/m2-conda-epoch-20230914-0_x86_64.conda - conda: https://repo.prefix.dev/conda-forge/noarch/m2-msys2-runtime-3.4.9.1-hd8ed1ab_4.conda @@ -358,23 +362,24 @@ environments: - conda: https://repo.prefix.dev/conda-forge/win-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/pywin32-307-py311hda3d55a_3.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/pyyaml-6.0.2-py311he736701_1.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/pyyaml-6.0.2-py311h5082efb_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/rattler-build-0.35.6-ha8cf89e_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/rpds-py-0.22.3-py311h533ab2d_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-ha32ba9b_23.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vc14_runtime-14.42.34433-he29a5d6_23.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hdffcdeb_23.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-h5fd82a7_24.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vc14_runtime-14.42.34433-h6356254_24.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hfef2bbc_24.conda - conda: https://repo.prefix.dev/conda-forge/noarch/win_inet_pton-1.1.0-pyh7428d3b_8.conda - conda: https://repo.prefix.dev/conda-forge/win-64/yaml-0.2.5-h8ffe710_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -391,10 +396,10 @@ environments: - pypi: https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/19/71/39c7c0d87f8d4e6c020a393182060eaefeeae6c01dab6a84ec346f2567df/rich-13.9.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/22/32/d0fbc4383a6a213d315c39dda9107f81654d9941c43d6c687e61995ec388/rosdistro-1.0.1-py3-none-any.whl - - pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/b4/4f/b52f634c9548a9291a70dfce26ca7ebce388235c93588a1068028ea23fcc/ruamel.yaml.clib-0.2.12-cp311-cp311-win_amd64.whl - - pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + - pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e default: channels: - url: https://repo.prefix.dev/conda-forge/ @@ -403,7 +408,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/brotli-python-1.1.0-py311hfdbb021_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/ca-certificates-2024.12.14-hbcca054_0.conda @@ -415,8 +420,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -430,14 +435,14 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-64/libgomp-14.2.0-h77fa898_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/liblzma-5.6.3-hb9d3cd8_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.47.2-hee588c1_0.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.48.0-hee588c1_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libstdcxx-14.2.0-hc0a3c3a_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-he02047a_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-h2d0b736_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/openssl-3.4.0-h7b32b05_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/patchelf-0.17.2-h58526e2_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda @@ -449,19 +454,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h9ecbd09_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h2dc5d0c_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/rattler-build-0.35.6-hff40e2b_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/readline-8.2-h8228510_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/rpds-py-0.22.3-py311h9e33e62_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -470,7 +476,7 @@ environments: linux-aarch64: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/brotli-python-1.1.0-py311h89d996e_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/bzip2-1.0.8-h68df207_7.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ca-certificates-2024.12.14-hcefe29a_0.conda @@ -482,8 +488,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -497,14 +503,14 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libgomp-14.2.0-he277a41_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/liblzma-5.6.3-h86ecc28_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libnsl-2.0.1-h31becfc_0.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.47.2-h5eb1b54_0.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.48.0-h5eb1b54_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libstdcxx-14.2.0-h3f4de04_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libstdcxx-ng-14.2.0-hf1166c9_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libuuid-2.38.1-hb4cce97_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libxcrypt-4.4.36-h31becfc_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libzlib-1.3.1-h86ecc28_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-hcccb83c_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-ha32ae93_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/openssl-3.4.0-hd08dc88_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/patchelf-0.17.2-h884eca8_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda @@ -516,19 +522,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311ha879c10_1.conda + - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311h58d527c_2.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/rattler-build-0.35.6-h33857bb_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/readline-8.2-h8fc344f_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/rpds-py-0.22.3-py311h7270cec_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/tk-8.6.13-h194ca79_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/yaml-0.2.5-hf897c2e_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -536,7 +543,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/zstd-1.5.6-h02f22dd_0.conda osx-64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/brotli-python-1.1.0-py311hd89902b_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/ca-certificates-2024.12.14-h8857fd0_0.conda @@ -548,21 +555,21 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-specifications-2024.10.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jupyter_core-5.7.2-pyh31011fe_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.6-hf95d169_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.7-hf95d169_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libexpat-2.6.4-h240833e_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libffi-3.4.2-h0d85af4_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/osx-64/liblzma-5.6.3-hd471939_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.47.2-hdb6dae5_0.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.48.0-hdb6dae5_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-hf036a51_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-h0622a9a_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/openssl-3.4.0-hc426f3f_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda @@ -573,19 +580,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311h3336109_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311ha3cf9ac_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/rattler-build-0.35.6-h625f1b7_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/readline-8.2-h9e318b2_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/rpds-py-0.22.3-py311h3b9c2be_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -593,7 +601,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/brotli-python-1.1.0-py311h3f08180_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ca-certificates-2024.12.14-hf0a4a13_0.conda @@ -605,21 +613,21 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/conda-package-streaming-0.11.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-specifications-2024.10.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jupyter_core-5.7.2-pyh31011fe_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.6-ha82da77_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.7-ha82da77_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libexpat-2.6.4-h286801f_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libffi-3.4.2-h3422bc3_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/osx-arm64/liblzma-5.6.3-h39f12f2_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.47.2-h3f77e49_0.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.48.0-h3f77e49_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/nbformat-5.10.4-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h7bae524_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/openssl-3.4.0-h81ee809_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pkgutil-resolve-name-1.3.10-pyhd8ed1ab_2.conda - conda: https://repo.prefix.dev/conda-forge/noarch/platformdirs-4.3.6-pyhd8ed1ab_1.conda @@ -630,19 +638,20 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/python-fastjsonschema-2.21.1-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h460d6c5_1.conda + - conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h4921393_2.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/rattler-build-0.35.6-h3ab7716_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/readline-8.2-h92ec313_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/rpds-py-0.22.3-py311h3ff9189_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -650,7 +659,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda win-64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.12.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/brotli-python-1.1.0-py311hda3d55a_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - conda: https://repo.prefix.dev/conda-forge/win-64/ca-certificates-2024.12.14-h56e8100_0.conda @@ -664,8 +673,8 @@ environments: - conda: https://repo.prefix.dev/conda-forge/noarch/defusedxml-0.7.1-pyhd8ed1ab_0.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/win-64/git-2.47.1-h57928b3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/h2-4.1.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/jsonschema-4.23.0-pyhd8ed1ab_1.conda @@ -674,7 +683,7 @@ environments: - conda: https://repo.prefix.dev/conda-forge/win-64/libexpat-2.6.4-he0c23c2_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/libffi-3.4.2-h8ffe710_5.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/win-64/liblzma-5.6.3-h2466b09_1.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.47.2-h67fdade_0.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.48.0-h67fdade_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/m2-conda-epoch-20230914-0_x86_64.conda - conda: https://repo.prefix.dev/conda-forge/noarch/m2-msys2-runtime-3.4.9.1-hd8ed1ab_4.conda @@ -691,23 +700,24 @@ environments: - conda: https://repo.prefix.dev/conda-forge/win-64/python_abi-3.11-5_cp311.conda - conda: https://repo.prefix.dev/conda-forge/noarch/pytz-2024.2-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/pywin32-307-py311hda3d55a_3.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/pyyaml-6.0.2-py311he736701_1.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/pyyaml-6.0.2-py311h5082efb_2.conda - conda: https://repo.prefix.dev/conda-forge/win-64/rattler-build-0.35.6-ha8cf89e_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/requests-toolbelt-1.0.0-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/win-64/rpds-py-0.22.3-py311h533ab2d_0.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/tqdm-4.67.1-pyhd8ed1ab_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + - conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://repo.prefix.dev/conda-forge/noarch/urllib3-2.3.0-pyhd8ed1ab_0.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-ha32ba9b_23.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vc14_runtime-14.42.34433-he29a5d6_23.conda - - conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hdffcdeb_23.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-h5fd82a7_24.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vc14_runtime-14.42.34433-h6356254_24.conda + - conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hfef2bbc_24.conda - conda: https://repo.prefix.dev/conda-forge/noarch/win_inet_pton-1.1.0-pyh7428d3b_8.conda - conda: https://repo.prefix.dev/conda-forge/win-64/yaml-0.2.5-h8ffe710_2.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -772,17 +782,17 @@ packages: - pkg:pypi/anaconda-client?source=hash-mapping size: 72548 timestamp: 1719693590229 -- conda: https://repo.prefix.dev/conda-forge/noarch/attrs-24.3.0-pyh71513ae_0.conda - sha256: 750186af694a7130eaf7119fbb56db0d2326d8995ad5b8eae23c622b85fea29a - md5: 356927ace43302bf6f5926e2a58dae6a +- conda: https://repo.prefix.dev/conda-forge/noarch/attrs-25.1.0-pyh71513ae_0.conda + sha256: 1f267886522dfb9ae4e5ebbc3135b5eb13cff27bdbfe8d881a4d893459166ab4 + md5: 2cc3f588512f04f3a0c64b4e9bedc02d depends: - python >=3.9 license: MIT license_family: MIT purls: - - pkg:pypi/attrs?source=hash-mapping - size: 56354 - timestamp: 1734348889193 + - pkg:pypi/attrs?source=compressed-mapping + size: 56370 + timestamp: 1737819298139 - conda: https://repo.prefix.dev/conda-forge/linux-64/brotli-python-1.1.0-py311hfdbb021_2.conda sha256: 949913bbd1f74d1af202d3e4bff2e0a4e792ec00271dc4dd08641d4221aa2e12 md5: d21daab070d76490cb39a8f1d1729d79 @@ -1167,28 +1177,28 @@ packages: - pkg:pypi/h2?source=hash-mapping size: 52000 timestamp: 1733298867359 -- conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.0.0-pyhd8ed1ab_1.conda - sha256: ec89b7e5b8aa2f0219f666084446e1fb7b54545861e9caa892acb24d125761b5 - md5: 2aa5ff7fa34a81b9196532c84c10d865 +- conda: https://repo.prefix.dev/conda-forge/noarch/hpack-4.1.0-pyhd8ed1ab_0.conda + sha256: 6ad78a180576c706aabeb5b4c8ceb97c0cb25f1e112d76495bff23e3779948ba + md5: 0a802cb9888dd14eeefc611f05c40b6e depends: - python >=3.9 license: MIT license_family: MIT purls: - pkg:pypi/hpack?source=hash-mapping - size: 29412 - timestamp: 1733299296857 -- conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.0.1-pyhd8ed1ab_1.conda - sha256: e91c6ef09d076e1d9a02819cd00fa7ee18ecf30cdd667605c853980216584d1b - md5: 566e75c90c1d0c8c459eb0ad9833dc7a + size: 30731 + timestamp: 1737618390337 +- conda: https://repo.prefix.dev/conda-forge/noarch/hyperframe-6.1.0-pyhd8ed1ab_0.conda + sha256: 77af6f5fe8b62ca07d09ac60127a30d9069fdc3c68d6b256754d0ffb1f7779f8 + md5: 8e6923fc12f1fe8f8c4e5c9f343256ac depends: - python >=3.9 license: MIT license_family: MIT purls: - pkg:pypi/hyperframe?source=hash-mapping - size: 17239 - timestamp: 1733298862681 + size: 17397 + timestamp: 1737618427549 - conda: https://repo.prefix.dev/conda-forge/noarch/idna-3.10-pyhd8ed1ab_1.conda sha256: d7a472c9fd479e2e8dcb83fb8d433fce971ea369d704ece380e876f9c3494e87 md5: 39a4f67be3286c86d696df570b1201b7 @@ -1295,26 +1305,26 @@ packages: purls: [] size: 698245 timestamp: 1729655345825 -- conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.6-hf95d169_1.conda - sha256: c40661648c34c08e21b69e0eec021ccaf090ffff070d2a9cbcb1519e1b310568 - md5: 1bad6c181a0799298aad42fc5a7e98b7 +- conda: https://repo.prefix.dev/conda-forge/osx-64/libcxx-19.1.7-hf95d169_0.conda + sha256: 6b2fa3fb1e8cd2000b0ed259e0c4e49cbef7b76890157fac3e494bc659a20330 + md5: 4b8f8dc448d814169dbc58fc7286057d depends: - __osx >=10.13 license: Apache-2.0 WITH LLVM-exception license_family: Apache purls: [] - size: 527370 - timestamp: 1734494305140 -- conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.6-ha82da77_1.conda - sha256: 2b2443404503cd862385fd2f2a2c73f9624686fd1e5a45050b4034cfc06904ec - md5: ce5252d8db110cdb4ae4173d0a63c7c5 + size: 527924 + timestamp: 1736877256721 +- conda: https://repo.prefix.dev/conda-forge/osx-arm64/libcxx-19.1.7-ha82da77_0.conda + sha256: 776092346da87a2a23502e14d91eb0c32699c4a1522b7331537bd1c3751dcff5 + md5: 5b3e1610ff8bd5443476b91d618f5b77 depends: - __osx >=11.0 license: Apache-2.0 WITH LLVM-exception license_family: Apache purls: [] - size: 520992 - timestamp: 1734494699681 + size: 523505 + timestamp: 1736877862502 - conda: https://repo.prefix.dev/conda-forge/linux-64/libexpat-2.6.4-h5888daf_0.conda sha256: 56541b98447b58e52d824bd59d6382d609e11de1f8adf20b23143e353d2b8d26 md5: db833e03127376d461e1e13e76f09b6c @@ -1496,6 +1506,8 @@ packages: depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 + constrains: + - xz ==5.6.3=*_1 license: 0BSD purls: [] size: 111132 @@ -1505,6 +1517,8 @@ packages: md5: eb08b903681f9f2432c320e8ed626723 depends: - libgcc >=13 + constrains: + - xz ==5.6.3=*_1 license: 0BSD purls: [] size: 124138 @@ -1514,6 +1528,8 @@ packages: md5: f9e9205fed9c664421c1c09f0b90ce6d depends: - __osx >=10.13 + constrains: + - xz ==5.6.3=*_1 license: 0BSD purls: [] size: 103745 @@ -1523,6 +1539,8 @@ packages: md5: b2553114a7f5e20ccd02378a77d836aa depends: - __osx >=11.0 + constrains: + - xz ==5.6.3=*_1 license: 0BSD purls: [] size: 99129 @@ -1534,6 +1552,8 @@ packages: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 + constrains: + - xz ==5.6.3=*_1 license: 0BSD purls: [] size: 104332 @@ -1558,58 +1578,58 @@ packages: purls: [] size: 34501 timestamp: 1697358973269 -- conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.47.2-hee588c1_0.conda - sha256: 48af21ebc2cbf358976f1e0f4a0ab9e91dfc83d0ef337cf3837c6f5bc22fb352 - md5: b58da17db24b6e08bcbf8fed2fb8c915 +- conda: https://repo.prefix.dev/conda-forge/linux-64/libsqlite-3.48.0-hee588c1_1.conda + sha256: 22853d289ef6ec8a5b20f1aa261895b06525439990d3b139f8bfd0b5c5e32a3a + md5: 3fa05c528d8a1e2a67bbf1e36f22d3bc depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libzlib >=1.3.1,<2.0a0 license: Unlicense purls: [] - size: 873551 - timestamp: 1733761824646 -- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.47.2-h5eb1b54_0.conda - sha256: 885a27fa84a5a73ed9779168c02b6c386e2fc7a53f0566b32a09ceca146b42b4 - md5: d4bf59f8783a4a66c0aec568f6de3ff4 + size: 878223 + timestamp: 1737564987837 +- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/libsqlite-3.48.0-h5eb1b54_1.conda + sha256: 81dd9bf66c7f1d9064e007e2c787133100c406e7ca2de61dba9fb7b87372f255 + md5: 4f3a61fe206f20b27c385ee608bcdfda depends: - libgcc >=13 - libzlib >=1.3.1,<2.0a0 license: Unlicense purls: [] - size: 1042182 - timestamp: 1733761913736 -- conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.47.2-hdb6dae5_0.conda - sha256: 4d5e188d921f93c97ce172fc8c4341e8171670ec98d76f9961f65f6306fcda77 - md5: 44d9799fda97eb34f6d88ac1e3eb0ea6 + size: 1044879 + timestamp: 1737565049785 +- conda: https://repo.prefix.dev/conda-forge/osx-64/libsqlite-3.48.0-hdb6dae5_1.conda + sha256: ccff3309ed7b1561d3bb00f1e4f36d9d1323af998013e3182a13bf0b5dcef4ec + md5: 6c4d367a4916ea169d614590bdf33b7c depends: - __osx >=10.13 - libzlib >=1.3.1,<2.0a0 license: Unlicense purls: [] - size: 923167 - timestamp: 1733761860127 -- conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.47.2-h3f77e49_0.conda - sha256: f192f3c8973de9ec4c214990715f13b781965247a5cedf9162e7f9e699cfc3c4 - md5: 122d6f29470f1a991e85608e77e56a8a + size: 926014 + timestamp: 1737565233282 +- conda: https://repo.prefix.dev/conda-forge/osx-arm64/libsqlite-3.48.0-h3f77e49_1.conda + sha256: 17c06940cc2a13fd6a17effabd6881b1477db38b2cd3ee2571092d293d3fdd75 + md5: 4c55169502ecddf8077973a987d08f08 depends: - __osx >=11.0 - libzlib >=1.3.1,<2.0a0 license: Unlicense purls: [] - size: 850553 - timestamp: 1733762057506 -- conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.47.2-h67fdade_0.conda - sha256: ecfc0182c3b2e63c870581be1fa0e4dbdfec70d2011cb4f5bde416ece26c41df - md5: ff00095330e0d35a16bd3bdbd1a2d3e7 + size: 852831 + timestamp: 1737564996616 +- conda: https://repo.prefix.dev/conda-forge/win-64/libsqlite-3.48.0-h67fdade_1.conda + sha256: eb889b9ea754d30268fa740f91e62fae6c30ca40f9769051dd42390d2470a7ff + md5: 5a7a8f7f68ce1bdb7b58219786436f30 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: Unlicense purls: [] - size: 891292 - timestamp: 1733762116902 + size: 897026 + timestamp: 1737565547561 - conda: https://repo.prefix.dev/conda-forge/linux-64/libstdcxx-14.2.0-hc0a3c3a_1.conda sha256: 4661af0eb9bdcbb5fb33e5d0023b001ad4be828fccdcc56500059d56f9869462 md5: 234a5554c53625688d51062645337328 @@ -1834,43 +1854,43 @@ packages: - pkg:pypi/nbformat?source=hash-mapping size: 100945 timestamp: 1733402844974 -- conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-he02047a_1.conda - sha256: 6a1d5d8634c1a07913f1c525db6455918cbc589d745fac46d9d6e30340c8731a - md5: 70caf8bb6cf39a0b6b7efc885f51c0fe +- conda: https://repo.prefix.dev/conda-forge/linux-64/ncurses-6.5-h2d0b736_2.conda + sha256: 17fe6afd8a00446010220d52256bd222b1e4fcb93bd587e7784b03219f3dc358 + md5: 04b34b9a40cdc48cfdab261ab176ff74 depends: - __glibc >=2.17,<3.0.a0 - - libgcc-ng >=12 + - libgcc >=13 license: X11 AND BSD-3-Clause purls: [] - size: 889086 - timestamp: 1724658547447 -- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-hcccb83c_1.conda - sha256: acad4cf1f57b12ee1e42995e6fac646fa06aa026529f05eb8c07eb0a84a47a84 - md5: 91d49c85cacd92caa40cf375ef72a25d + size: 894452 + timestamp: 1736683239706 +- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/ncurses-6.5-ha32ae93_2.conda + sha256: 9fd726174dde993c560dd6fa1a383e61d546d380e98e0b0348d22512e5d86e24 + md5: 779046fb585c71373e8a051be06c6011 depends: - - libgcc-ng >=12 + - libgcc >=13 license: X11 AND BSD-3-Clause purls: [] - size: 924472 - timestamp: 1724658573518 -- conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-hf036a51_1.conda - sha256: b0b3180039ef19502525a2abd5833c00f9624af830fd391f851934d57bffb9af - md5: e102bbf8a6ceeaf429deab8032fc8977 + size: 928402 + timestamp: 1736683192463 +- conda: https://repo.prefix.dev/conda-forge/osx-64/ncurses-6.5-h0622a9a_2.conda + sha256: 507456591054ff83a0179c6b3804dbf6ea7874ac07b68bdf6ab5f23f2065e067 + md5: 7eb0c4be5e4287a3d6bfef015669a545 depends: - __osx >=10.13 license: X11 AND BSD-3-Clause purls: [] - size: 822066 - timestamp: 1724658603042 -- conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h7bae524_1.conda - sha256: 27d0b9ff78ad46e1f3a6c96c479ab44beda5f96def88e2fe626e0a49429d8afc - md5: cb2b0ea909b97b3d70cd3921d1445e1a + size: 822835 + timestamp: 1736683439206 +- conda: https://repo.prefix.dev/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_2.conda + sha256: b45c73348ec9841d5c893acc2e97adff24127548fe8c786109d03c41ed564e91 + md5: f6f7c5b7d0983be186c46c4f6f8f9af8 depends: - __osx >=11.0 license: X11 AND BSD-3-Clause purls: [] - size: 802321 - timestamp: 1724658775723 + size: 796754 + timestamp: 1736683572099 - pypi: https://files.pythonhosted.org/packages/b9/54/dd730b32ea14ea797530a4479b2ed46a6fb250f682a9cfb997e968bf0261/networkx-3.4.2-py3-none-any.whl name: networkx version: 3.4.2 @@ -2286,9 +2306,9 @@ packages: - pkg:pypi/pywin32?source=hash-mapping size: 6023110 timestamp: 1728636767562 -- conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h9ecbd09_1.conda - sha256: e721e5ff389a7b2135917c04b27391be3d3382e261bb60a369b1620655365c3d - md5: abeb54d40f439b86f75ea57045ab8496 +- conda: https://repo.prefix.dev/conda-forge/linux-64/pyyaml-6.0.2-py311h2dc5d0c_2.conda + sha256: d107ad62ed5c62764fba9400f2c423d89adf917d687c7f2e56c3bfed605fb5b3 + md5: 014417753f948da1f70d132b2de573be depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -2299,11 +2319,11 @@ packages: license_family: MIT purls: - pkg:pypi/pyyaml?source=hash-mapping - size: 212644 - timestamp: 1725456264282 -- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311ha879c10_1.conda - sha256: c0f373c2944cf18da2cec19bae76284ef54cef44b3925c249d53821e4021d59a - md5: ad89d09994540880f297259742a8428a + size: 213136 + timestamp: 1737454846598 +- conda: https://repo.prefix.dev/conda-forge/linux-aarch64/pyyaml-6.0.2-py311h58d527c_2.conda + sha256: b7eb3696fae7e3ae66d523f422fc4757b1842b23f022ad5d0c94209f75c258b2 + md5: 01b93dc85ced3be09926e04498cbd260 depends: - libgcc >=13 - python >=3.11,<3.12.0a0 @@ -2314,11 +2334,11 @@ packages: license_family: MIT purls: - pkg:pypi/pyyaml?source=hash-mapping - size: 205817 - timestamp: 1725456351893 -- conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311h3336109_1.conda - sha256: d8f4513c53a7c0be9f1cdb9d1af31ac85cf8a6f0e4194715e36e915c03104662 - md5: b0132bec7165a53403dcc393ff761a9e + size: 206194 + timestamp: 1737454848998 +- conda: https://repo.prefix.dev/conda-forge/osx-64/pyyaml-6.0.2-py311ha3cf9ac_2.conda + sha256: 4855c51eedcde05f3d9666a0766050c7cbdff29b150d63c1adc4071637ba61d7 + md5: f49b0da3b1e172263f4f1e2f261a490d depends: - __osx >=10.13 - python >=3.11,<3.12.0a0 @@ -2328,11 +2348,11 @@ packages: license_family: MIT purls: - pkg:pypi/pyyaml?source=hash-mapping - size: 193941 - timestamp: 1725456465818 -- conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h460d6c5_1.conda - sha256: 9ae182eef4e96a7c2f46cc9add19496276612663e17429500432631dce31a831 - md5: d32590e7bd388f18b036c6fc402a0cb1 + size: 197287 + timestamp: 1737454852180 +- conda: https://repo.prefix.dev/conda-forge/osx-arm64/pyyaml-6.0.2-py311h4921393_2.conda + sha256: 2af6006c9f692742181f4aa2e0656eb112981ccb0b420b899d3dd42c881bd72f + md5: 250b2ee8777221153fd2de9c279a7efa depends: - __osx >=11.0 - python >=3.11,<3.12.0a0 @@ -2343,11 +2363,11 @@ packages: license_family: MIT purls: - pkg:pypi/pyyaml?source=hash-mapping - size: 192321 - timestamp: 1725456528007 -- conda: https://repo.prefix.dev/conda-forge/win-64/pyyaml-6.0.2-py311he736701_1.conda - sha256: 86608f1b4f6b1819a74b6b1344c34304745fd7e84bfc9900269f57cf28178d31 - md5: d0c5f3c595039890be0c9af47d23b9ba + size: 196951 + timestamp: 1737454935552 +- conda: https://repo.prefix.dev/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 @@ -2359,8 +2379,8 @@ packages: license_family: MIT purls: - pkg:pypi/pyyaml?source=hash-mapping - size: 187901 - timestamp: 1725456808581 + size: 187430 + timestamp: 1737454904007 - conda: https://repo.prefix.dev/conda-forge/linux-64/rattler-build-0.35.6-hff40e2b_0.conda sha256: 0c8c82fd3cf13e69f5c600767b7ba60db38c4cdea0cbad66fdb624ada52a7f27 md5: c926bc2b91cdb32687e9a9f5909a4aa9 @@ -2371,6 +2391,7 @@ packages: constrains: - __glibc >=2.17 license: BSD-3-Clause + license_family: BSD purls: [] size: 10747673 timestamp: 1737419180461 @@ -2383,6 +2404,7 @@ packages: constrains: - __glibc >=2.17 license: BSD-3-Clause + license_family: BSD purls: [] size: 11002462 timestamp: 1737419203421 @@ -2394,6 +2416,7 @@ packages: constrains: - __osx >=10.13 license: BSD-3-Clause + license_family: BSD purls: [] size: 9263112 timestamp: 1737419217243 @@ -2405,6 +2428,7 @@ packages: constrains: - __osx >=11.0 license: BSD-3-Clause + license_family: BSD purls: [] size: 8654822 timestamp: 1737419214645 @@ -2416,6 +2440,7 @@ packages: - vc14_runtime >=14.42.34433 - ucrt >=10.0.20348.0 license: BSD-3-Clause + license_family: BSD purls: [] size: 8615244 timestamp: 1737419207280 @@ -2461,19 +2486,21 @@ packages: purls: [] size: 250351 timestamp: 1679532511311 -- conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.35.1-pyhd8ed1ab_1.conda - sha256: f972eecb4dc8e06257af37642f92b0f2df04a7fe4c950f2e1045505e5e93985f - md5: 8c9083612c1bfe6878715ed5732605f8 +- conda: https://repo.prefix.dev/conda-forge/noarch/referencing-0.36.2-pyh29332c3_0.conda + sha256: e20909f474a6cece176dfc0dc1addac265deb5fa92ea90e975fbca48085b20c3 + md5: 9140f1c09dd5489549c6a33931b943c7 depends: - attrs >=22.2.0 - python >=3.9 - rpds-py >=0.7.0 + - typing_extensions >=4.4.0 + - python license: MIT license_family: MIT purls: - pkg:pypi/referencing?source=hash-mapping - size: 42201 - timestamp: 1733366868091 + size: 51668 + timestamp: 1737836872415 - conda: https://repo.prefix.dev/conda-forge/noarch/requests-2.32.3-pyhd8ed1ab_1.conda sha256: d701ca1136197aa121bbbe0e8c18db6b5c94acbd041c2b43c70e5ae104e1d8ad md5: a9b9368f3701a417eac9edbcae7cb737 @@ -2524,16 +2551,16 @@ packages: - rospkg - pytest ; extra == 'test' requires_python: '>=3.6' -- pypi: https://files.pythonhosted.org/packages/1c/e2/772f8cff8172a612823755035073b00753613c24af0ed6d3bae215021608/rospkg-1.5.1-py3-none-any.whl +- pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl name: rospkg - version: 1.5.1 - sha256: 1167a8f908d9c4379954732a605810e166ddcc18fcf47e6555395e1d6d972a7c + version: 1.6.0 + sha256: 491d49a0d85969cd99df056122f95fc33ff277992a4e275c4448c2e02220a9cb requires_dist: - catkin-pkg - pyyaml - distro>=1.4.0 ; python_full_version >= '3.8' - pytest ; extra == 'test' - - mock ; python_full_version < '3.3' and extra == 'test' + requires_python: '>=3.6' - conda: https://repo.prefix.dev/conda-forge/linux-64/rpds-py-0.22.3-py311h9e33e62_0.conda sha256: 0908ac4acb1a10fe63046e947a96c77cea0d392619ef965944da86c3574b68ec md5: b1f5799ae0cc22198928f09879da01f5 @@ -2646,17 +2673,17 @@ packages: version: 0.2.12 sha256: 4a6679521a58256a90b0d89e03992c15144c5f3858f40d7c18886023d7943db6 requires_python: '>=3.9' -- conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.7.0-pyhff2d567_0.conda - sha256: c653155d975cecf78156423d85e754e21ed8ec747e0afe8301afab50fa088b4f - md5: 764aced8c122bc0f3f1d01d401536b82 +- conda: https://repo.prefix.dev/conda-forge/noarch/setuptools-75.8.0-pyhff2d567_0.conda + sha256: e0778e4f276e9a81b51c56f51ec22a27b4d8fc955abc0be77ad09ca9bea06bb9 + md5: 8f28e299c11afdd79e0ec1e279dcdc52 depends: - python >=3.9 license: MIT license_family: MIT purls: - pkg:pypi/setuptools?source=hash-mapping - size: 774395 - timestamp: 1736450264351 + size: 775598 + timestamp: 1736512753595 - conda: https://repo.prefix.dev/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda sha256: 41db0180680cc67c3fa76544ffd48d6a5679d96f4b71d7498a759e94edc9a2db md5: a451d576819089b0d672f18768be0f65 @@ -2744,13 +2771,24 @@ packages: - pkg:pypi/traitlets?source=hash-mapping size: 110051 timestamp: 1733367480074 -- conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2024b-hc8b5060_0.conda - sha256: 4fde5c3008bf5d2db82f2b50204464314cc3c91c1d953652f7bd01d9e52aefdf - md5: 8ac3367aafb1cc0a068483c580af8015 +- conda: https://repo.prefix.dev/conda-forge/noarch/typing_extensions-4.12.2-pyha770c72_1.conda + sha256: 337be7af5af8b2817f115b3b68870208b30c31d3439bec07bfb2d8f4823e3568 + md5: d17f13df8b65464ca316cbc000a3cb64 + depends: + - python >=3.9 + license: PSF-2.0 + license_family: PSF + purls: + - pkg:pypi/typing-extensions?source=hash-mapping + size: 39637 + timestamp: 1733188758212 +- conda: https://repo.prefix.dev/conda-forge/noarch/tzdata-2025a-h78e105d_0.conda + sha256: c4b1ae8a2931fe9b274c44af29c5475a85b37693999f8c792dad0f8c6734b1de + md5: dbcace4706afdfb7eb891f7b37d07c04 license: LicenseRef-Public-Domain purls: [] - size: 122354 - timestamp: 1728047496079 + size: 122921 + timestamp: 1737119101255 - conda: https://repo.prefix.dev/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda sha256: db8dead3dd30fb1a032737554ce91e2819b43496a0db09927edf01c32b577450 md5: 6797b005cd0f439c4c5c9ac565783700 @@ -2775,31 +2813,31 @@ packages: - pkg:pypi/urllib3?source=hash-mapping size: 100102 timestamp: 1734859520452 -- conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-ha32ba9b_23.conda - sha256: 986ddaf8feec2904eac9535a7ddb7acda1a1dfb9482088fdb8129f1595181663 - md5: 7c10ec3158d1eb4ddff7007c9101adb0 +- conda: https://repo.prefix.dev/conda-forge/win-64/vc-14.3-h5fd82a7_24.conda + sha256: 7ce178cf139ccea5079f9c353b3d8415d1d49b0a2f774662c355d3f89163d7b4 + md5: 00cf3a61562bd53bd5ea99e6888793d0 depends: - - vc14_runtime >=14.38.33135 + - vc14_runtime >=14.40.33810 track_features: - vc14 license: BSD-3-Clause license_family: BSD purls: [] - size: 17479 - timestamp: 1731710827215 -- conda: https://repo.prefix.dev/conda-forge/win-64/vc14_runtime-14.42.34433-he29a5d6_23.conda - sha256: c483b090c4251a260aba6ff3e83a307bcfb5fb24ad7ced872ab5d02971bd3a49 - md5: 32b37d0cfa80da34548501cdc913a832 + size: 17693 + timestamp: 1737627189024 +- conda: https://repo.prefix.dev/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.42.34433.* *_23 + - vs2015_runtime 14.42.34433.* *_24 license: LicenseRef-MicrosoftVisualCpp2015-2022Runtime license_family: Proprietary purls: [] - size: 754247 - timestamp: 1731710681163 -- pypi: git+https://github.com/RoboStack/vinca.git@cbb8eba834ce3834df552977d6b08c325a30768e + size: 753531 + timestamp: 1737627061911 +- pypi: git+https://github.com/robostack/vinca?rev=cbb8eba834ce3834df552977d6b08c325a30768e#cbb8eba834ce3834df552977d6b08c325a30768e name: vinca version: 0.0.4 requires_dist: @@ -2811,16 +2849,16 @@ packages: - networkx>=2.5 - rich>=10 requires_python: '>=3.6' -- conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hdffcdeb_23.conda - sha256: 568ce8151eaae256f1cef752fc78651ad7a86ff05153cc7a4740b52ae6536118 - md5: 5c176975ca2b8366abad3c97b3cd1e83 +- conda: https://repo.prefix.dev/conda-forge/win-64/vs2015_runtime-14.42.34433-hfef2bbc_24.conda + sha256: 09102e0bd283af65772c052d85028410b0c31989b3cd96c260485d28e270836e + md5: 117fcc5b86c48f3b322b0722258c7259 depends: - vc14_runtime >=14.42.34433 license: BSD-3-Clause license_family: BSD purls: [] - size: 17572 - timestamp: 1731710685291 + size: 17669 + timestamp: 1737627066773 - conda: https://repo.prefix.dev/conda-forge/noarch/win_inet_pton-1.1.0-pyh7428d3b_8.conda sha256: 93807369ab91f230cf9e6e2a237eaa812492fe00face5b38068735858fba954f md5: 46e441ba871f524e2b067929da3051c2 diff --git a/pixi.toml b/pixi.toml index 6ce4ae16..f7264808 100644 --- a/pixi.toml +++ b/pixi.toml @@ -33,10 +33,10 @@ vinca = { git ="https://github.com/RoboStack/vinca.git", rev = "cbb8eba834ce3834 #vinca = { path = "../vinca", editable = true } [feature.beta.tasks] -generate-recipes = { cmd = "vinca -m", depends_on = ["rename-file"] } +generate-recipes = { cmd = "vinca -m", depends-on = ["rename-file"] } remove-file = { cmd = "rm vinca.yaml; rm -rf recipes" } build_additional_recipes = { cmd = "rattler-build build --recipe-dir ./additional_recipes -m ./conda_build_config.yaml --skip-existing" } -build = { cmd = "rattler-build build --recipe-dir ./recipes -m ./conda_build_config.yaml -c robostack-jazzy -c https://repo.prefix.dev/conda-forge --skip-existing", depends_on = ["build_additional_recipes", "generate-recipes"] } +build = { cmd = "rattler-build build --recipe-dir ./recipes -m ./conda_build_config.yaml -c robostack-jazzy -c https://repo.prefix.dev/conda-forge --skip-existing", depends-on = ["build_additional_recipes", "generate-recipes"] } build_one_package = { cmd = "cp ./patch/$PACKAGE.*patch ./recipes/$PACKAGE/patch/; rattler-build build --recipe ./recipes/$PACKAGE/recipe.yaml -m ./conda_build_config.yaml -c robostack-jazzy -c https://repo.prefix.dev/conda-forge", env = { PACKAGE = "ros-jazzy-ros-workspace" } } create_snapshot = { cmd = "vinca-snapshot -d jazzy -o rosdistro_snapshot.yaml" } @@ -44,16 +44,16 @@ create_snapshot = { cmd = "vinca-snapshot -d jazzy -o rosdistro_snapshot.yaml" } beta = ["beta"] [target.linux-64.tasks] -rename-file = { cmd = "ln -s vinca_linux_64.yaml vinca.yaml", depends_on = ["remove-file"] } +rename-file = { cmd = "ln -s vinca_linux_64.yaml vinca.yaml", depends-on = ["remove-file"] } [target.osx-64.tasks] -rename-file = { cmd = "ln -s vinca_osx.yaml vinca.yaml", depends_on = ["remove-file"] } +rename-file = { cmd = "ln -s vinca_osx.yaml vinca.yaml", depends-on = ["remove-file"] } [target.osx-arm64.tasks] -rename-file = { cmd = "ln -s vinca_osx_arm64.yaml vinca.yaml", depends_on = ["remove-file"] } +rename-file = { cmd = "ln -s vinca_osx_arm64.yaml vinca.yaml", depends-on = ["remove-file"] } [target.linux-aarch64.tasks] -rename-file = { cmd = "ln -s vinca_linux_aarch64.yaml vinca.yaml", depends_on = ["remove-file"] } +rename-file = { cmd = "ln -s vinca_linux_aarch64.yaml vinca.yaml", depends-on = ["remove-file"] } [target.win-64.tasks] -rename-file = { cmd = "cp vinca_win.yaml vinca.yaml", depends_on = ["remove-file"] } +rename-file = { cmd = "cp vinca_win.yaml vinca.yaml", depends-on = ["remove-file"] } diff --git a/pkg_additional_info.yaml b/pkg_additional_info.yaml index bc5aae9c..8dd8e5a5 100644 --- a/pkg_additional_info.yaml +++ b/pkg_additional_info.yaml @@ -4,3 +4,5 @@ ros_workspace: build_number: 3 rviz_common: build_number: 3 +tinyxml2_vendor: + build_number: 3 diff --git a/robostack.yaml b/robostack.yaml index c40fc3e8..b73a0be3 100644 --- a/robostack.yaml +++ b/robostack.yaml @@ -43,6 +43,8 @@ cartographer: robostack: [cartographer] ca-certificates: robostack: [ca-certificates] +cargo: + robostack: [rust] clang-format: robostack: [clang-format] clang-tidy: @@ -949,7 +951,10 @@ sdl-image: sdl2: robostack: [sdl2] socat: - robostack: [socat] + robostack: + linux: [socat] + osx: [socat] + win64: [] spacenavd: robostack: [libspnav] spdlog: diff --git a/tests/ros-jazzy-ur-client-library.yaml b/tests/ros-jazzy-ur-client-library.yaml new file mode 100644 index 00000000..94feedb7 --- /dev/null +++ b/tests/ros-jazzy-ur-client-library.yaml @@ -0,0 +1,8 @@ +tests: + - script: + - cmake-package-check ur_client_library --targets ur_client_library::urcl + requirements: + run: + - cmake-package-check + - ${{ compiler('c') }} + - ${{ compiler('cxx') }} diff --git a/vinca_linux_64.yaml b/vinca_linux_64.yaml index 16084216..c17dc6d0 100644 --- a/vinca_linux_64.yaml +++ b/vinca_linux_64.yaml @@ -48,6 +48,18 @@ packages_select_by_deps: - moveit - moveit-planners-chomp + - moveit-servo + - moveit-visual-tools + + - ros2_control + - ros2_controllers + - gz_ros2_control + - gz_ros2_control_demos + + - rviz_visual_tools + + - ur + - ur_simulation_gz - ros_gz - slam_toolbox @@ -62,5 +74,12 @@ packages_select_by_deps: - sbg_driver - gtsam + # requested in https://github.com/RoboStack/ros-humble/issues/249 + - twist_mux + + # requested in https://github.com/RoboStack/ros-humble/issues/252 + - rmw_zenoh_cpp + + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_linux_aarch64.yaml b/vinca_linux_aarch64.yaml index 16084216..91520513 100644 --- a/vinca_linux_aarch64.yaml +++ b/vinca_linux_aarch64.yaml @@ -48,6 +48,18 @@ packages_select_by_deps: - moveit - moveit-planners-chomp + - moveit-servo + - moveit-visual-tools + + - ros2_control + - ros2_controllers + - gz_ros2_control + - gz_ros2_control_demos + + - rviz_visual_tools + + - ur + - ur_simulation_gz - ros_gz - slam_toolbox @@ -62,5 +74,11 @@ packages_select_by_deps: - sbg_driver - gtsam + # requested in https://github.com/RoboStack/ros-humble/issues/249 + - twist_mux + + # requested in https://github.com/RoboStack/ros-humble/issues/252 + - rmw_zenoh_cpp + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_osx.yaml b/vinca_osx.yaml index f8b0bbf5..f2d5b245 100644 --- a/vinca_osx.yaml +++ b/vinca_osx.yaml @@ -58,6 +58,18 @@ packages_select_by_deps: - moveit - moveit-planners-chomp + - moveit-servo + - moveit-visual-tools + + - ros2_control + - ros2_controllers + - gz_ros2_control + - gz_ros2_control_demos + + - rviz_visual_tools + + - ur + - ur_simulation_gz - ros_gz - slam_toolbox @@ -72,5 +84,12 @@ packages_select_by_deps: - sbg_driver - gtsam + # requested in https://github.com/RoboStack/ros-humble/issues/249 + - twist_mux + + # requested in https://github.com/RoboStack/ros-humble/issues/252 + - rmw_zenoh_cpp + + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_osx_arm64.yaml b/vinca_osx_arm64.yaml index ffd0d8d6..0acecce2 100644 --- a/vinca_osx_arm64.yaml +++ b/vinca_osx_arm64.yaml @@ -58,6 +58,18 @@ packages_select_by_deps: - moveit - moveit-planners-chomp + - moveit-servo + - moveit-visual-tools + + - ros2_control + - ros2_controllers + - gz_ros2_control + - gz_ros2_control_demos + + - rviz_visual_tools + + - ur + - ur_simulation_gz - ros_gz - slam_toolbox @@ -72,5 +84,12 @@ packages_select_by_deps: - sbg_driver - gtsam + # requested in https://github.com/RoboStack/ros-humble/issues/249 + - twist_mux + + # requested in https://github.com/RoboStack/ros-humble/issues/252 + - rmw_zenoh_cpp + + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_win.yaml b/vinca_win.yaml index 131f4356..95d3fe49 100644 --- a/vinca_win.yaml +++ b/vinca_win.yaml @@ -56,6 +56,19 @@ packages_select_by_deps: - moveit - moveit-planners-chomp + - moveit-servo + - moveit-visual-tools + + - ros2_control + - ros2_controllers + - gz_ros2_control + - gz_ros2_control_demos + + - rviz_visual_tools + + # ur driver does not support Windows + - ur + - ur_simulation_gz - ros_gz - slam_toolbox @@ -73,6 +86,12 @@ packages_select_by_deps: # Commented out as in the next rebuild on Windows we will switch to use the conda-forge version #- gtsam + # requested in https://github.com/RoboStack/ros-humble/issues/249 + - twist_mux + + # requested in https://github.com/RoboStack/ros-humble/issues/252 + - rmw_zenoh_cpp + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml