diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 0000000..ba4b337 --- /dev/null +++ b/.gitattributes @@ -0,0 +1,3 @@ +# SCM syntax highlighting & preventing 3-way merges +pixi.lock merge=binary linguist-language=YAML linguist-generated=true -diff +uv.lock merge=binary linguist-language=TOML linguist-generated=true -diff diff --git a/.gitignore b/.gitignore index ebbd523..b98572e 100644 --- a/.gitignore +++ b/.gitignore @@ -5,9 +5,14 @@ build* *.egg-info compile_commands.json +# ros env +install +log + # vscode environments .vscode .envrc +.clangd .helix @@ -25,8 +30,8 @@ __pycache__ evalio_results *.pyi -*.png # final outputs +*.png figures -graphics \ No newline at end of file +graphics* diff --git a/README.md b/README.md index 80d3966..ca42547 100644 --- a/README.md +++ b/README.md @@ -55,6 +55,19 @@ Datasets can be commented out in the config file if they haven't been downloaded evalio stats evalio_results/25.10.03_full/ ``` +## ROS Support + +FORM has a simple ROS wrapper found in [ros/](ros/). Using it is as easy as cloning into your workspace, + +```sh +cd ~/ros2_ws/src +git clone https://github.com/rpl-cmu/form.git +cd .. +colcon build --packages-select form +``` + +More details (including setup using [pixi](https://pixi.prefix.dev/latest/) and [robostack](https://robostack.github.io/index.html) for the purists out there) can be found in the [ros README](ros/) + ## Roadmap - [ ] ROS Node - [ ] Merge wrapper into upstream evalio diff --git a/form/form.cpp b/form/form.cpp index eb399a5..d69f197 100644 --- a/form/form.cpp +++ b/form/form.cpp @@ -113,4 +113,14 @@ Estimator::register_scan(const std::vector &scan) noexcept { return keypoints; } +std::tuple, std::vector> +Estimator::current_map() const noexcept { + std::tuple, std::vector> map_points; + tuple::for_seq(std::make_index_sequence<2>{}, [&](auto I) { + std::get(map_points) = + std::get(m_keypoint_map).to_vector(m_constraints.get_values()); + }); + return map_points; +} + } // namespace form diff --git a/form/form.hpp b/form/form.hpp index 6433e9e..0e5cfc2 100644 --- a/form/form.hpp +++ b/form/form.hpp @@ -78,6 +78,10 @@ struct Estimator { /// @brief Get the current lidar estimate gtsam::Pose3 current_lidar_estimate() { return m_constraints.get_current_pose(); } + /// @brief Get the current map point clouds for visualization + std::tuple, std::vector> + current_map() const noexcept; + /// @brief Register a new scan and return the extracted features std::tuple, std::vector> register_scan(const std::vector &scan) noexcept; diff --git a/form/mapping/map.hpp b/form/mapping/map.hpp index 05ca681..321e54d 100644 --- a/form/mapping/map.hpp +++ b/form/mapping/map.hpp @@ -137,6 +137,10 @@ template class KeypointMap { VoxelMap to_voxel_map(const gtsam::Values &values, double voxel_width) const noexcept; + /// @brief Transform all keypoints to the global scan and insert them into a + /// vector + std::vector to_vector(const gtsam::Values &values) const noexcept; + /// @brief Insert matches into the map, adding only those that are sufficiently /// far from existing points based on min_dist_map void insert_matches(const tbb::concurrent_vector> &matches); diff --git a/form/mapping/map.tpp b/form/mapping/map.tpp index fba02d9..e5619d4 100644 --- a/form/mapping/map.tpp +++ b/form/mapping/map.tpp @@ -22,6 +22,7 @@ #pragma once #include "form/mapping/map.hpp" +#include #include namespace form { @@ -145,6 +146,30 @@ VoxelMap KeypointMap::to_voxel_map(const gtsam::Values &values, return world_map; } +template +std::vector +KeypointMap::to_vector(const gtsam::Values &values) const noexcept { + // Create a new map + std::vector world_map; + auto num_points = std::accumulate( + m_scan_keypoints.begin(), m_scan_keypoints.end(), size_t{0}, + [](size_t sum, const auto &pair) { return sum + pair.second.size(); }); + world_map.reserve(num_points); + + // Iterate over all the keypoints in the map + for (const auto &[scan_index, keypoints] : m_scan_keypoints) { + // Get the pose of the scan + const auto &world_T_scan = values.at(X(scan_index)); + + // Transform each keypoint into the world scan and add it to the map + for (const auto &keypoint : keypoints) { + world_map.push_back(keypoint.transform(world_T_scan)); + } + } + + return world_map; +} + template void KeypointMap::insert_matches( const tbb::concurrent_vector> &matches) { @@ -155,10 +180,10 @@ void KeypointMap::insert_matches( const ScanIndex scan_j = matches.front().query.scan; auto &keypoints = get(scan_j); - double max_dist_map_sqrd = m_params.min_dist_map * m_params.min_dist_map; + double min_dist_map_sqrd = m_params.min_dist_map * m_params.min_dist_map; for (const auto &match : matches) { - if (match.dist_sqrd > max_dist_map_sqrd) { + if (match.dist_sqrd > min_dist_map_sqrd) { keypoints.push_back(match.query); } } diff --git a/python/bindings.cpp b/python/bindings.cpp index ddea939..26727ea 100644 --- a/python/bindings.cpp +++ b/python/bindings.cpp @@ -82,7 +82,7 @@ class FORM : public evalio::Pipeline { (int, max_num_recent_scans, 10, params_.scans.max_num_recent_scans), (int, max_steps_unused_keyscan, 10, params_.scans.max_steps_unused_keyscan), (double, keyscan_match_ratio, 0.1, params_.scans.keyscan_match_ratio), - (double, max_dist_map, 0.1, params_.map.min_dist_map), + (double, min_dist_map, 0.1, params_.map.min_dist_map), // misc (int, num_threads, 0, params_.num_threads) ); diff --git a/ros/CMakeLists.txt b/ros/CMakeLists.txt new file mode 100644 index 0000000..a8171df --- /dev/null +++ b/ros/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.16...3.26) +project(form VERSION 0.1.0 LANGUAGES CXX) + +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +# Build the core FORM library from the parent directory +# Need PIC since FORM (static) gets linked into a shared library (form_odometry_node) +set(CMAKE_POSITION_INDEPENDENT_CODE ON) +add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/.. ${CMAKE_CURRENT_BINARY_DIR}/form_core) + +find_package(ament_cmake REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(rcutils REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(std_msgs REQUIRED) +find_package(tf2_ros REQUIRED) + +# ROS 2 node +add_library(form_odometry_node SHARED src/node.cpp) +target_compile_features(form_odometry_node PUBLIC cxx_std_17) +target_include_directories(form_odometry_node PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) +target_link_libraries(form_odometry_node FORM) +ament_target_dependencies( + form_odometry_node + geometry_msgs + nav_msgs + rclcpp + rclcpp_components + rcutils + sensor_msgs + std_msgs + tf2_ros) + +rclcpp_components_register_node(form_odometry_node PLUGIN "form_ros::EstimatorNode" EXECUTABLE form_node) + +install(TARGETS form_odometry_node LIBRARY DESTINATION lib RUNTIME DESTINATION lib/${PROJECT_NAME}) +install(DIRECTORY launch rviz DESTINATION share/${PROJECT_NAME}/) + +ament_package() \ No newline at end of file diff --git a/ros/LICENSE b/ros/LICENSE new file mode 100644 index 0000000..2ac8271 --- /dev/null +++ b/ros/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2025 Easton Potokar, Taylor Pool, and Michael Kaess + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/ros/README.md b/ros/README.md new file mode 100644 index 0000000..2980e53 --- /dev/null +++ b/ros/README.md @@ -0,0 +1,93 @@ +# FORM ROS 2 Wrapper + +This ROS 2 node is based on the [KISS-ICP](https://github.com/PRBonn/kiss-icp) ROS 2 wrapper. +Thanks to the KISS-ICP developers for their clean and well-structured ROS node implementation. + +### Building + +You will need the same dependencies as FORM (most of which are available as ROS packages), +- [eigen3](https://libeigen.gitlab.io/eigen/docs-nightly/) +- [gtsam](https://github.com/borglab/gtsam/) +- [tbb](https://github.com/uxlfoundation/oneTBB) +- [tsl::robin_map](https://github.com/Tessil/robin-map) (will be pulled from source if not found) + +Once those are installed, simply clone FORM to your workspace and build, + +```sh +git clone https://github.com/contagon/form +colcon build +source ./install/setup.bash +``` + +### Running + +The main launch file is `odometry.launch.py` which will launch the odometry node. FORM has three required inputs, **topic name**, **number of scanlines/rings/columns**, and **number of rows/circular count**. This last two are required for FORM's feature extraction. + +To view all the available arguments, you can run: + +```sh +ros2 launch form odometry.launch.py --show-args +``` +which will output the following: + +| Parameter | Default | Description | +|--------------------|--------------|--------------------------------------| +| `topic` | `None` | Input point cloud topic | +| `num_columns` | `None` | LiDAR image width (columns) | +| `num_rows` | `None` | LiDAR image height (rows) | +| `min_range` | `1.0` | Minimum LiDAR range | +| `max_range` | `100.0` | Maximum LiDAR range | +| `visualize` | `true` | Launch RViz and publish point clouds | +| `bagfile` | `''` | Optional rosbag file/folder to play | +| `base_frame` | `''` | Base frame id | +| `lidar_odom_frame` | `odom_lidar` | Odometry frame id | +| `publish_odom_tf` | `True` | Publish odom->base TF | +| `invert_odom_tf` | `True` | Invert published odom TF | +| `use_sim_time` | `True` | Use simulation time | + +If a bagfile is provided, the node will play the bagfile and process the point clouds. If not, it will just subscribe to the topic and process incoming point clouds in real-time. + +Thus as an example + +```sh +ros2 launch form odometry.launch.py bagfile:= topic:= num_columns:= num_rows:= +``` + +### Pointcloud Format + +FORM requires point clouds to be in row-major order with no dropped points for its feature extraction method. It does it's best to infer the ordering and density of the point cloud using the following heuristics, + +| Format | Heuristic to Infer | +|----------------|----------------------------------------------------------| +| all points | Point cloud size equaling `num_columns` * `num_rows` | +| dropped points | Point cloud size not equaling `num_columns` * `num_rows` | +| row-major | Stationary ring number for first few points | +| column-major | Increasing ring number for first few points | + +IMPORTANT: If you're point cloud *does not* is not in row or column major format, FORM will crash! Please open an issue and we can add a flag to handle you're appropriate cloud formatting. (For example, I've seen some velodyne point clouds have ring order returned as 0, 8, 1, 9, 2, 10, ... This will break things) + +NOTE: If your point cloud is row major and has dropped invalid points, there is usually no way to figure out where along the scan line the dropped points belong. FORM places all of them at the end. This may have an impact on feature extraction, but things generally *should* still work. + + +### Development + +We're not huge fans of installing ROS2 system wide, so this folder is setup to install all dependencies using [pixi](https://pixi.prefix.dev/latest/) and [robostack](https://robostack.github.io/index.html). + +Install pixi, then building is all done in a single command from the `ros/` directory +```sh +pixi run build +source install/setup.sh +``` + +If you need to utilize ROS2 commands, you can do either of the following, +```sh +pixi run ros2 +# enter into a pixi shell +pixi shell +ros2 +``` + +If you have the oxford spires dataset installed using [evalio](https://github.com/contagon/evalio/tree/master), you can use the following commands to launch and run a trajectory from it, +```sh +pixi run oxford +``` \ No newline at end of file diff --git a/ros/launch/odometry.launch.py b/ros/launch/odometry.launch.py new file mode 100644 index 0000000..8c2500a --- /dev/null +++ b/ros/launch/odometry.launch.py @@ -0,0 +1,173 @@ +# MIT License +# +# Copyright (c) 2025 Easton Potokar, Taylor Pool, and Michael Kaess +# +# Adapted from KISS-ICP launch file +# (Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill Stachniss) +from typing import Any +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import ( + LaunchConfiguration, + PathJoinSubstitution, + PythonExpression, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +class config: + # Feature extraction + neighbor_points: int = 5 + num_sectors: int = 6 + planar_threshold: float = 1.0 + planar_feats_per_sector: int = 50 + point_feats_per_sector: int = 3 + radius: float = 1.0 + min_points: int = 5 + + # Optimization + max_dist_matching: float = 0.8 + new_pose_threshold: float = 0.0001 + max_num_rematches: int = 30 + disable_smoothing: bool = False + + # Mapping + max_num_keyscans: int = 50 + max_num_recent_scans: int = 10 + max_steps_unused_keyscan: int = 10 + keyscan_match_ratio: float = 0.1 + min_dist_map: float = 0.1 + + # Misc + num_threads: int = 0 + + # Covariance diagonal values + position_covariance: float = 0.1 + orientation_covariance: float = 0.1 + + +def make_config( + launch_args: "list[DeclareLaunchArgument]", + name: str, + description: str, + default: Any | None = None, +): + launch_args.append( + DeclareLaunchArgument( + name=name, + default_value=None if default is None else str(default), + description=description, + ) + ) + return LaunchConfiguration(name, default=default) + + +def generate_launch_description(): + la = [] + # fmt: off + topic = make_config(la, "topic", "Input point cloud topic") + # lidar geometry config + num_columns = make_config(la, "num_columns", "LiDAR image width (columns)") + num_rows = make_config(la, "num_rows", "LiDAR image height (rows)") + min_range = make_config(la, "min_range", "Minimum LiDAR range", 1.0) + max_range = make_config(la, "max_range", "Maximum LiDAR range", 100.0) + # optional visualization and rosbag play + visualize = make_config(la, "visualize", "Launch RViz and debug visualization", True) + bagfile = make_config(la, "bagfile", "Optional rosbag file/folder to play", "") + # tf tree configuration + base_frame = make_config(la, "base_frame", "Base frame id", "") + lidar_odom_frame = make_config(la, "lidar_odom_frame", "Odometry frame id", "odom_lidar") + publish_odom_tf = make_config(la, "publish_odom_tf", "Publish odom->base TF", True) + invert_odom_tf = make_config(la, "invert_odom_tf", "Invert published odom TF", True) + use_sim_time = make_config(la, "use_sim_time", "Use simulation time", True) + # fmt: on + + # FORM node + form_node = Node( + package="form", + executable="form_node", + name="form_node", + output="screen", + remappings=[ + ("pointcloud_topic", topic), + ], + parameters=[ + { + # ROS node configuration + "base_frame": base_frame, + "lidar_odom_frame": lidar_odom_frame, + "publish_odom_tf": publish_odom_tf, + "invert_odom_tf": invert_odom_tf, + # LiDAR geometry + "num_columns": num_columns, + "num_rows": num_rows, + "min_range": min_range, + "max_range": max_range, + # Feature extraction + "neighbor_points": config.neighbor_points, + "num_sectors": config.num_sectors, + "planar_threshold": config.planar_threshold, + "planar_feats_per_sector": config.planar_feats_per_sector, + "point_feats_per_sector": config.point_feats_per_sector, + "radius": config.radius, + "min_points": config.min_points, + # Optimization + "max_dist_matching": config.max_dist_matching, + "new_pose_threshold": config.new_pose_threshold, + "max_num_rematches": config.max_num_rematches, + "disable_smoothing": config.disable_smoothing, + # Mapping + "max_num_keyscans": config.max_num_keyscans, + "max_num_recent_scans": config.max_num_recent_scans, + "max_steps_unused_keyscan": config.max_steps_unused_keyscan, + "keyscan_match_ratio": config.keyscan_match_ratio, + "min_dist_map": config.min_dist_map, + # Misc + "num_threads": config.num_threads, + # Fixed covariances + "position_covariance": config.position_covariance, + "orientation_covariance": config.orientation_covariance, + # ROS CLI arguments + "publish_debug_clouds": visualize, + "use_sim_time": use_sim_time, + }, + ], + ) + rviz_node = Node( + package="rviz2", + executable="rviz2", + output="screen", + arguments=[ + "-d", + PathJoinSubstitution([FindPackageShare("form"), "rviz", "form.rviz"]), + ], + condition=IfCondition(visualize), + ) + + bagfile_play = ExecuteProcess( + cmd=[ + "ros2", + "bag", + "play", + "--rate", + "1", + bagfile, + "--clock", + "1000.0", + "--read-ahead-queue-size", + "10000", + ], + output="screen", + condition=IfCondition(PythonExpression(["'", bagfile, "' != ''"])), + ) + + return LaunchDescription( + [ + *la, + form_node, + rviz_node, + bagfile_play, + ] + ) diff --git a/ros/package.xml b/ros/package.xml new file mode 100644 index 0000000..089151a --- /dev/null +++ b/ros/package.xml @@ -0,0 +1,30 @@ + + + form + 0.1.0 + FORM: Fixed-lag Odometry with Reparative Mapping - ROS 2 Wrapper + Easton Potokar + MIT + + ament_cmake + + geometry_msgs + nav_msgs + rclcpp + rclcpp_components + rcutils + sensor_msgs + std_msgs + tf2_ros + + eigen + gtsam + tbb + robin-map-dev + + ros2launch + + + ament_cmake + + diff --git a/ros/pixi.lock b/ros/pixi.lock new file mode 100644 index 0000000..93c03a2 --- /dev/null +++ b/ros/pixi.lock @@ -0,0 +1,9762 @@ +version: 6 +environments: + default: + channels: + - url: https://conda.anaconda.org/robostack-jazzy/ + - url: https://conda.anaconda.org/conda-forge/ + options: + pypi-prerelease-mode: if-necessary-or-explicit + packages: + linux-64: + - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-20_gnu.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/adwaita-icon-theme-49.0-unix_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.15.3-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/argcomplete-3.6.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-hecf2907_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/at-spi2-atk-2.38.0-h0630a04_3.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/at-spi2-core-2.40.3-h0630a04_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/atk-1.0-2.38.0-h04ea711_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/attr-2.5.2-h39aace5_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.45.1-default_h4852527_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.45.1-default_hfdba357_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.45.1-default_h4852527_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/bullet-3.25-h26dfbe5_5.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/bullet-cpp-3.25-hcbe3ca9_5.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-hda65f42_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.6-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.11.0-h4d9bdce_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2026.1.4-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-he90730b_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/catkin_pkg-1.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cffi-2.0.0-py312h460c074_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-22-22.1.0-default_h99862b1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-22.1.0-default_cfg_hcbb2b3e_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-format-22-22.1.0-default_h99862b1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-format-22.1.0-default_h99862b1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-tools-22.1.0-default_h99862b1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang_impl_linux-64-22.1.0-default_h0a60c25_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cli11-2.6.2-h54a6638_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.2.3-hc85cc9f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-argcomplete-0.3.3-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-bash-0.5.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-cd-0.1.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-cmake-0.2.29-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/colcon-common-extensions-0.3.0-py312h7900ff3_4.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-core-0.20.1-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-defaults-0.2.9-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-devtools-0.3.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-library-path-0.2.1-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-metadata-0.2.5-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-output-0.2.13-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-package-information-0.4.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-package-selection-0.2.10-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-parallel-executor-0.4.0-pyhe01879c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-pkg-config-0.1.0-py_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-powershell-0.5.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-python-setup-py-0.2.9-pyhff2d567_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-recursive-crawl-0.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-ros-0.5.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-test-result-0.3.8-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colcon-zsh-0.5.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/coloredlogs-15.0.1-pyhd8ed1ab_4.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/compiler-rt-22.1.0-ha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/compiler-rt22-22.1.0-hb700be7_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt22_linux-64-22.1.0-hffcefe0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_linux-64-22.1.0-ha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/compilers-1.11.0-ha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/conda-gcc-specs-14.3.0-he8ccf15_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/coverage-7.13.4-py312h8a5da7c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cppcheck-2.18.3-py312h014360a_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cryptography-46.0.5-py312ha4b625e_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.11.0-hfcd1e18_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.28-hd9c7081_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.16.2-h24cb091_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.4.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/distro-1.9.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/docutils-0.22.4-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h171cf75_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/empy-3.3.4-pyh9f0ad1d_1.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/epoxy-1.5.10-hb03c661_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.3.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-7.3.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-builtins-3.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-comprehensions-3.17.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-docstrings-1.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-import-order-0.19.2-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/flake8-quotes-3.4.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-12.1.0-hff5e90c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-ubuntu-0.83-h77eed37_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-hc364b38_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/foonathan-memory-0.7.3-h5888daf_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fortran-compiler-1.11.0-h9bea470_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freeglut-3.2.2-ha6d2627_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freeimage-3.18.0-h49ef1fa_24.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.14.1-ha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fribidi-1.0.16-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-14.3.0-h0dff253_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-14.3.0-hb1e0a52_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-14.3.0-h298d278_21.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gdk-pixbuf-2.44.5-h2b0a6b4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/geographiclib-cpp-2.5.2-hb700be7_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gettext-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gettext-tools-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran-14.3.0-h76987e4_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran_impl_linux-64-14.3.0-h1a219da_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran_linux-64-14.3.0-hfa02b96_21.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/glew-2.3.0-h71661d4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/glib-2.86.3-h5192d8d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/glib-tools-2.86.3-hf516916_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.17.0-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.14-hecca717_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/graphviz-14.1.2-h8b86629_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gst-plugins-base-1.26.10-h0363672_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gstreamer-1.26.10-h17cb667_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.17.0-h84d6215_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gtk3-3.24.43-h993cebd_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gts-0.7.6-h977cf35_4.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gtsam-4.2.0-py312h7f00892_14.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-14.3.0-h76987e4_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-14.3.0-h2185e75_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-14.3.0-he467f4b_21.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gz-cmake3-3.5.5-h05f81b2_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gz-math7-7.5.2-h5bbc156_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gz-math7-python-7.5.2-py312h89d136e_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gz-utils2-2.2.1-hdaf9e28_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-12.3.2-h6083320_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/hicolor-icon-theme-0.17-ha770c72_2.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/humanfriendly-10.0-pyh707e725_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-78.2-h33c6efd_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/imath-3.2.2-hde8ca8f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-metadata-8.7.0-pyhe01879c_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/iniconfig-2.3.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/jasper-4.2.9-he3c4edf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/jxrlib-1.1-hd590300_3.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-4.18.0-he073ed8_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/keyutils-1.6.3-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lame-3.100-h166bdaf_1003.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/noarch/lark-parser-0.12.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.18-h0c24ade_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.45.1-default_hbd61a6d_101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libacl-2.3.2-h0f662aa_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libamd-3.3.3-h456b2da_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libasprintf-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libasprintf-devel-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.11.0-5_h4a7cf45_openblas.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.88.0-hd24cca6_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.88.0-hfcd1e18_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-headers-1.88.0-ha770c72_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-python-1.88.0-py312hf890105_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-python-devel-1.88.0-py312h26dfbe5_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libbtf-2.3.2-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcamd-3.3.3-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcap-2.77-h3ff7636_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.11.0-5_h0358290_openblas.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libccolamd-3.3.4-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcholmod-5.3.1-h9cf07ce_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp21.1-21.1.8-default_h99862b1_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp22.1-22.1.0-default_h99862b1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-22.1.0-default_h746c552_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcolamd-3.3.4-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcompiler-rt-22.1.0-hb700be7_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-hb8b1518_5.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.18.0-h4e3cde8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcxsparse-4.4.1-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.25-h17f619e_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.125-hb03c661_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-devel-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libevent-2.1.12-hf998b51_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.3-hecca717_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.5.2-h3435931_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libflac-1.5.0-he200343_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.14.1-ha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.14.1-h73754d4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-15.2.0-he0feb66_17.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-14.3.0-hf649bbc_117.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-15.2.0-h69a702a_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgd-2.3.3-h5fbf134_12.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgettextpo-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgettextpo-devel-0.25.1-h3f43e3d_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-15.2.0-h69a702a_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-15.2.0-h68bc16d_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-devel-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.86.3-h6548e54_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglu-9.0.3-h5888daf_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-devel-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-15.2.0-he0feb66_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-cmake3-3.5.5-h54a6638_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-cmake4-4.2.0-h54a6638_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-math7-7.5.2-h54a6638_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-utils2-2.2.1-h54a6638_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libhwloc-2.12.2-default_hafda6a7_1000.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h3b78370_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.2-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libklu-2.3.5-h95ff59c_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.11.0-5_h47877c9_openblas.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libldl-3.3.2-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm21-21.1.8-hf7376ad_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm22-22.1.0-hf7376ad_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.2-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.67.0-had1ee68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hb9d3cd8_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libogg-1.3.5-hd0c01bc_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libopenblas-0.3.30-pthreads_h94d23a6_4.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-devel-1.7.0-ha4b6fd6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libopus-1.6.1-h280c20c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libparu-1.0.0-hc6afc67_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.55-h421ea60_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-18.2-hb80d175_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libraw-0.21.5-h074291d_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/librbio-4.3.4-hf02c80a_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/librsvg-2.60.0-h61e6d4b_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-14.3.0-h8f1669f_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsndfile-1.2.2-hc7d488a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspex-3.2.3-h9226d62_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspqr-4.3.4-h23b7119_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.51.2-hf4e2dac_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-15.2.0-h934c35e_17.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-14.3.0-h9f08a49_117.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-15.2.0-hdf11a46_17.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsuitesparseconfig-7.10.1-h901830b_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsystemd0-257.10-hd0affe5_4.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.1-h9d88235_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libumfpack-6.3.5-h873dde6_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liburcu-0.14.0-hac33072_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.41.3-h5347b49_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.51.0-hb03c661_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libvorbis-1.3.7-h54a6638_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.6.0-hd42ef1d_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.13.1-hca5e8e5_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-16-2.15.1-hca6bf5a_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.15.1-he237659_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.43-h711ed8c_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/llvm-openmp-22.1.0-h4922eb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lttng-ust-2.13.9-hf5eda4c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lxml-6.0.2-py312h63ddcf0_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-4.4.5-py312h3d67a73_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.10.0-h5888daf_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/mccabe-0.7.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mpg123-1.32.9-hc50e24c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.13.2-h171cf75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/nspr-4.38-h29cc59b_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/nss-3.118-h445c969_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.4.2-py312h33ff503_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openexr-3.4.6-h40f6f1d_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.4-h55fea9a_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openjph-0.26.3-h8d634f6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.10-he970967_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.6.1-h35e630c_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/orocos-kdl-1.5.3-hecca717_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-26.0-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pango-1.56.4-hadf4263_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre-8.45-h9c3ff4c_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.47-haa7fec5_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.4-h54a6638_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pluggy-1.6.0-pyhf9edf01_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/psutil-7.2.2-py312h5253ce2_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pugixml-1.15-h3f63f65_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pulseaudio-client-17.0-h9a6aba3_3.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-3.0.1-pyh7a1b43c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-11-hc364b38_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-global-3.0.1-pyhc7ab6ef_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pybullet-3.25-py312hf49885f_5.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pycodestyle-2.14.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pydocstyle-6.3.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyflakes-3.4.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.2-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.3.2-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytest-9.0.2-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytest-cov-7.0.0-pyhcf101f3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytest-repeat-0.9.4-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytest-rerunfailures-16.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.12-hd63d673_2_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhe01879c_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-orocos-kdl-1.5.3-py312h1289d80_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-8_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.3-py312h8a5da7c_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt-main-5.15.15-hc240232_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.3-h853b02a_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.6-hb9d3cd8_1.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-action-msgs-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-actionlib-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-auto-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-copyright-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-core-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-cppcheck-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-cpplint-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-definitions-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-dependencies-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-include-directories-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-interfaces-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-libraries-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-link-flags-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-targets-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-flake8-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gen-version-h-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gmock-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gtest-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-include-directories-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-libraries-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-lint-cmake-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-pep257-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-pytest-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-python-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-ros-0.12.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-target-dependencies-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-test-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-uncrustify-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-version-2.5.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-xmllint-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-copyright-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cppcheck-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cpplint-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-flake8-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-index-cpp-1.8.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-index-python-1.8.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-auto-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-cmake-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-common-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-package-0.16.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-pep257-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-uncrustify-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-xmllint-0.17.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-builtin-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-class-loader-2.7.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-common-interfaces-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-composition-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-console-bridge-vendor-1.7.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-cyclonedds-0.10.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-diagnostic-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-domain-coordinator-0.12.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-eigen3-cmake-module-0.3.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastcdr-2.2.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastrtps-2.14.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastrtps-cmake-module-3.6.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-foonathan-memory-vendor-1.3.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-geometry-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-geometry2-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gmock-vendor-1.14.9000-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gtest-vendor-1.14.9000-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gtsam-4.2.0-py312hfb442f0_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-cmake-vendor-0.0.10-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-math-vendor-0.0.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-utils-vendor-0.0.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-binding-c-2.0.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-hoofs-2.0.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-posh-2.0.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-image-transport-5.1.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-interactive-markers-2.5.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-kdl-parser-2.11.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-keyboard-handler-0.3.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-laser-geometry-2.7.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-3.4.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-ros-0.26.10-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-3.4.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-ament-cmake-3.4.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-ros-0.26.10-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-xml-3.4.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-yaml-3.4.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libcurl-vendor-3.4.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-liblz4-vendor-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libstatistics-collector-1.7.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libyaml-vendor-1.6.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-lifecycle-msgs-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-map-msgs-2.4.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-mcap-vendor-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-message-filters-4.11.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-nav-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-orocos-kdl-vendor-0.5.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-osrf-pycommon-2.1.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-pluginlib-5.4.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-point-cloud-transport-4.0.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-pybind11-vendor-3.1.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-python-cmake-module-0.11.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-python-orocos-kdl-vendor-0.5.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-9.2.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-action-9.2.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-lifecycle-9.2.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-logging-interface-3.1.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-logging-spdlog-3.1.1-np2py312h918b84f_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-yaml-param-parser-9.2.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-28.1.15-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-action-28.1.15-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-components-28.1.15-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-lifecycle-28.1.15-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclpy-7.1.8-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcpputils-2.11.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcutils-6.7.5-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-resource-retriever-3.4.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-7.3.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-connextdds-0.22.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-connextdds-common-0.22.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-cyclonedds-cpp-2.2.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-dds-common-3.1.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-cpp-8.4.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-dynamic-cpp-8.4.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-shared-cpp-8.4.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-implementation-2.15.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-implementation-cmake-7.3.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-robot-state-publisher-3.3.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-base-0.11.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-core-0.11.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-environment-4.2.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-workspace-1.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2action-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2bag-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2cli-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2cli-common-extensions-0.3.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2component-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2doctor-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2interface-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2launch-0.26.10-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2lifecycle-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2multicast-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2node-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2param-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2pkg-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2plugin-5.4.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2run-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2service-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2topic-0.32.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-compression-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-compression-zstd-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-cpp-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-interfaces-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-py-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-default-plugins-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-mcap-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-sqlite3-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-transport-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosgraph-msgs-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-adapter-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-cli-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-cmake-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-core-generators-0.2.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-core-runtime-0.2.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-default-generators-1.6.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-default-runtime-1.6.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-dynamic-typesupport-0.1.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-dynamic-typesupport-fastrtps-0.1.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-c-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-cpp-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-py-0.22.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-type-description-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-parser-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-pycommon-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-c-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-cpp-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-py-0.13.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-c-3.2.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-cpp-3.2.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-fastrtps-c-3.6.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-fastrtps-cpp-3.6.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-interface-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-introspection-c-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-introspection-cpp-4.6.7-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rpyutils-0.4.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rti-connext-dds-cmake-module-0.22.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-assimp-vendor-14.1.19-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-common-14.1.19-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-default-plugins-14.1.19-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-ogre-vendor-14.1.19-np2py312hf3be069_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-rendering-14.1.19-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz2-14.1.19-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sensor-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sensor-msgs-py-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-service-msgs-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-shape-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-spdlog-vendor-1.6.1-np2py312h918b84f_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sqlite3-vendor-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sros2-0.13.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sros2-cmake-0.13.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-statistics-msgs-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-std-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-std-srvs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-stereo-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-bullet-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-eigen-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-eigen-kdl-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-geometry-msgs-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-kdl-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-msgs-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-py-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-ros-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-ros-py-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-sensor-msgs-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-tools-0.36.18-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tinyxml2-vendor-0.9.2-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tracetools-8.2.4-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-trajectory-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-type-description-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-uncrustify-vendor-3.0.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-unique-identifier-msgs-2.5.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdf-2.10.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdf-parser-plugin-2.10.0-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdfdom-4.0.1-py312h24bf083_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdfdom-headers-1.1.2-py312h24bf083_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-visualization-msgs-5.3.6-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-yaml-cpp-vendor-9.0.1-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-zstd-vendor-0.26.9-np2py312h2ed9cc7_14.conda + - conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros2-distro-mutex-0.13.0-jazzy_14.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/rosdistro-1.0.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/rospkg-1.6.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhe01879c_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/snowballstemmer-3.0.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/spdlog-1.17.0-hab81395_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/sqlite-3.51.2-h04a0ce9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.10.1-h5b2951e_7100101.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.28-h4ee821c_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-2022.3.0-hb700be7_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-devel-2022.3.0-h51de99f_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h366c992_103.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/tomli-2.4.0-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.15.0-pyhcf101f3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025c-hc9c84f9_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/uncrustify-0.81.0-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.24.0-hd6090a7_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-h4f16b4b_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-image-0.4.0-hb711507_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.46-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.13-he1eb515_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxau-1.0.12-hb03c661_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxaw-1.0.16-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxcomposite-0.4.7-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxcursor-1.2.3-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdamage-1.1.6-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb03c661_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxext-1.3.7-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxfixes-6.0.2-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxi-1.8.2-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxinerama-1.1.6-hecca717_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxmu-1.3.1-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxpm-3.5.18-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrandr-1.5.5-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxshmfence-1.3.3-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxt-1.3.1-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.7-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-xorgproto-2025.1-hb03c661_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h280c20c_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-cpp-0.8.0-h3f2d84a_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.23.0-pyhcf101f3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.7-hb78ec9c_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zziplib-0.13.69-he45264a_2.conda +packages: +- conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-20_gnu.conda + build_number: 20 + sha256: 1dd3fffd892081df9726d7eb7e0dea6198962ba775bd88842135a4ddb4deb3c9 + md5: a9f577daf3de00bca7c3c76c0ecbd1de + depends: + - __glibc >=2.17,<3.0.a0 + - libgomp >=7.5.0 + constrains: + - openmp_impl <0.0a0 + license: BSD-3-Clause + size: 28948 + timestamp: 1770939786096 +- conda: https://conda.anaconda.org/conda-forge/noarch/adwaita-icon-theme-49.0-unix_0.conda + sha256: a362b4f5c96a0bf4def96be1a77317e2730af38915eb9bec85e2a92836501ed7 + md5: b3f0179590f3c0637b7eb5309898f79e + depends: + - __unix + - hicolor-icon-theme + - librsvg + license: LGPL-3.0-or-later OR CC-BY-SA-3.0 + license_family: LGPL + size: 631452 + timestamp: 1758743294412 +- conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.15.3-hb03c661_0.conda + sha256: d88aa7ae766cf584e180996e92fef2aa7d8e0a0a5ab1d4d49c32390c1b5fff31 + md5: dcdc58c15961dbf17a0621312b01f5cb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: LGPL-2.1-or-later + license_family: GPL + size: 584660 + timestamp: 1768327524772 +- conda: https://conda.anaconda.org/conda-forge/noarch/argcomplete-3.6.3-pyhd8ed1ab_0.conda + sha256: a2a1879c53b7a8438c898d20fa5f6274e4b1c30161f93b7818236e9df6adffde + md5: 8f37c8fb7116a18da04e52fa9e2c8df9 + depends: + - python >=3.10 + license: Apache-2.0 + license_family: Apache + size: 42386 + timestamp: 1760975036972 +- conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-hecf2907_1.conda + sha256: c49e992c1a2978f5a8cdf3cdf9aac0c0a444bbddb7316dbfbf16f5a94ff71c10 + md5: 649115e82c2a9620fcf0d3a846ee365f + depends: + - __glibc >=2.17,<3.0.a0 + - libboost >=1.88.0,<1.89.0a0 + - libgcc >=14 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + - zlib + license: BSD-3-Clause + license_family: BSD + size: 3645199 + timestamp: 1753274588181 +- conda: https://conda.anaconda.org/conda-forge/linux-64/at-spi2-atk-2.38.0-h0630a04_3.tar.bz2 + sha256: 26ab9386e80bf196e51ebe005da77d57decf6d989b4f34d96130560bc133479c + md5: 6b889f174df1e0f816276ae69281af4d + depends: + - at-spi2-core >=2.40.0,<2.41.0a0 + - atk-1.0 >=2.36.0 + - dbus >=1.13.6,<2.0a0 + - libgcc-ng >=9.3.0 + - libglib >=2.68.1,<3.0a0 + license: LGPL-2.1-or-later + license_family: LGPL + size: 339899 + timestamp: 1619122953439 +- conda: https://conda.anaconda.org/conda-forge/linux-64/at-spi2-core-2.40.3-h0630a04_0.tar.bz2 + sha256: c4f9b66bd94c40d8f1ce1fad2d8b46534bdefda0c86e3337b28f6c25779f258d + md5: 8cb2fc4cd6cc63f1369cfa318f581cc3 + depends: + - dbus >=1.13.6,<2.0a0 + - libgcc-ng >=9.3.0 + - libglib >=2.68.3,<3.0a0 + - xorg-libx11 + - xorg-libxi + - xorg-libxtst + license: LGPL-2.1-or-later + license_family: LGPL + size: 658390 + timestamp: 1625848454791 +- conda: https://conda.anaconda.org/conda-forge/linux-64/atk-1.0-2.38.0-h04ea711_2.conda + sha256: df682395d05050cd1222740a42a551281210726a67447e5258968dd55854302e + md5: f730d54ba9cd543666d7220c9f7ed563 + depends: + - libgcc-ng >=12 + - libglib >=2.80.0,<3.0a0 + - libstdcxx-ng >=12 + constrains: + - atk-1.0 2.38.0 + license: LGPL-2.0-or-later + license_family: LGPL + size: 355900 + timestamp: 1713896169874 +- conda: https://conda.anaconda.org/conda-forge/linux-64/attr-2.5.2-h39aace5_0.conda + sha256: a9c114cbfeda42a226e2db1809a538929d2f118ef855372293bd188f71711c48 + md5: 791365c5f65975051e4e017b5da3abf5 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: GPL-2.0-or-later + license_family: GPL + size: 68072 + timestamp: 1756738968573 +- conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.45.1-default_h4852527_101.conda + sha256: 2851d34944b056d028543f0440fb631aeeff204151ea09589d8d9c13882395de + md5: 9902aeb08445c03fb31e01beeb173988 + depends: + - binutils_impl_linux-64 >=2.45.1,<2.45.2.0a0 + license: GPL-3.0-only + license_family: GPL + size: 35128 + timestamp: 1770267175160 +- conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.45.1-default_hfdba357_101.conda + sha256: 74341b26a2b9475dc14ba3cf12432fcd10a23af285101883e720216d81d44676 + md5: 83aa53cb3f5fc849851a84d777a60551 + depends: + - ld_impl_linux-64 2.45.1 default_hbd61a6d_101 + - sysroot_linux-64 + - zstd >=1.5.7,<1.6.0a0 + license: GPL-3.0-only + license_family: GPL + size: 3744895 + timestamp: 1770267152681 +- conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.45.1-default_h4852527_101.conda + sha256: 4826f97d33cbe54459970a1e84500dbe0cccf8326aaf370e707372ae20ec5a47 + md5: dec96579f9a7035a59492bf6ee613b53 + depends: + - binutils_impl_linux-64 2.45.1 default_hfdba357_101 + license: GPL-3.0-only + license_family: GPL + size: 36060 + timestamp: 1770267177798 +- conda: https://conda.anaconda.org/conda-forge/linux-64/bullet-3.25-h26dfbe5_5.conda + sha256: 1ba37b4b500aa486012a19c3071477e2bac202822625980e99da77e2d18ea408 + md5: 980176113a639a707f5b158031cbac21 + depends: + - bullet-cpp 3.25 hcbe3ca9_5 + - numpy + - pybullet 3.25 py312hf49885f_5 + - python + license: Zlib + size: 11631 + timestamp: 1761041385662 +- conda: https://conda.anaconda.org/conda-forge/linux-64/bullet-cpp-3.25-hcbe3ca9_5.conda + sha256: 5b1d2b088f15796123a81d2213cf7998e7d36cb19293bc55d0d6c1d3254af7e5 + md5: 17f8b21e05588ceea91fbb1162133dbb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libgl >=1.7.0,<2.0a0 + - libstdcxx >=13 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + license: Zlib + size: 42581149 + timestamp: 1761041037901 +- conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-hda65f42_8.conda + sha256: c30daba32ddebbb7ded490f0e371eae90f51e72db620554089103b4a6934b0d5 + md5: 51a19bba1b8ebfb60df25cde030b7ebc + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: bzip2-1.0.6 + license_family: BSD + size: 260341 + timestamp: 1757437258798 +- conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.6-hb03c661_0.conda + sha256: cc9accf72fa028d31c2a038460787751127317dcfa991f8d1f1babf216bb454e + md5: 920bb03579f15389b9e512095ad995b7 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 207882 + timestamp: 1765214722852 +- conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.11.0-h4d9bdce_0.conda + sha256: 8e7a40f16400d7839c82581410aa05c1f8324a693c9d50079f8c50dc9fb241f0 + md5: abd85120de1187b0d1ec305c2173c71b + depends: + - binutils + - gcc + - gcc_linux-64 14.* + license: BSD-3-Clause + license_family: BSD + size: 6693 + timestamp: 1753098721814 +- conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2026.1.4-hbd8a1cb_0.conda + sha256: b5974ec9b50e3c514a382335efa81ed02b05906849827a34061c496f4defa0b2 + md5: bddacf101bb4dd0e51811cb69c7790e2 + depends: + - __unix + license: ISC + size: 146519 + timestamp: 1767500828366 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-he90730b_1.conda + sha256: 06525fa0c4e4f56e771a3b986d0fdf0f0fc5a3270830ee47e127a5105bde1b9a + md5: bb6c4808bfa69d6f7f6b07e5846ced37 + depends: + - __glibc >=2.17,<3.0.a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - icu >=78.1,<79.0a0 + - libexpat >=2.7.3,<3.0a0 + - libfreetype >=2.14.1 + - libfreetype6 >=2.14.1 + - libgcc >=14 + - libglib >=2.86.3,<3.0a0 + - libpng >=1.6.53,<1.7.0a0 + - libstdcxx >=14 + - libxcb >=1.17.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pixman >=0.46.4,<1.0a0 + - xorg-libice >=1.1.2,<2.0a0 + - xorg-libsm >=1.2.6,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxrender >=0.9.12,<0.10.0a0 + license: LGPL-2.1-only or MPL-1.1 + size: 989514 + timestamp: 1766415934926 +- conda: https://conda.anaconda.org/conda-forge/noarch/catkin_pkg-1.1.0-pyhd8ed1ab_0.conda + sha256: fe602164dc1920551e1452543e22338d55d8a879959f12598c9674cf295c6341 + md5: 3e500faf80e42f26d422d849877d48c4 + depends: + - docutils + - packaging + - pyparsing >=1.5.7 + - python >=3.10 + - python-dateutil + - setuptools + license: BSD-3-Clause + license_family: BSD + size: 54106 + timestamp: 1757558592553 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cffi-2.0.0-py312h460c074_1.conda + sha256: 7dafe8173d5f94e46cf9cd597cc8ff476a8357fbbd4433a8b5697b2864845d9c + md5: 648ee28dcd4e07a1940a17da62eccd40 + depends: + - __glibc >=2.17,<3.0.a0 + - libffi >=3.5.2,<3.6.0a0 + - libgcc >=14 + - pycparser + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + license: MIT + license_family: MIT + size: 295716 + timestamp: 1761202958833 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-22.1.0-default_cfg_hcbb2b3e_0.conda + sha256: 0d9742b0b96fabbe31a412903f1b9de6548cc65cce39d78c1d845a2156480d1b + md5: feae0bebfd6f906118d713872ee396d8 + depends: + - binutils + - clang-22 22.1.0 default_h99862b1_0 + - clang_impl_linux-64 22.1.0 default_h0a60c25_0 + - libgcc-devel_linux-64 + - llvm-openmp >=22.1.0 + - sysroot_linux-64 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 28113 + timestamp: 1772101286498 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-22-22.1.0-default_h99862b1_0.conda + sha256: a24a4eb8522693fbfc6c6b9ab1914314437ca0858b8ac6909275b47be3e93e39 + md5: 1f2b771fc99f1c8115301a9d232dfd94 + depends: + - __glibc >=2.17,<3.0.a0 + - compiler-rt22 22.1.0.* + - libclang-cpp22.1 22.1.0 default_h99862b1_0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 835553 + timestamp: 1772101189757 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-format-22.1.0-default_h99862b1_0.conda + sha256: 67e99d217817f3115e2e6ba6b90d3cbc955445bb5d87742e143890bd1a05cdb4 + md5: 0ebd70b00f94acd3d2bc01bfc1151fa4 + depends: + - __glibc >=2.17,<3.0.a0 + - clang-format-22 22.1.0 default_h99862b1_0 + - libclang-cpp22.1 >=22.1.0,<22.2.0a0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 28114 + timestamp: 1772101578252 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-format-22-22.1.0-default_h99862b1_0.conda + sha256: a632b53be7fca298c62eb1cc017feff11b1c10718431bd7dca7ceefacbb64ae2 + md5: b423173906754d2bb291d35a90826c58 + depends: + - __glibc >=2.17,<3.0.a0 + - libclang-cpp22.1 >=22.1.0,<22.2.0a0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 70149 + timestamp: 1772101519733 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-tools-22.1.0-default_h99862b1_0.conda + sha256: 2edfe83cf1b6eb4baee5a8de966741bdb3d41944cb83bc9523a1674f7e9613de + md5: 5a2857dadc04f8e0f77454e0ad48cb4e + depends: + - __glibc >=2.17,<3.0.a0 + - clang-format 22.1.0 default_h99862b1_0 + - libclang-cpp22.1 >=22.1.0,<22.2.0a0 + - libclang13 >=22.1.0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + - libxml2 + - libxml2-16 >=2.14.6 + constrains: + - clangdev 22.1.0 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 10639751 + timestamp: 1772101626870 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang_impl_linux-64-22.1.0-default_h0a60c25_0.conda + sha256: 8ac20fa0b6c96e739c06ec22e83560136d06799522bcd9421b083ec999ca01a1 + md5: c679d2aa7914d773899033583278fa24 + depends: + - binutils_impl_linux-64 + - clang-22 22.1.0 default_h99862b1_0 + - compiler-rt 22.1.0.* + - compiler-rt_linux-64 + - libgcc-devel_linux-64 + - sysroot_linux-64 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 27622 + timestamp: 1772101256543 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cli11-2.6.2-h54a6638_0.conda + sha256: 1d635e8963e094d95d35148df4b46e495f93bb0750ad5069f4e0e6bbb47ac3bf + md5: 83dae3dfadcfec9b37a9fbff6f7f7378 + depends: + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: BSD-3-Clause + license_family: BSD + size: 99051 + timestamp: 1772207728613 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.2.3-hc85cc9f_0.conda + sha256: b42757cd16eb0dbf50d8a28cbdf9ae3ce84349c6b4b94ebdb1fa0234a67f2e06 + md5: 5510e057b9197282ab7a67ef41b5d76d + depends: + - __glibc >=2.17,<3.0.a0 + - bzip2 >=1.0.8,<2.0a0 + - libcurl >=8.18.0,<9.0a0 + - libexpat >=2.7.3,<3.0a0 + - libgcc >=14 + - liblzma >=5.8.2,<6.0a0 + - libstdcxx >=14 + - libuv >=1.51.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - ncurses >=6.5,<7.0a0 + - rhash >=1.4.6,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: BSD-3-Clause + license_family: BSD + size: 22336786 + timestamp: 1769597568744 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-argcomplete-0.3.3-pyhd8ed1ab_1.conda + sha256: 05ccb85cad9ca58be9dcb74225f6180a68907a6ab0c990e3940f4decc5bb2280 + md5: bde6042a1b40a2d4021e1becbe8dd84f + depends: + - argcomplete + - colcon-core + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 18692 + timestamp: 1735452378252 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-bash-0.5.0-pyhd8ed1ab_1.conda + sha256: 4a1258c9743f4e29d666993c3aa29aaf5a310a77f5334f98b81f1c80c2a46fa7 + md5: abcd9e9bc122d03f86d364ccb15957c7 + depends: + - colcon-core >=0.4.0 + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 19001 + timestamp: 1735646679519 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-cd-0.1.1-pyhd8ed1ab_1.conda + sha256: 4cbac86d8c2c62293586664b3ccb3371bb51b671a8ee607adaadf78a9a745f92 + md5: 872e61a33caebff21a695ea1f886f3bf + depends: + - colcon-core >=0.4.1 + - colcon-package-information + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 16858 + timestamp: 1735513271475 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-cmake-0.2.29-pyhd8ed1ab_1.conda + sha256: edc01069635b0bb7d9a58c1f36371d1c841ecf90b8e74397df418436209ce01c + md5: b5b23d06f0def5724475bd12365f1aa5 + depends: + - colcon-core + - colcon-library-path + - colcon-test-result >=0.3.3 + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 26257 + timestamp: 1757616401522 +- conda: https://conda.anaconda.org/conda-forge/linux-64/colcon-common-extensions-0.3.0-py312h7900ff3_4.conda + sha256: 27f2433f8e452f31d6b9a5d1e59cb034466f06850c4f1eabf079452583bce57c + md5: 75c354bb1fbd29aeebeb140b05233b66 + depends: + - colcon-argcomplete + - colcon-bash + - colcon-cd + - colcon-cmake + - colcon-core + - colcon-defaults + - colcon-devtools + - colcon-library-path + - colcon-metadata + - colcon-output + - colcon-package-information + - colcon-package-selection + - colcon-parallel-executor + - colcon-powershell + - colcon-python-setup-py + - colcon-recursive-crawl + - colcon-ros + - colcon-test-result + - colcon-zsh + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + license_family: APACHE + size: 13032 + timestamp: 1759757821346 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-core-0.20.1-pyhcf101f3_0.conda + sha256: 488babf2d1649d60ca2505de6f2bb8f2d66c41805e9ffeba0446a0fd2eeaafc0 + md5: 243a645c3e76d48a1a62209cd1477d0c + depends: + - python >=3.10 + - coloredlogs + - distlib + - empy + - pytest + - pytest-cov + - pytest-repeat + - pytest-rerunfailures + - setuptools >=30.3.0,<80 + - tomli >=1.0.0 + - python + license: Apache-2.0 + license_family: APACHE + size: 95568 + timestamp: 1759822473386 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-defaults-0.2.9-pyhd8ed1ab_1.conda + sha256: dd89f3e92a80532b9c6427ec9dd12742be9e27c3d6639555a4f786787fb5f33d + md5: 1bc984ddc9434fd2fdabde2e0e44dd14 + depends: + - colcon-core >=0.2.0 + - python >=3.10 + - pyyaml + license: Apache-2.0 + license_family: APACHE + size: 15580 + timestamp: 1757616344706 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-devtools-0.3.0-pyhd8ed1ab_1.conda + sha256: 76fcd1500b6f70f61be4c1fa1defb9d56d69389d22261a6e0c0f966ed8ea515d + md5: d4c1201d9d20e0c05836ca81884c7cdb + depends: + - colcon-core + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 14943 + timestamp: 1757616967604 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-library-path-0.2.1-pyhd8ed1ab_1.conda + sha256: b3a01541cbe8e4c7ca789c71b5d0155ca14cc9c6ebaa6036d1becd72cb0c3227 + md5: 37c84be9d74c37fde10d1155d77e805e + depends: + - colcon-core + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 13505 + timestamp: 1757615646068 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-metadata-0.2.5-pyhd8ed1ab_1.conda + sha256: f337471a44b2d29111ee562872da6ab2abcd55e139c8a5e74c76f3f7fb3042b7 + md5: df798f897da0ae212d14faa79a4565f5 + depends: + - colcon-core + - python >=3.10 + - pyyaml + license: Apache-2.0 + license_family: APACHE + size: 20031 + timestamp: 1757624342935 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-output-0.2.13-pyhd8ed1ab_0.conda + sha256: ce2802f9c76f4502d17ff47f76f634449a1ae10fded0bed6a65c05d35ccafb33 + md5: d0294b947e6256444f31979612468bba + depends: + - colcon-core >=0.3.8 + - python >=3.5 + license: Apache-2.0 + license_family: APACHE + size: 16174 + timestamp: 1676526311561 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-package-information-0.4.0-pyhd8ed1ab_1.conda + sha256: 6654254ab628a9ca1648a18b7a1c078ae11bf9eca898a4ee20f601b622acd783 + md5: 6f4c11d25a53f2a7daac0232c3306556 + depends: + - colcon-core + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 18705 + timestamp: 1764592318817 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-package-selection-0.2.10-pyhd8ed1ab_1.conda + sha256: 1cc39947aace656988696bc63c520e031c27a974e18b3fce0db58e18bb6228a5 + md5: 1ef460db4fbafbb3279e950378d317b5 + depends: + - colcon-core >=0.3.19 + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 18069 + timestamp: 1757614388574 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-parallel-executor-0.4.0-pyhe01879c_0.conda + sha256: 45285d47851b2d38c3ae7665af68f49f7a670737e6320d2715cf5870747007d2 + md5: 1bad6182810fe70aa0baaf2ec0c2747d + depends: + - python >=3.9 + - colcon-core >=0.3.15 + - python + license: Apache-2.0 + license_family: APACHE + size: 20688 + timestamp: 1755156877864 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-pkg-config-0.1.0-py_0.tar.bz2 + sha256: c8c6baf7ba174c908d501c6df577c140de73f46aadea09a6b3aaf405406e3b5a + md5: 434ecb5d163df485879081aedebd59bf + depends: + - colcon-core + - python >=3.5 + license: Apache-2.0 + license_family: APACHE + size: 10397 + timestamp: 1571038968482 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-powershell-0.5.0-pyhd8ed1ab_0.conda + sha256: 9afc4546ba72326e6a7e0e9874879709e3c14260e49ae11663164bd0f3911106 + md5: 3f5f803ff3703d28c8ec4cc9b3564257 + depends: + - colcon-core >=0.3.18 + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 17608 + timestamp: 1770791211378 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-python-setup-py-0.2.9-pyhff2d567_1.conda + sha256: c3f6cb06b4e1f0fc0efc50ee7ca78fb8d1bcdfff92afcd0e9235c53eb521e61a + md5: f9e99cee078c732ab49d547fa1a7a752 + depends: + - colcon-core >=0.6.1 + - python >=3.9 + - setuptools + license: Apache-2.0 + license_family: APACHE + size: 16561 + timestamp: 1753971248803 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-recursive-crawl-0.2.3-pyhd8ed1ab_0.conda + sha256: 8aede8793a64695cf65f37633ede04c125db71d13abc2c8fb70b44fbc48d3794 + md5: 0e15eecc695ef5a4508ffe3e438f1466 + depends: + - colcon-core >=0.2.0 + - python >=3.5 + license: Apache-2.0 + license_family: APACHE + size: 13254 + timestamp: 1696534627965 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-ros-0.5.0-pyhd8ed1ab_0.conda + sha256: 7c018dd7074de3b3bac375718cd43ff4677ef18f8ab81c3a75bed4eb646e280e + md5: 7ba348bf6258968e8f514cd25c207933 + depends: + - catkin_pkg >=0.4.14 + - colcon-cmake >=0.2.6 + - colcon-core >=0.7.0 + - colcon-pkg-config + - colcon-python-setup-py >=0.2.4 + - colcon-recursive-crawl + - python >=3.6 + license: Apache-2.0 + license_family: APACHE + size: 23852 + timestamp: 1719301582281 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-test-result-0.3.8-pyhd8ed1ab_1.conda + sha256: a9657a89b55efc8abd46d3b32bd4cb9ed06ecc84b76ddf5e6d336945633a9269 + md5: 1f45017750d20d6538970315e10a2f01 + depends: + - colcon-core + - python >=3.10 + license: Apache-2.0 + license_family: APACHE + size: 17214 + timestamp: 1757615650730 +- conda: https://conda.anaconda.org/conda-forge/noarch/colcon-zsh-0.5.0-pyhd8ed1ab_1.conda + sha256: 0f089c2ee902d7d43b75f22af74af2dd914546d81e7380c097e31a206c42984e + md5: a274fdd9d63e809b4fdcaee36a8bc42c + depends: + - colcon-core >=0.4.0 + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 18905 + timestamp: 1735357634338 +- conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda + sha256: ab29d57dc70786c1269633ba3dff20288b81664d3ff8d21af995742e2bb03287 + md5: 962b9857ee8e7018c22f2776ffa0b2d7 + depends: + - python >=3.9 + license: BSD-3-Clause + license_family: BSD + size: 27011 + timestamp: 1733218222191 +- conda: https://conda.anaconda.org/conda-forge/noarch/coloredlogs-15.0.1-pyhd8ed1ab_4.conda + sha256: 8021c76eeadbdd5784b881b165242db9449783e12ce26d6234060026fd6a8680 + md5: b866ff7007b934d564961066c8195983 + depends: + - humanfriendly >=9.1 + - python >=3.9 + license: MIT + license_family: MIT + size: 43758 + timestamp: 1733928076798 +- conda: https://conda.anaconda.org/conda-forge/linux-64/compiler-rt-22.1.0-ha770c72_0.conda + sha256: 6c6cd8ec8b99e9e4bbe121b77e0f356a2f8845add6d0cd4d6f71f6201fa654c2 + md5: 98cc540405de03e37417cc94f4191301 + depends: + - compiler-rt22 22.1.0 hb700be7_0 + - libcompiler-rt 22.1.0 hb700be7_0 + constrains: + - clang 22.1.0 + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 16378 + timestamp: 1772021047024 +- conda: https://conda.anaconda.org/conda-forge/linux-64/compiler-rt22-22.1.0-hb700be7_0.conda + sha256: a23f7a8bd6722b41abea88ebd0cea674b0daf8dfee70ece8d2cc798556144675 + md5: 6930338793ffed4140d0903011f6937e + depends: + - __glibc >=2.17,<3.0.a0 + - compiler-rt22_linux-64 22.1.0.* + - libgcc >=14 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 114932 + timestamp: 1772021045728 +- conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt22_linux-64-22.1.0-hffcefe0_0.conda + sha256: a37472aa2288bea0c588ae47aca6291238558303fdc2e814b58b8de64937263b + md5: 1254d960f9dd3d269c093ee6db94a454 + constrains: + - compiler-rt >=9.0.1 + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 48094890 + timestamp: 1772020917994 +- conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_linux-64-22.1.0-ha770c72_0.conda + sha256: 081a126085b6656b8f5e0ffe0636eb07287d81376bdb8d49f5e0e455dce8bce9 + md5: 00fd62b3f1c0019f6aa9d6913f0917f9 + depends: + - compiler-rt22_linux-64 22.1.0 hffcefe0_0 + constrains: + - clang 22.1.0 + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 16403 + timestamp: 1772021046573 +- conda: https://conda.anaconda.org/conda-forge/linux-64/compilers-1.11.0-ha770c72_0.conda + sha256: 5709f2cbfeb8690317ba702611bdf711a502b417fecda6ad3313e501f6f8bd61 + md5: fdcf2e31dd960ef7c5daa9f2c95eff0e + depends: + - c-compiler 1.11.0 h4d9bdce_0 + - cxx-compiler 1.11.0 hfcd1e18_0 + - fortran-compiler 1.11.0 h9bea470_0 + license: BSD-3-Clause + license_family: BSD + size: 7482 + timestamp: 1753098722454 +- conda: https://conda.anaconda.org/conda-forge/linux-64/conda-gcc-specs-14.3.0-he8ccf15_17.conda + sha256: 522e7a22da3e8f30c8e8c80831c4d7399d8797fce154acbdf904111501d637f6 + md5: 4e58f090f75b2941346da3685564e7a7 + depends: + - gcc_impl_linux-64 >=14.3.0,<14.3.1.0a0 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 31646 + timestamp: 1770252240343 +- conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 + sha256: 29caeda123ea705e68de46dc3b86065ec78f5b44d7ae69b320cc57e136d2d9d7 + md5: e891b2b856a57d2b2ddb9ed366e3f2ce + depends: + - libgcc-ng >=10.3.0 + - libstdcxx-ng >=10.3.0 + license: BSD-3-Clause + license_family: BSD + size: 18460 + timestamp: 1648912649612 +- conda: https://conda.anaconda.org/conda-forge/linux-64/coverage-7.13.4-py312h8a5da7c_0.conda + sha256: 2c785feaf79c31981ef4a87e41ea1161e1ce6b740ce3f1fb9cf44245cae5cf29 + md5: a8df7f0812ac4fa6bbc7135556d3e2c4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + - tomli + license: Apache-2.0 + license_family: APACHE + size: 388190 + timestamp: 1770720373428 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cppcheck-2.18.3-py312h014360a_1.conda + sha256: f4321bdeddc9178f006a8cc3dedeaf32ab7e4c3be843845fbf594bc07999d2d6 + md5: ab786ccd5cc6a08c0ebd5f6154c9dfcd + depends: + - pygments + - python + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - tinyxml2 >=11.0.0,<11.1.0a0 + - pcre >=8.45,<9.0a0 + - python_abi 3.12.* *_cp312 + license: GPL-3.0-or-later + license_family: GPL + size: 3065679 + timestamp: 1757440259649 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cryptography-46.0.5-py312ha4b625e_0.conda + sha256: 3a20020b7c9efbabfbfdd726ff303df81159e0c3a41a40ef8b37c3ce161a7849 + md5: 4c69182866fcdd2fc335885b8f0ac192 + depends: + - __glibc >=2.17,<3.0.a0 + - cffi >=1.14 + - libgcc >=14 + - openssl >=3.5.5,<4.0a0 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + constrains: + - __glibc >=2.17 + license: Apache-2.0 AND BSD-3-Clause AND PSF-2.0 AND MIT + license_family: BSD + size: 1712251 + timestamp: 1770772759286 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.11.0-hfcd1e18_0.conda + sha256: 3fcc97ae3e89c150401a50a4de58794ffc67b1ed0e1851468fcc376980201e25 + md5: 5da8c935dca9186673987f79cef0b2a5 + depends: + - c-compiler 1.11.0 h4d9bdce_0 + - gxx + - gxx_linux-64 14.* + license: BSD-3-Clause + license_family: BSD + size: 6635 + timestamp: 1753098722177 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.28-hd9c7081_0.conda + sha256: ee09ad7610c12c7008262d713416d0b58bf365bc38584dce48950025850bdf3f + md5: cae723309a49399d2949362f4ab5c9e4 + depends: + - __glibc >=2.17,<3.0.a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - libntlm >=1.8,<2.0a0 + - libstdcxx >=13 + - libxcrypt >=4.4.36 + - openssl >=3.5.0,<4.0a0 + license: BSD-3-Clause-Attribution + license_family: BSD + size: 209774 + timestamp: 1750239039316 +- conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.16.2-h24cb091_1.conda + sha256: 8bb557af1b2b7983cf56292336a1a1853f26555d9c6cecf1e5b2b96838c9da87 + md5: ce96f2f470d39bd96ce03945af92e280 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + - libglib >=2.86.2,<3.0a0 + - libexpat >=2.7.3,<3.0a0 + license: AFL-2.1 OR GPL-2.0-or-later + size: 447649 + timestamp: 1764536047944 +- conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.4.0-pyhd8ed1ab_0.conda + sha256: 6d977f0b2fc24fee21a9554389ab83070db341af6d6f09285360b2e09ef8b26e + md5: 003b8ba0a94e2f1e117d0bd46aebc901 + depends: + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 275642 + timestamp: 1752823081585 +- conda: https://conda.anaconda.org/conda-forge/noarch/distro-1.9.0-pyhd8ed1ab_1.conda + sha256: 5603c7d0321963bb9b4030eadabc3fd7ca6103a38475b4e0ed13ed6d97c86f4e + md5: 0a2014fd9860f8b1eaa0b1f3d3771a08 + depends: + - python >=3.9 + license: Apache-2.0 + license_family: APACHE + size: 41773 + timestamp: 1734729953882 +- conda: https://conda.anaconda.org/conda-forge/noarch/docutils-0.22.4-pyhd8ed1ab_0.conda + sha256: 0d605569a77350fb681f9ed8d357cc71649b59a304099dc9d09fbeec5e84a65e + md5: d6bd3cd217e62bbd7efe67ff224cd667 + depends: + - python >=3.10 + license: CC-PDDC AND BSD-3-Clause AND BSD-2-Clause AND ZPL-2.1 + size: 438002 + timestamp: 1766092633160 +- conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h171cf75_1.conda + sha256: fee3738c2431c13f4930778e9d7daca9328e7e2f2a38928cf6ca5a0daa86474a + md5: ea2db216eae84bc83b0b2961f38f5c0d + depends: + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: MPL-2.0 + license_family: MOZILLA + size: 1169164 + timestamp: 1759819831835 +- conda: https://conda.anaconda.org/conda-forge/noarch/empy-3.3.4-pyh9f0ad1d_1.tar.bz2 + sha256: 75e04755df8d8db7a7711dddaf68963c11258b755c9c24565bfefa493ee383e3 + md5: e4be10fd1a907b223da5be93f06709d2 + depends: + - python + license: LGPL-2.1 + license_family: GPL + size: 40210 + timestamp: 1586444722817 +- conda: https://conda.anaconda.org/conda-forge/linux-64/epoxy-1.5.10-hb03c661_2.conda + sha256: a5b51e491fec22bcc1765f5b2c8fff8a97428e9a5a7ee6730095fb9d091b0747 + md5: 057083b06ccf1c2778344b6dabace38b + depends: + - __glibc >=2.17,<3.0.a0 + - libdrm >=2.4.125,<2.5.0a0 + - libegl >=1.7.0,<2.0a0 + - libegl-devel + - libgcc >=14 + - libgl >=1.7.0,<2.0a0 + - libgl-devel + - libglx >=1.7.0,<2.0a0 + - libglx-devel + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxdamage >=1.1.6,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxfixes >=6.0.1,<7.0a0 + - xorg-libxxf86vm >=1.1.6,<2.0a0 + license: MIT + license_family: MIT + size: 411735 + timestamp: 1758743520805 +- conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.3.1-pyhd8ed1ab_0.conda + sha256: ee6cf346d017d954255bbcbdb424cddea4d14e4ed7e9813e429db1d795d01144 + md5: 8e662bd460bda79b1ea39194e3c4c9ab + depends: + - python >=3.10 + - typing_extensions >=4.6.0 + license: MIT and PSF-2.0 + size: 21333 + timestamp: 1763918099466 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-7.3.0-pyhd8ed1ab_0.conda + sha256: a32e511ea71a9667666935fd9f497f00bcc6ed0099ef04b9416ac24606854d58 + md5: 04a55140685296b25b79ad942264c0ef + depends: + - mccabe >=0.7.0,<0.8.0 + - pycodestyle >=2.14.0,<2.15.0 + - pyflakes >=3.4.0,<3.5.0 + - python >=3.9 + license: MIT + license_family: MIT + size: 111916 + timestamp: 1750968083921 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-builtins-3.1.0-pyhd8ed1ab_0.conda + sha256: d022684576c0c6f474bddbc263c82a3ba303c3bd09185d15af4eb7b60e896d7f + md5: 5cbaa86cc684a52a057831cbcb3bd5b9 + depends: + - flake8 + - python >=3.10 + license: GPL-2.0-only + license_family: GPL2 + size: 19501 + timestamp: 1761594405382 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-comprehensions-3.17.0-pyhd8ed1ab_0.conda + sha256: a0427b75e67d6f2f41f7645b850ac028876bee3a11d8fbaa18d88fd61b467a94 + md5: 9f5bd5fb0aa24273e9cce97830629e20 + depends: + - flake8 >=3.0,!=3.2.0 + - python >=3.10 + license: MIT + license_family: MIT + size: 14049 + timestamp: 1757526877129 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-docstrings-1.7.0-pyhd8ed1ab_0.conda + sha256: e0757805056f7ad3c7172ca4eaf79c9db4a7d23b858aa8fdcdfbd25f8ad7254d + md5: d66b253112adf72dc5edeabe41b88dce + depends: + - flake8 >=3 + - pydocstyle >=2.1 + - python >=3.7 + license: MIT + license_family: MIT + size: 10395 + timestamp: 1675285794906 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-import-order-0.19.2-pyhd8ed1ab_0.conda + sha256: 046902c4b7b07877e68c5dd638f92ece9416fe1b10153dd7d617b91c4f18946c + md5: f4b095568df0c12ab60f8519cb203317 + depends: + - flake8 + - pycodestyle + - python >=3.9 + - setuptools + license: LGPL-3.0-only + license_family: LGPL + size: 21041 + timestamp: 1750969641622 +- conda: https://conda.anaconda.org/conda-forge/noarch/flake8-quotes-3.4.0-pyhd8ed1ab_1.conda + sha256: 72129d47a933843df04e98f9afb27b3c2345d89f6c4b6637ea9cd1846960ad67 + md5: adde488e6dff56bffd2e5f428ae8cded + depends: + - flake8 + - python >=3.9 + license: MIT + license_family: MIT + size: 14776 + timestamp: 1735335323771 +- conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-12.1.0-hff5e90c_0.conda + sha256: d4e92ba7a7b4965341dc0fca57ec72d01d111b53c12d11396473115585a9ead6 + md5: f7d7a4104082b39e3b3473fbd4a38229 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: MIT + license_family: MIT + size: 198107 + timestamp: 1767681153946 +- conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 + sha256: 58d7f40d2940dd0a8aa28651239adbf5613254df0f75789919c4e6762054403b + md5: 0c96522c6bdaed4b1566d11387caaf45 + license: BSD-3-Clause + license_family: BSD + size: 397370 + timestamp: 1566932522327 +- conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 + sha256: c52a29fdac682c20d252facc50f01e7c2e7ceac52aa9817aaf0bb83f7559ec5c + md5: 34893075a5c9e55cdafac56607368fc6 + license: OFL-1.1 + license_family: Other + size: 96530 + timestamp: 1620479909603 +- conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 + sha256: 00925c8c055a2275614b4d983e1df637245e19058d79fc7dd1a93b8d9fb4b139 + md5: 4d59c254e01d9cde7957100457e2d5fb + license: OFL-1.1 + license_family: Other + size: 700814 + timestamp: 1620479612257 +- conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-ubuntu-0.83-h77eed37_3.conda + sha256: 2821ec1dc454bd8b9a31d0ed22a7ce22422c0aef163c59f49dfdf915d0f0ca14 + md5: 49023d73832ef61042f6a237cb2687e7 + license: LicenseRef-Ubuntu-Font-Licence-Version-1.0 + license_family: Other + size: 1620504 + timestamp: 1727511233259 +- conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda + sha256: 7093aa19d6df5ccb6ca50329ef8510c6acb6b0d8001191909397368b65b02113 + md5: 8f5b0b297b59e1ac160ad4beec99dbee + depends: + - __glibc >=2.17,<3.0.a0 + - freetype >=2.12.1,<3.0a0 + - libexpat >=2.6.3,<3.0a0 + - libgcc >=13 + - libuuid >=2.38.1,<3.0a0 + - libzlib >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 265599 + timestamp: 1730283881107 +- conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 + sha256: a997f2f1921bb9c9d76e6fa2f6b408b7fa549edd349a77639c9fe7a23ea93e61 + md5: fee5683a3f04bd15cbd8318b096a27ab + depends: + - fonts-conda-forge + license: BSD-3-Clause + license_family: BSD + size: 3667 + timestamp: 1566974674465 +- conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-hc364b38_1.conda + sha256: 54eea8469786bc2291cc40bca5f46438d3e062a399e8f53f013b6a9f50e98333 + md5: a7970cd949a077b7cb9696379d338681 + depends: + - font-ttf-ubuntu + - font-ttf-inconsolata + - font-ttf-dejavu-sans-mono + - font-ttf-source-code-pro + license: BSD-3-Clause + license_family: BSD + size: 4059 + timestamp: 1762351264405 +- conda: https://conda.anaconda.org/conda-forge/linux-64/foonathan-memory-0.7.3-h5888daf_1.conda + sha256: 28d9fce64ee8b5e94350feb0829e054811678f9638039f78ddff8a8615c1b693 + md5: 2a3316f47d7827afde5381ecd43b5e85 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: Zlib + size: 227132 + timestamp: 1746246721660 +- conda: https://conda.anaconda.org/conda-forge/linux-64/fortran-compiler-1.11.0-h9bea470_0.conda + sha256: 53e5562ede83b478ebe9f4fc3d3b4eff5b627883f48aa0bf412e8fd90b5d6113 + md5: d5596f445a1273ddc5ea68864c01b69f + depends: + - binutils + - c-compiler 1.11.0 h4d9bdce_0 + - gfortran + - gfortran_linux-64 14.* + license: BSD-3-Clause + license_family: BSD + size: 6656 + timestamp: 1753098722318 +- conda: https://conda.anaconda.org/conda-forge/linux-64/freeglut-3.2.2-ha6d2627_3.conda + sha256: 676540a8e7f73a894cb1fcb870e7bec623ec1c0a2d277094fd713261a02d8d56 + md5: 84ec3f5b46f3076be49f2cf3f1cfbf02 + depends: + - libgcc-ng >=12 + - libstdcxx-ng >=12 + - libxcb >=1.16,<2.0.0a0 + - xorg-libx11 >=1.8.9,<2.0a0 + - xorg-libxau >=1.0.11,<2.0a0 + - xorg-libxext >=1.3.4,<2.0a0 + - xorg-libxfixes + - xorg-libxi + license: MIT + license_family: MIT + size: 144010 + timestamp: 1719014356708 +- conda: https://conda.anaconda.org/conda-forge/linux-64/freeimage-3.18.0-h49ef1fa_24.conda + sha256: 42a16cc6d4521d8b596d533be088f828afb390cb4b9ebba265f9ed22a91c2bdf + md5: 14ccdbaf6fcf27563ac43e522559a79b + depends: + - __glibc >=2.17,<3.0.a0 + - imath >=3.2.2,<3.2.3.0a0 + - jxrlib >=1.1,<1.2.0a0 + - libgcc >=14 + - libjpeg-turbo >=3.1.2,<4.0a0 + - libpng >=1.6.50,<1.7.0a0 + - libraw >=0.21.4,<0.22.0a0 + - libstdcxx >=14 + - libtiff >=4.7.1,<4.8.0a0 + - libwebp-base >=1.6.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - openexr >=3.4.3,<3.5.0a0 + - openjpeg >=2.5.4,<3.0a0 + license: GPL-2.0-or-later OR GPL-3.0-or-later OR FreeImage + size: 469295 + timestamp: 1763479124009 +- conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.14.1-ha770c72_0.conda + sha256: bf8e4dffe46f7d25dc06f31038cacb01672c47b9f45201f065b0f4d00ab0a83e + md5: 4afc585cd97ba8a23809406cd8a9eda8 + depends: + - libfreetype 2.14.1 ha770c72_0 + - libfreetype6 2.14.1 h73754d4_0 + license: GPL-2.0-only OR FTL + size: 173114 + timestamp: 1757945422243 +- conda: https://conda.anaconda.org/conda-forge/linux-64/fribidi-1.0.16-hb03c661_0.conda + sha256: 858283ff33d4c033f4971bf440cebff217d5552a5222ba994c49be990dacd40d + md5: f9f81ea472684d75b9dd8d0b328cf655 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: LGPL-2.1-or-later + size: 61244 + timestamp: 1757438574066 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-14.3.0-h0dff253_17.conda + sha256: e3eb2b4655d8a65488fdfbe470705a290121c4265f9559933a8071aa9aac5b91 + md5: dfcfcc0c20762eeb840771eda366940e + depends: + - conda-gcc-specs + - gcc_impl_linux-64 14.3.0 hb1e0a52_17 + license: BSD-3-Clause + license_family: BSD + size: 29381 + timestamp: 1770252396987 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-14.3.0-hb1e0a52_17.conda + sha256: bc7014fcc7fcd54ae922fc3453ad8d88a26f439570bb6a89f785f8b5793306b2 + md5: f5c501fe2a016ed0103f7a89d2ac0412 + depends: + - binutils_impl_linux-64 >=2.45 + - libgcc >=14.3.0 + - libgcc-devel_linux-64 14.3.0 hf649bbc_117 + - libgomp >=14.3.0 + - libsanitizer 14.3.0 h8f1669f_17 + - libstdcxx >=14.3.0 + - libstdcxx-devel_linux-64 14.3.0 h9f08a49_117 + - sysroot_linux-64 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 74850589 + timestamp: 1770252142196 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-14.3.0-h298d278_21.conda + sha256: 27ad0cd10dccffca74e20fb38c9f8643ff8fce56eee260bf89fa257d5ab0c90a + md5: 1403ed5fe091bd7442e4e8a229d14030 + depends: + - gcc_impl_linux-64 14.3.0.* + - binutils_linux-64 + - sysroot_linux-64 + license: BSD-3-Clause + size: 28946 + timestamp: 1770908213807 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gdk-pixbuf-2.44.5-h2b0a6b4_0.conda + sha256: bd61bc71e6a21f3d8e1a362310789fc329fd45eab3c66f1204249253f9abd3d0 + md5: e3bcef76c3ecb25823c503ce11783d85 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libglib >=2.86.3,<3.0a0 + - libjpeg-turbo >=3.1.2,<4.0a0 + - liblzma >=5.8.2,<6.0a0 + - libpng >=1.6.54,<1.7.0a0 + - libtiff >=4.7.1,<4.8.0a0 + license: LGPL-2.1-or-later + license_family: LGPL + size: 575201 + timestamp: 1769891110279 +- conda: https://conda.anaconda.org/conda-forge/linux-64/geographiclib-cpp-2.5.2-hb700be7_0.conda + sha256: 0a402f0943f7598e85fadf294ab087f9ba877c55fbcc22010b2085495314bae1 + md5: eb2f3edf40dae98bca1b43e9e8fd1bc9 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: MIT + license_family: MIT + size: 600564 + timestamp: 1755957967788 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gettext-0.25.1-h3f43e3d_1.conda + sha256: cbfa8c80771d1842c2687f6016c5e200b52d4ca8f2cc119f6377f64f899ba4ff + md5: c42356557d7f2e37676e121515417e3b + depends: + - __glibc >=2.17,<3.0.a0 + - gettext-tools 0.25.1 h3f43e3d_1 + - libasprintf 0.25.1 h3f43e3d_1 + - libasprintf-devel 0.25.1 h3f43e3d_1 + - libgcc >=14 + - libgettextpo 0.25.1 h3f43e3d_1 + - libgettextpo-devel 0.25.1 h3f43e3d_1 + - libiconv >=1.18,<2.0a0 + - libstdcxx >=14 + license: LGPL-2.1-or-later AND GPL-3.0-or-later + size: 541357 + timestamp: 1753343006214 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gettext-tools-0.25.1-h3f43e3d_1.conda + sha256: c792729288bdd94f21f25f80802d4c66957b4e00a57f7cb20513f07aadfaff06 + md5: a59c05d22bdcbb4e984bf0c021a2a02f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + license: GPL-3.0-or-later + license_family: GPL + size: 3644103 + timestamp: 1753342966311 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran-14.3.0-h76987e4_17.conda + sha256: 99c81907e46f0a95ae18810ea8b8055d8e3b70231318d36f5ae44f9cafcaff57 + md5: 329ef645bc2f75b4025cba573810e178 + depends: + - gcc 14.3.0 h0dff253_17 + - gcc_impl_linux-64 14.3.0 hb1e0a52_17 + - gfortran_impl_linux-64 14.3.0 h1a219da_17 + license: BSD-3-Clause + license_family: BSD + size: 28712 + timestamp: 1770252415213 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran_impl_linux-64-14.3.0-h1a219da_17.conda + sha256: 04593b314f7ab8619536cdc23f3bf1e826d0b2dcf6adbf2f39932a7aec65b25a + md5: ea4724804b89ddc81d16cabe3f4719b5 + depends: + - gcc_impl_linux-64 >=14.3.0 + - libgcc >=14.3.0 + - libgfortran5 >=14.3.0 + - libstdcxx >=14.3.0 + - sysroot_linux-64 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 18360922 + timestamp: 1770252307342 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gfortran_linux-64-14.3.0-hfa02b96_21.conda + sha256: 406e1b10478b29795377cc2ad561618363aaf37b208e5cb3de7858256f73276a + md5: 234863e90d09d229043af1075fcf8204 + depends: + - gfortran_impl_linux-64 14.3.0.* + - gcc_linux-64 ==14.3.0 h298d278_21 + - binutils_linux-64 + - sysroot_linux-64 + license: BSD-3-Clause + size: 27130 + timestamp: 1770908213808 +- conda: https://conda.anaconda.org/conda-forge/linux-64/glew-2.3.0-h71661d4_0.conda + sha256: 535d152ee06e3d3015a5ab410dfea9574e1678e226fa166f859a0b9e1153e597 + md5: 7eefecda1c71c380bfc406d16e78bbee + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libgl >=1.7.0,<2.0a0 + - libglu >=9.0.3,<9.1.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext + license: BSD-3-Clause + license_family: BSD + size: 492673 + timestamp: 1766373546677 +- conda: https://conda.anaconda.org/conda-forge/linux-64/glib-2.86.3-h5192d8d_1.conda + sha256: af2965f0a4951bab26763e02dd5bb22094ddc8aa30803fc5c1d699843067ef28 + md5: aefbd04e8e6cabe1d24eb8ffa6c48fd5 + depends: + - glib-tools 2.86.3 hf516916_1 + - libglib 2.86.3 h6548e54_1 + - packaging + - python * + license: LGPL-2.1-or-later + size: 79272 + timestamp: 1770929835447 +- conda: https://conda.anaconda.org/conda-forge/linux-64/glib-tools-2.86.3-hf516916_1.conda + sha256: ee8394e3b857286ece3f61318316f06ace70e76e2224d2312cef4680400765fc + md5: 5ebd79c20c7ecf979f20e26fedc0a4fd + depends: + - __glibc >=2.17,<3.0.a0 + - libffi + - libgcc >=14 + - libglib 2.86.3 h6548e54_1 + license: LGPL-2.1-or-later + size: 214148 + timestamp: 1770929777740 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gmock-1.17.0-ha770c72_1.conda + sha256: 80ca13dc518962fcd86856586cb5fb612fe69914234eab322f9dee25f628090f + md5: 33e7a8280999b958df24a95f0cb86b1a + depends: + - gtest 1.17.0 h84d6215_1 + license: BSD-3-Clause + license_family: BSD + size: 7578 + timestamp: 1748320126956 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda + sha256: 309cf4f04fec0c31b6771a5809a1909b4b3154a2208f52351e1ada006f4c750c + md5: c94a5994ef49749880a8139cf9afcbe1 + depends: + - libgcc-ng >=12 + - libstdcxx-ng >=12 + license: GPL-2.0-or-later OR LGPL-3.0-or-later + size: 460055 + timestamp: 1718980856608 +- conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.14-hecca717_2.conda + sha256: 25ba37da5c39697a77fce2c9a15e48cf0a84f1464ad2aafbe53d8357a9f6cc8c + md5: 2cd94587f3a401ae05e03a6caf09539d + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: LGPL-2.0-or-later + license_family: LGPL + size: 99596 + timestamp: 1755102025473 +- conda: https://conda.anaconda.org/conda-forge/linux-64/graphviz-14.1.2-h8b86629_0.conda + sha256: 48d4aae8d2f7dd038b8c2b6a1b68b7bca13fa6b374b78c09fcc0757fa21234a1 + md5: 341fc61cfe8efa5c72d24db56c776f44 + depends: + - __glibc >=2.17,<3.0.a0 + - adwaita-icon-theme + - cairo >=1.18.4,<2.0a0 + - fonts-conda-ecosystem + - gdk-pixbuf >=2.44.4,<3.0a0 + - gtk3 >=3.24.43,<4.0a0 + - gts >=0.7.6,<0.8.0a0 + - libexpat >=2.7.3,<3.0a0 + - libgcc >=14 + - libgd >=2.3.3,<2.4.0a0 + - libglib >=2.86.3,<3.0a0 + - librsvg >=2.60.0,<3.0a0 + - libstdcxx >=14 + - libwebp-base >=1.6.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pango >=1.56.4,<2.0a0 + license: EPL-1.0 + license_family: Other + size: 2426455 + timestamp: 1769427102743 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gst-plugins-base-1.26.10-h0363672_0.conda + sha256: f43bc8fd2c8b0c4317cf771f2cf8a9e7eee47105c233bfed00158f6579e41340 + md5: fd9738c3189541787bd967e19587de26 + depends: + - __glibc >=2.17,<3.0.a0 + - alsa-lib >=1.2.15.1,<1.3.0a0 + - gstreamer 1.26.10 h17cb667_0 + - libdrm >=2.4.125,<2.5.0a0 + - libegl >=1.7.0,<2.0a0 + - libexpat >=2.7.3,<3.0a0 + - libgcc >=14 + - libgl >=1.7.0,<2.0a0 + - libglib >=2.86.3,<3.0a0 + - libogg >=1.3.5,<1.4.0a0 + - libopus >=1.5.2,<2.0a0 + - libpng >=1.6.53,<1.7.0a0 + - libstdcxx >=14 + - libvorbis >=1.3.7,<1.4.0a0 + - libxcb >=1.17.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pango >=1.56.4,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxau >=1.0.12,<2.0a0 + - xorg-libxdamage >=1.1.6,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxfixes >=6.0.2,<7.0a0 + - xorg-libxrender >=0.9.12,<0.10.0a0 + - xorg-libxshmfence >=1.3.3,<2.0a0 + - xorg-libxxf86vm >=1.1.6,<2.0a0 + license: LGPL-2.0-or-later + license_family: LGPL + size: 2928142 + timestamp: 1766699713774 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gstreamer-1.26.10-h17cb667_0.conda + sha256: 35044ecb0b08cd61f32b18f0c0c60f8d4aa610352eee4c5902e171a3decc0eba + md5: 0c38cdf4414540aae129822f961b5636 + depends: + - __glibc >=2.17,<3.0.a0 + - glib >=2.86.3,<3.0a0 + - libgcc >=14 + - libglib >=2.86.3,<3.0a0 + - libiconv >=1.18,<2.0a0 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + license: LGPL-2.0-or-later + license_family: LGPL + size: 2059388 + timestamp: 1766699555877 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gtest-1.17.0-h84d6215_1.conda + sha256: 1f738280f245863c5ac78bcc04bb57266357acda45661c4aa25823030c6fb5db + md5: 55e29b72a71339bc651f9975492db71f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + constrains: + - gmock 1.17.0 + license: BSD-3-Clause + license_family: BSD + size: 416610 + timestamp: 1748320117187 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gtk3-3.24.43-h993cebd_6.conda + sha256: 004688fbb2c479b200a6d85ef38c3129fcd4ce13537b7ee2371d962b372761c1 + md5: f9f33c65b20e6a61f21714785e3613ec + depends: + - __glibc >=2.17,<3.0.a0 + - at-spi2-atk >=2.38.0,<3.0a0 + - atk-1.0 >=2.38.0 + - cairo >=1.18.4,<2.0a0 + - epoxy >=1.5.10,<1.6.0a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - fribidi >=1.0.16,<2.0a0 + - gdk-pixbuf >=2.44.4,<3.0a0 + - glib-tools + - harfbuzz >=11.5.1 + - hicolor-icon-theme + - libcups >=2.3.3,<2.4.0a0 + - libcups >=2.3.3,<3.0a0 + - libexpat >=2.7.1,<3.0a0 + - libgcc >=14 + - libglib >=2.86.0,<3.0a0 + - liblzma >=5.8.1,<6.0a0 + - libxkbcommon >=1.12.2,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pango >=1.56.4,<2.0a0 + - wayland >=1.24.0,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxcomposite >=0.4.6,<1.0a0 + - xorg-libxcursor >=1.2.3,<2.0a0 + - xorg-libxdamage >=1.1.6,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxfixes >=6.0.2,<7.0a0 + - xorg-libxi >=1.8.2,<2.0a0 + - xorg-libxinerama >=1.1.5,<1.2.0a0 + - xorg-libxrandr >=1.5.4,<2.0a0 + - xorg-libxrender >=0.9.12,<0.10.0a0 + license: LGPL-2.0-or-later + license_family: LGPL + size: 5587108 + timestamp: 1761327349586 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gts-0.7.6-h977cf35_4.conda + sha256: b5cd16262fefb836f69dc26d879b6508d29f8a5c5948a966c47fe99e2e19c99b + md5: 4d8df0b0db060d33c9a702ada998a8fe + depends: + - libgcc-ng >=12 + - libglib >=2.76.3,<3.0a0 + - libstdcxx-ng >=12 + license: LGPL-2.0-or-later + license_family: LGPL + size: 318312 + timestamp: 1686545244763 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gtsam-4.2.0-py312h7f00892_14.conda + sha256: 376119758a83faf5bceea1d9737d3398e86fcdb5cdb6f571c84f12faa7ce5aa4 + md5: 5a2122dbd95cf9514e22497af8d69f0d + depends: + - __glibc >=2.17,<3.0.a0 + - geographiclib-cpp >=2.5.2,<2.6.0a0 + - libamd >=3.3.3,<4.0a0 + - libboost >=1.88.0,<1.89.0a0 + - libbtf >=2.3.2,<3.0a0 + - libcamd >=3.3.3,<4.0a0 + - libccolamd >=3.3.4,<4.0a0 + - libcholmod >=5.3.1,<6.0a0 + - libcolamd >=3.3.4,<4.0a0 + - libcxsparse >=4.4.1,<5.0a0 + - libgcc >=14 + - libklu >=2.3.5,<3.0a0 + - libldl >=3.3.2,<4.0a0 + - libparu >=1.0.0,<2.0a0 + - librbio >=4.3.4,<5.0a0 + - libspex >=3.2.3,<4.0a0 + - libspqr >=4.3.4,<5.0a0 + - libstdcxx >=14 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - libumfpack >=6.3.5,<7.0a0 + - metis >=5.1.0,<5.1.1.0a0 + - numpy >=1.23,<3 + - pyparsing + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + - suitesparse >=7.10.1,<8.0a0 + - tbb >=2021.13.0 + license: BSD-3-Clause + license_family: BSD + size: 19166117 + timestamp: 1756775626500 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-14.3.0-h76987e4_17.conda + sha256: 13280aa6d2e8313e7bf15d066d1a6767b749e8a3485116fb8744d1a3db93c279 + md5: eae8e3fb1f5eecb829dd7347d33ecacb + depends: + - gcc 14.3.0 h0dff253_17 + - gxx_impl_linux-64 14.3.0 h2185e75_17 + license: BSD-3-Clause + license_family: BSD + size: 28708 + timestamp: 1770252431123 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-14.3.0-h2185e75_17.conda + sha256: d43556d0cc5bc636ef02a21fdfc08167430846538a5a92b4ee9a0dedad13ba8f + md5: 8f02f68c780b0a6eeba034af3ed1c00a + depends: + - gcc_impl_linux-64 14.3.0 hb1e0a52_17 + - libstdcxx-devel_linux-64 14.3.0 h9f08a49_117 + - sysroot_linux-64 + - tzdata + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 15251260 + timestamp: 1770252349885 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-14.3.0-he467f4b_21.conda + sha256: 1e07c197e0779fa9105e59cd55a835ded96bfde59eb169439736a89b27b48e5d + md5: 7b51f4ff82eeb1f386bfee20a7bed3ed + depends: + - gxx_impl_linux-64 14.3.0.* + - gcc_linux-64 ==14.3.0 h298d278_21 + - binutils_linux-64 + - sysroot_linux-64 + license: BSD-3-Clause + size: 27503 + timestamp: 1770908213813 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gz-cmake3-3.5.5-h05f81b2_0.conda + sha256: b654d0102a8b8242836a5863c0157945b5c549d505383f4f8b724926a55f68aa + md5: fda2ad837ffe2ed7f73ddfab260d82e3 + depends: + - libgz-cmake3 ==3.5.5 h54a6638_0 + license: Apache-2.0 + license_family: APACHE + size: 7430 + timestamp: 1759138411890 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gz-math7-7.5.2-h5bbc156_2.conda + sha256: 3c0eeb73fb3a5d01d6e2f10778a0948286b19cf9500ae24a67547262c521ff35 + md5: 058fd7a11695871d6c26080a1b2e96a1 + depends: + - libgz-math7 ==7.5.2 h54a6638_2 + - gz-math7-python >=7.5.2,<7.5.3.0a0 + license: Apache-2.0 + license_family: APACHE + size: 8251 + timestamp: 1759147748392 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gz-math7-python-7.5.2-py312h89d136e_2.conda + sha256: a20c5d236a70831cfa21fda695c4482fcbbe64ea4c2db32d59c66ee7df05fe05 + md5: f49be6a36d1cd45f9fcc96d2446c41c4 + depends: + - libgz-math7 ==7.5.2 h54a6638_2 + - python + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - libgz-math7 >=7.5.2,<8.0a0 + - pybind11-abi ==11 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + license_family: APACHE + size: 1029585 + timestamp: 1759147748392 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gz-utils2-2.2.1-hdaf9e28_2.conda + sha256: 6b845b603451c69fe3d288e48ea6c0360f7939b713744c20125d8f769f89514b + md5: 53ba6369380613e92f3f3a82252821ea + depends: + - libgz-utils2 ==2.2.1 h54a6638_2 + license: Apache-2.0 + license_family: APACHE + size: 8042 + timestamp: 1767701472560 +- conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-12.3.2-h6083320_0.conda + sha256: 92015faf283f9c0a8109e2761042cd47ae7a4505e24af42a53bc3767cb249912 + md5: d170a70fc1d5c605fcebdf16851bd54a + depends: + - __glibc >=2.17,<3.0.a0 + - cairo >=1.18.4,<2.0a0 + - graphite2 >=1.3.14,<2.0a0 + - icu >=78.2,<79.0a0 + - libexpat >=2.7.3,<3.0a0 + - libfreetype >=2.14.1 + - libfreetype6 >=2.14.1 + - libgcc >=14 + - libglib >=2.86.3,<3.0a0 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 2035859 + timestamp: 1769445400168 +- conda: https://conda.anaconda.org/conda-forge/linux-64/hicolor-icon-theme-0.17-ha770c72_2.tar.bz2 + sha256: 336f29ceea9594f15cc8ec4c45fdc29e10796573c697ee0d57ebb7edd7e92043 + md5: bbf6f174dcd3254e19a2f5d2295ce808 + license: GPL-2.0-or-later + license_family: GPL + size: 13841 + timestamp: 1605162808667 +- conda: https://conda.anaconda.org/conda-forge/noarch/humanfriendly-10.0-pyh707e725_8.conda + sha256: fa2071da7fab758c669e78227e6094f6b3608228740808a6de5d6bce83d9e52d + md5: 7fe569c10905402ed47024fc481bb371 + depends: + - __unix + - python >=3.9 + license: MIT + license_family: MIT + size: 73563 + timestamp: 1733928021866 +- conda: https://conda.anaconda.org/conda-forge/linux-64/icu-78.2-h33c6efd_0.conda + sha256: 142a722072fa96cf16ff98eaaf641f54ab84744af81754c292cb81e0881c0329 + md5: 186a18e3ba246eccfc7cff00cd19a870 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: MIT + license_family: MIT + size: 12728445 + timestamp: 1767969922681 +- conda: https://conda.anaconda.org/conda-forge/linux-64/imath-3.2.2-hde8ca8f_0.conda + sha256: 43f30e6fd8cbe1fef59da760d1847c9ceff3fb69ceee7fd4a34538b0927959dd + md5: c427448c6f3972c76e8a4474e0fe367b + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + license: BSD-3-Clause + license_family: BSD + size: 160289 + timestamp: 1759983212466 +- conda: https://conda.anaconda.org/conda-forge/noarch/importlib-metadata-8.7.0-pyhe01879c_1.conda + sha256: c18ab120a0613ada4391b15981d86ff777b5690ca461ea7e9e49531e8f374745 + md5: 63ccfdc3a3ce25b027b8767eb722fca8 + depends: + - python >=3.9 + - zipp >=3.20 + - python + license: Apache-2.0 + license_family: APACHE + size: 34641 + timestamp: 1747934053147 +- conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda + sha256: acc1d991837c0afb67c75b77fdc72b4bf022aac71fedd8b9ea45918ac9b08a80 + md5: c85c76dc67d75619a92f51dfbce06992 + depends: + - python >=3.9 + - zipp >=3.1.0 + constrains: + - importlib-resources >=6.5.2,<6.5.3.0a0 + license: Apache-2.0 + license_family: APACHE + size: 33781 + timestamp: 1736252433366 +- conda: https://conda.anaconda.org/conda-forge/noarch/iniconfig-2.3.0-pyhd8ed1ab_0.conda + sha256: e1a9e3b1c8fe62dc3932a616c284b5d8cbe3124bbfbedcf4ce5c828cb166ee19 + md5: 9614359868482abba1bd15ce465e3c42 + depends: + - python >=3.10 + license: MIT + license_family: MIT + size: 13387 + timestamp: 1760831448842 +- conda: https://conda.anaconda.org/conda-forge/linux-64/jasper-4.2.9-he3c4edf_0.conda + sha256: cea4c90ca4971cbc29d5930301cabcc581a781fd26d0cc7ca0aa459cb33ff573 + md5: 5455c1a77c2aa337f04d94ff0ef413c3 + depends: + - __glibc >=2.17,<3.0.a0 + - freeglut >=3.2.2,<4.0a0 + - libgcc >=14 + - libglu >=9.0.3,<10.0a0 + - libglu >=9.0.3,<9.1.0a0 + - libjpeg-turbo >=3.1.2,<4.0a0 + license: JasPer-2.0 + size: 683370 + timestamp: 1772794291374 +- conda: https://conda.anaconda.org/conda-forge/linux-64/jxrlib-1.1-hd590300_3.conda + sha256: 2057ca87b313bde5b74b93b0e696f8faab69acd4cb0edebb78469f3f388040c0 + md5: 5aeabe88534ea4169d4c49998f293d6c + depends: + - libgcc-ng >=12 + license: BSD-2-Clause + license_family: BSD + size: 239104 + timestamp: 1703333860145 +- conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-4.18.0-he073ed8_9.conda + sha256: 41557eeadf641de6aeae49486cef30d02a6912d8da98585d687894afd65b356a + md5: 86d9cba083cd041bfbf242a01a7a1999 + constrains: + - sysroot_linux-64 ==2.28 + license: LGPL-2.0-or-later AND LGPL-2.0-or-later WITH exceptions AND GPL-2.0-or-later + license_family: GPL + size: 1278712 + timestamp: 1765578681495 +- conda: https://conda.anaconda.org/conda-forge/linux-64/keyutils-1.6.3-hb9d3cd8_0.conda + sha256: 0960d06048a7185d3542d850986d807c6e37ca2e644342dd0c72feefcf26c2a4 + md5: b38117a3c920364aff79f870c984b4a3 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: LGPL-2.1-or-later + size: 134088 + timestamp: 1754905959823 +- conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda + sha256: 99df692f7a8a5c27cd14b5fb1374ee55e756631b9c3d659ed3ee60830249b238 + md5: 3f43953b7d3fb3aaa1d0d0723d91e368 + depends: + - keyutils >=1.6.1,<2.0a0 + - libedit >=3.1.20191231,<3.2.0a0 + - libedit >=3.1.20191231,<4.0a0 + - libgcc-ng >=12 + - libstdcxx-ng >=12 + - openssl >=3.3.1,<4.0a0 + license: MIT + license_family: MIT + size: 1370023 + timestamp: 1719463201255 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lame-3.100-h166bdaf_1003.tar.bz2 + sha256: aad2a703b9d7b038c0f745b853c6bb5f122988fe1a7a096e0e606d9cbec4eaab + md5: a8832b479f93521a9e7b5b743803be51 + depends: + - libgcc-ng >=12 + license: LGPL-2.0-only + license_family: LGPL + size: 508258 + timestamp: 1664996250081 +- conda: https://conda.anaconda.org/conda-forge/noarch/lark-parser-0.12.0-pyhd8ed1ab_1.conda + sha256: 7f1ad9630a87005a90099ad3ff883ac7a3fe5e85b9eb232d1f8ad0a670059cca + md5: 222dd97cb2d5da1638de5077da60712f + depends: + - python >=3.6 + license: MIT + license_family: MIT + size: 86134 + timestamp: 1725742423890 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.18-h0c24ade_0.conda + sha256: 836ec4b895352110335b9fdcfa83a8dcdbe6c5fb7c06c4929130600caea91c0a + md5: 6f2e2c8f58160147c4d1c6f4c14cbac4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libjpeg-turbo >=3.1.2,<4.0a0 + - libtiff >=4.7.1,<4.8.0a0 + license: MIT + license_family: MIT + size: 249959 + timestamp: 1768184673131 +- conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.45.1-default_hbd61a6d_101.conda + sha256: 565941ac1f8b0d2f2e8f02827cbca648f4d18cd461afc31f15604cd291b5c5f3 + md5: 12bd9a3f089ee6c9266a37dab82afabd + depends: + - __glibc >=2.17,<3.0.a0 + - zstd >=1.5.7,<1.6.0a0 + constrains: + - binutils_impl_linux-64 2.45.1 + license: GPL-3.0-only + license_family: GPL + size: 725507 + timestamp: 1770267139900 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda + sha256: 412381a43d5ff9bbed82cd52a0bbca5b90623f62e41007c9c42d3870c60945ff + md5: 9344155d33912347b37f0ae6c410a835 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: Apache-2.0 + license_family: Apache + size: 264243 + timestamp: 1745264221534 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libacl-2.3.2-h0f662aa_0.conda + sha256: 1b704cf161c6f84658a7ac534555ef365ec982f23576b1c4ae4cac4baeb61685 + md5: ef8039969013acacf5b741092aef2ee7 + depends: + - attr >=2.5.1,<2.6.0a0 + - libgcc-ng >=12 + license: GPL-2.0-or-later + license_family: GPL + size: 110600 + timestamp: 1706132570609 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libamd-3.3.3-h456b2da_7100101.conda + sha256: 5fc32a5497c9919ffde729a604b0acfa97c403ce5b2b27b28ca261cf0c4643aa + md5: a067596d679bcde85375143e7c374738 + depends: + - __glibc >=2.17,<3.0.a0 + - libgfortran5 >=13.3.0 + - libgfortran + - libgcc >=13 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: BSD-3-Clause + license_family: BSD + size: 48250 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libasprintf-0.25.1-h3f43e3d_1.conda + sha256: cb728a2a95557bb6a5184be2b8be83a6f2083000d0c7eff4ad5bbe5792133541 + md5: 3b0d184bc9404516d418d4509e418bdc + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: LGPL-2.1-or-later + size: 53582 + timestamp: 1753342901341 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libasprintf-devel-0.25.1-h3f43e3d_1.conda + sha256: 2fc95060efc3d76547b7872875af0b7212d4b1407165be11c5f830aeeb57fc3a + md5: fd9cf4a11d07f0ef3e44fc061611b1ed + depends: + - __glibc >=2.17,<3.0.a0 + - libasprintf 0.25.1 h3f43e3d_1 + - libgcc >=14 + license: LGPL-2.1-or-later + size: 34734 + timestamp: 1753342921605 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.11.0-5_h4a7cf45_openblas.conda + build_number: 5 + sha256: 18c72545080b86739352482ba14ba2c4815e19e26a7417ca21a95b76ec8da24c + md5: c160954f7418d7b6e87eaf05a8913fa9 + depends: + - libopenblas >=0.3.30,<0.3.31.0a0 + - libopenblas >=0.3.30,<1.0a0 + constrains: + - mkl <2026 + - liblapack 3.11.0 5*_openblas + - libcblas 3.11.0 5*_openblas + - blas 2.305 openblas + - liblapacke 3.11.0 5*_openblas + license: BSD-3-Clause + license_family: BSD + size: 18213 + timestamp: 1765818813880 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.88.0-hd24cca6_7.conda + sha256: dd489228e1916c7720c925248d0ba12803d1dc8b9898be0c51f4ab37bab6ffa5 + md5: d70e4dc6a847d437387d45462fe60cf9 + depends: + - __glibc >=2.17,<3.0.a0 + - bzip2 >=1.0.8,<2.0a0 + - icu >=78.1,<79.0a0 + - libgcc >=14 + - liblzma >=5.8.1,<6.0a0 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + constrains: + - boost-cpp <0.0a0 + license: BSL-1.0 + size: 3072984 + timestamp: 1766347479317 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.88.0-hfcd1e18_7.conda + sha256: 249e7a58aee14a619d4f6bca3ad955b7a0a84aad6ab201f734bb21ea16e654e6 + md5: 97ac87592030b16fa193c877538be3d5 + depends: + - libboost 1.88.0 hd24cca6_7 + - libboost-headers 1.88.0 ha770c72_7 + constrains: + - boost-cpp <0.0a0 + license: BSL-1.0 + size: 40112 + timestamp: 1766347628036 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-headers-1.88.0-ha770c72_7.conda + sha256: 88194078f2de6b68c40563871ccf638fd48cd1cf1d203ac4e653cee9cedd31a6 + md5: d9011bcea61514b510209b882a459a57 + constrains: + - boost-cpp <0.0a0 + license: BSL-1.0 + size: 14584021 + timestamp: 1766347497416 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-python-1.88.0-py312hf890105_7.conda + sha256: 53983b23517b668eae8a8db06bd47765c6fb33d65947222925462bdc43a87686 + md5: e7b252a7225110779b7e1df8d01ac9a0 + depends: + - __glibc >=2.17,<3.0.a0 + - libboost 1.88.0 hd24cca6_7 + - libgcc >=14 + - libstdcxx >=14 + - numpy >=1.23,<3 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + constrains: + - py-boost <0.0a0 + - boost <0.0a0 + license: BSL-1.0 + size: 130172 + timestamp: 1766347836920 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-python-devel-1.88.0-py312h26dfbe5_7.conda + sha256: bbf92788225d7aec6e13678cb1cb812b3336aaf4a812ab09739cb0495504b3bd + md5: f541dd78a5952bff51acd5b7b9e53acf + depends: + - libboost-devel 1.88.0 hfcd1e18_7 + - libboost-python 1.88.0 py312hf890105_7 + - numpy >=1.23,<3 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + constrains: + - py-boost <0.0a0 + - boost <0.0a0 + license: BSL-1.0 + size: 18972 + timestamp: 1766348204323 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libbtf-2.3.2-hf02c80a_7100101.conda + sha256: fe36f414f48ab87251f02aeef1fcbb6f3929322316842dada0f8142db2710264 + md5: 6f4aec52002defbdf3e24eb79e56a209 + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: LGPL-2.1-or-later + size: 26913 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcamd-3.3.3-hf02c80a_7100101.conda + sha256: 16e9ae4e173a8606b0b8be118dbdcf4e03c9dd9777eea6bf9dff4397133d0d06 + md5: 1c9d1532caadece8adc2d14c6d4fc726 + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: BSD-3-Clause + license_family: BSD + size: 44119 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcap-2.77-h3ff7636_0.conda + sha256: 9517cce5193144af0fcbf19b7bd67db0a329c2cc2618f28ffecaa921a1cbe9d3 + md5: 09c264d40c67b82b49a3f3b89037bd2e + depends: + - __glibc >=2.17,<3.0.a0 + - attr >=2.5.2,<2.6.0a0 + - libgcc >=14 + license: BSD-3-Clause + license_family: BSD + size: 121429 + timestamp: 1762349484074 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.11.0-5_h0358290_openblas.conda + build_number: 5 + sha256: 0cbdcc67901e02dc17f1d19e1f9170610bd828100dc207de4d5b6b8ad1ae7ad8 + md5: 6636a2b6f1a87572df2970d3ebc87cc0 + depends: + - libblas 3.11.0 5_h4a7cf45_openblas + constrains: + - liblapacke 3.11.0 5*_openblas + - blas 2.305 openblas + - liblapack 3.11.0 5*_openblas + license: BSD-3-Clause + license_family: BSD + size: 18194 + timestamp: 1765818837135 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libccolamd-3.3.4-hf02c80a_7100101.conda + sha256: cc90aa5e0ad1f7ae9a29d9a42aacd7f7f02aba0bf5467513bfda7e6b18a4cbc8 + md5: e5107e02dc4c2f9f41eef72d72c23517 + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: BSD-3-Clause + license_family: BSD + size: 41578 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcholmod-5.3.1-h9cf07ce_7100101.conda + sha256: 69540315b4b8de93b383243334151ed19e98968baaa59440ba645a3bff68d765 + md5: f51e24ce110ae24c92074736a308e47e + depends: + - libgcc >=13 + - libstdcxx >=13 + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + - liblapack >=3.9.0,<4.0a0 + - libcolamd >=3.3.4,<4.0a0 + - libamd >=3.3.3,<4.0a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - libccolamd >=3.3.4,<4.0a0 + - libblas >=3.9.0,<4.0a0 + - libcamd >=3.3.3,<4.0a0 + license: LGPL-2.1-or-later AND GPL-2.0-or-later AND Apache-2.0 + size: 990886 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp21.1-21.1.8-default_h99862b1_3.conda + sha256: de512ce246faec2d4f7766774769921a85b5aa053a74abd2f8c97ad50b393aac + md5: 24a2802074d26aecfdbc9b3f1d8168d1 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libllvm21 >=21.1.8,<21.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 21066639 + timestamp: 1770190428756 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp22.1-22.1.0-default_h99862b1_0.conda + sha256: 914da94dbf829192b2bb360a7684b32e46f047a57de96a2f5ab39a011aeae6ea + md5: d966a23335e090a5410cc4f0dec8d00a + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 21661249 + timestamp: 1772101075353 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-22.1.0-default_h746c552_0.conda + sha256: 4a9dd814492a129f2ff40cd4ab0b942232c9e3c6dbc0d0aaf861f1f65e99cc7d + md5: 140459a7413d8f6884eb68205ce39a0d + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libllvm22 >=22.1.0,<22.2.0a0 + - libstdcxx >=14 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 12817500 + timestamp: 1772101411287 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcolamd-3.3.4-hf02c80a_7100101.conda + sha256: 00d1b976b914f0c20ae6f81f4e4713fa87717542eba8757b9a3c9e8abcc29858 + md5: 56d4c5542887e8955f21f8546ad75d9d + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: BSD-3-Clause + license_family: BSD + size: 33160 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcompiler-rt-22.1.0-hb700be7_0.conda + sha256: a80eb63faa09b9e091922e805a5d6bd8e3531948d9bbe09b841c0f84f058bf00 + md5: a5c4f5f06ed7db43eb32bbc80ce28300 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + constrains: + - compiler-rt >=9.0.1 + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 10658616 + timestamp: 1772021015681 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-hb8b1518_5.conda + sha256: cb83980c57e311783ee831832eb2c20ecb41e7dee6e86e8b70b8cef0e43eab55 + md5: d4a250da4737ee127fb1fa6452a9002e + depends: + - __glibc >=2.17,<3.0.a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - libstdcxx >=13 + - libzlib >=1.3.1,<2.0a0 + license: Apache-2.0 + license_family: Apache + size: 4523621 + timestamp: 1749905341688 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.18.0-h4e3cde8_0.conda + sha256: 5454709d9fb6e9c3dd6423bc284fa7835a7823bfa8323f6e8786cdd555101fab + md5: 0a5563efed19ca4461cf927419b6eb73 + depends: + - __glibc >=2.17,<3.0.a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=14 + - libnghttp2 >=1.67.0,<2.0a0 + - libssh2 >=1.11.1,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.4,<4.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: curl + license_family: MIT + size: 462942 + timestamp: 1767821743793 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcxsparse-4.4.1-hf02c80a_7100101.conda + sha256: ab40fc8a4662f550d053576a56db896247bc81eb291eff3811f24c231829e3dd + md5: 917931d508582ef891bbac172294d9fb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - _openmp_mutex >=4.5 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: LGPL-2.1-or-later + size: 113979 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.25-h17f619e_0.conda + sha256: aa8e8c4be9a2e81610ddf574e05b64ee131fab5e0e3693210c9d6d2fba32c680 + md5: 6c77a605a7a689d17d4819c0f8ac9a00 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 73490 + timestamp: 1761979956660 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.125-hb03c661_1.conda + sha256: c076a213bd3676cc1ef22eeff91588826273513ccc6040d9bea68bccdc849501 + md5: 9314bc5a1fe7d1044dc9dfd3ef400535 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libpciaccess >=0.18,<0.19.0a0 + license: MIT + license_family: MIT + size: 310785 + timestamp: 1757212153962 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda + sha256: d789471216e7aba3c184cd054ed61ce3f6dac6f87a50ec69291b9297f8c18724 + md5: c277e0a4d549b03ac1e9d6cbbe3d017b + depends: + - ncurses + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - ncurses >=6.5,<7.0a0 + license: BSD-2-Clause + license_family: BSD + size: 134676 + timestamp: 1738479519902 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda + sha256: 7fd5408d359d05a969133e47af580183fbf38e2235b562193d427bb9dad79723 + md5: c151d5eb730e9b7480e6d48c0fc44048 + depends: + - __glibc >=2.17,<3.0.a0 + - libglvnd 1.7.0 ha4b6fd6_2 + license: LicenseRef-libglvnd + size: 44840 + timestamp: 1731330973553 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-devel-1.7.0-ha4b6fd6_2.conda + sha256: f6e7095260305dc05238062142fb8db4b940346329b5b54894a90610afa6749f + md5: b513eb83b3137eca1192c34bf4f013a7 + depends: + - __glibc >=2.17,<3.0.a0 + - libegl 1.7.0 ha4b6fd6_2 + - libgl-devel 1.7.0 ha4b6fd6_2 + - xorg-libx11 + license: LicenseRef-libglvnd + size: 30380 + timestamp: 1731331017249 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda + sha256: 1cd6048169fa0395af74ed5d8f1716e22c19a81a8a36f934c110ca3ad4dd27b4 + md5: 172bf1cd1ff8629f2b1179945ed45055 + depends: + - libgcc-ng >=12 + license: BSD-2-Clause + license_family: BSD + size: 112766 + timestamp: 1702146165126 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libevent-2.1.12-hf998b51_1.conda + sha256: 2e14399d81fb348e9d231a82ca4d816bf855206923759b69ad006ba482764131 + md5: a1cfcc585f0c42bf8d5546bb1dfb668d + depends: + - libgcc-ng >=12 + - openssl >=3.1.1,<4.0a0 + license: BSD-3-Clause + license_family: BSD + size: 427426 + timestamp: 1685725977222 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.3-hecca717_0.conda + sha256: 1e1b08f6211629cbc2efe7a5bca5953f8f6b3cae0eeb04ca4dacee1bd4e2db2f + md5: 8b09ae86839581147ef2e5c5e229d164 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + constrains: + - expat 2.7.3.* + license: MIT + license_family: MIT + size: 76643 + timestamp: 1763549731408 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.5.2-h3435931_0.conda + sha256: 31f19b6a88ce40ebc0d5a992c131f57d919f73c0b92cd1617a5bec83f6e961e6 + md5: a360c33a5abe61c07959e449fa1453eb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 58592 + timestamp: 1769456073053 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libflac-1.5.0-he200343_1.conda + sha256: e755e234236bdda3d265ae82e5b0581d259a9279e3e5b31d745dc43251ad64fb + md5: 47595b9d53054907a00d95e4d47af1d6 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + - libogg >=1.3.5,<1.4.0a0 + - libstdcxx >=14 + license: BSD-3-Clause + license_family: BSD + size: 424563 + timestamp: 1764526740626 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.14.1-ha770c72_0.conda + sha256: 4641d37faeb97cf8a121efafd6afd040904d4bca8c46798122f417c31d5dfbec + md5: f4084e4e6577797150f9b04a4560ceb0 + depends: + - libfreetype6 >=2.14.1 + license: GPL-2.0-only OR FTL + size: 7664 + timestamp: 1757945417134 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.14.1-h73754d4_0.conda + sha256: 4a7af818a3179fafb6c91111752954e29d3a2a950259c14a2fc7ba40a8b03652 + md5: 8e7251989bca326a28f4a5ffbd74557a + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libpng >=1.6.50,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + constrains: + - freetype >=2.14.1 + license: GPL-2.0-only OR FTL + size: 386739 + timestamp: 1757945416744 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-15.2.0-he0feb66_17.conda + sha256: 43860222cf3abf04ded0cf24541a105aa388e0e1d4d6ca46258e186d4e87ae3e + md5: 3c281169ea25b987311400d7a7e28445 + depends: + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + constrains: + - libgcc-ng ==15.2.0=*_17 + - libgomp 15.2.0 he0feb66_17 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 1040478 + timestamp: 1770252533873 +- conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-14.3.0-hf649bbc_117.conda + sha256: 57ef92396b4dc06c5a34792c0f601bc49793a963712e8419d5f03cb4ff87729f + md5: 50d5470d29a25808d108d3917426d24b + depends: + - __unix + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 3081070 + timestamp: 1770251857403 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-15.2.0-h69a702a_17.conda + sha256: bdfe50501e4a2d904a5eae65a7ae26e2b7a29b473ab084ad55d96080b966502e + md5: 1478bfa85224a65ab096d69ffd2af1e5 + depends: + - libgcc 15.2.0 he0feb66_17 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 27541 + timestamp: 1770252546553 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgd-2.3.3-h5fbf134_12.conda + sha256: 245be793e831170504f36213134f4c24eedaf39e634679809fd5391ad214480b + md5: 88c1c66987cd52a712eea89c27104be6 + depends: + - __glibc >=2.17,<3.0.a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - icu >=78.1,<79.0a0 + - libexpat >=2.7.3,<3.0a0 + - libfreetype >=2.14.1 + - libfreetype6 >=2.14.1 + - libgcc >=14 + - libjpeg-turbo >=3.1.2,<4.0a0 + - libpng >=1.6.53,<1.7.0a0 + - libtiff >=4.7.1,<4.8.0a0 + - libwebp-base >=1.6.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + license: GD + license_family: BSD + size: 177306 + timestamp: 1766331805898 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgettextpo-0.25.1-h3f43e3d_1.conda + sha256: 50a9e9815cf3f5bce1b8c5161c0899cc5b6c6052d6d73a4c27f749119e607100 + md5: 2f4de899028319b27eb7a4023be5dfd2 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + license: GPL-3.0-or-later + license_family: GPL + size: 188293 + timestamp: 1753342911214 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgettextpo-devel-0.25.1-h3f43e3d_1.conda + sha256: c7ea10326fd450a2a21955987db09dde78c99956a91f6f05386756a7bfe7cc04 + md5: 3f7a43b3160ec0345c9535a9f0d7908e + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libgettextpo 0.25.1 h3f43e3d_1 + - libiconv >=1.18,<2.0a0 + license: GPL-3.0-or-later + license_family: GPL + size: 37407 + timestamp: 1753342931100 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-15.2.0-h69a702a_17.conda + sha256: 1604c083dd65bc91e68b6cfe32c8610395088cb96af1acaf71f0dcaf83ac58f7 + md5: a6c682ac611cb1fa4d73478f9e6efb06 + depends: + - libgfortran5 15.2.0 h68bc16d_17 + constrains: + - libgfortran-ng ==15.2.0=*_17 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 27515 + timestamp: 1770252591906 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-15.2.0-h68bc16d_17.conda + sha256: b1c77b85da9a3e204de986f59e262268805c6a35dffdf3953f1b98407db2aef3 + md5: 202fdf8cad9eea704c2b0d823d1732bf + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=15.2.0 + constrains: + - libgfortran 15.2.0 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 2480824 + timestamp: 1770252563579 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda + sha256: dc2752241fa3d9e40ce552c1942d0a4b5eeb93740c9723873f6fcf8d39ef8d2d + md5: 928b8be80851f5d8ffb016f9c81dae7a + depends: + - __glibc >=2.17,<3.0.a0 + - libglvnd 1.7.0 ha4b6fd6_2 + - libglx 1.7.0 ha4b6fd6_2 + license: LicenseRef-libglvnd + size: 134712 + timestamp: 1731330998354 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-devel-1.7.0-ha4b6fd6_2.conda + sha256: e281356c0975751f478c53e14f3efea6cd1e23c3069406d10708d6c409525260 + md5: 53e7cbb2beb03d69a478631e23e340e9 + depends: + - __glibc >=2.17,<3.0.a0 + - libgl 1.7.0 ha4b6fd6_2 + - libglx-devel 1.7.0 ha4b6fd6_2 + license: LicenseRef-libglvnd + size: 113911 + timestamp: 1731331012126 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.86.3-h6548e54_1.conda + sha256: cf44d4ae071b524b1e1bbd0eb9bc428715b41c735a6cdce97ec6f813160dcedc + md5: 5b5846bc2b23e07a1d61b89dcb67fcf0 + depends: + - __glibc >=2.17,<3.0.a0 + - libffi >=3.5.2,<3.6.0a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pcre2 >=10.47,<10.48.0a0 + constrains: + - glib 2.86.3 *_1 + license: LGPL-2.1-or-later + size: 4368329 + timestamp: 1770929706446 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglu-9.0.3-h5888daf_1.conda + sha256: a0105eb88f76073bbb30169312e797ed5449ebb4e964a756104d6e54633d17ef + md5: 8422fcc9e5e172c91e99aef703b3ce65 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libopengl >=1.7.0,<2.0a0 + - libstdcxx >=13 + license: SGI-B-2.0 + size: 325262 + timestamp: 1748692137626 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda + sha256: 1175f8a7a0c68b7f81962699751bb6574e6f07db4c9f72825f978e3016f46850 + md5: 434ca7e50e40f4918ab701e3facd59a0 + depends: + - __glibc >=2.17,<3.0.a0 + license: LicenseRef-libglvnd + size: 132463 + timestamp: 1731330968309 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda + sha256: 2d35a679624a93ce5b3e9dd301fff92343db609b79f0363e6d0ceb3a6478bfa7 + md5: c8013e438185f33b13814c5c488acd5c + depends: + - __glibc >=2.17,<3.0.a0 + - libglvnd 1.7.0 ha4b6fd6_2 + - xorg-libx11 >=1.8.10,<2.0a0 + license: LicenseRef-libglvnd + size: 75504 + timestamp: 1731330988898 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-devel-1.7.0-ha4b6fd6_2.conda + sha256: 0a930e0148ab6e61089bbcdba25a2e17ee383e7de82e7af10cc5c12c82c580f3 + md5: 27ac5ae872a21375d980bd4a6f99edf3 + depends: + - __glibc >=2.17,<3.0.a0 + - libglx 1.7.0 ha4b6fd6_2 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-xorgproto + license: LicenseRef-libglvnd + size: 26388 + timestamp: 1731331003255 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-15.2.0-he0feb66_17.conda + sha256: b961b5dd9761907a7179678b58a69bb4fc16b940eb477f635aea3aec0a3f17a6 + md5: 51b78c6a757575c0d12f4401ffc67029 + depends: + - __glibc >=2.17,<3.0.a0 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 603334 + timestamp: 1770252441199 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-cmake3-3.5.5-h54a6638_0.conda + sha256: 6092ccfec5a52200a2dd5cfa33f67e7c75d473dbb1673baf145a56456589196f + md5: 046a934130154ef383da67712d179235 + depends: + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: Apache-2.0 + license_family: APACHE + size: 217564 + timestamp: 1759138411890 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-cmake4-4.2.0-h54a6638_1.conda + sha256: f306eba52c454fab2d6435959fda20a9d9062c86e918a79edd2afd2a82885f9c + md5: c6600ee72e2cadd45348bc7b99e8f736 + depends: + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: Apache-2.0 + license_family: APACHE + size: 217934 + timestamp: 1759138566319 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-math7-7.5.2-h54a6638_2.conda + sha256: fce7eb4797a025c4c61f9502372801bba87ffddc39c68dfbd09f25f30e282c45 + md5: 27dd93bf04ea4699afedf5ec38758c55 + depends: + - eigen + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - libgz-cmake4 >=4.2.0,<5.0a0 + - libgz-utils2 >=2.2.1,<3.0a0 + license: Apache-2.0 + license_family: APACHE + size: 295819 + timestamp: 1759147748392 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libgz-utils2-2.2.1-h54a6638_2.conda + sha256: 65ae6597a3f6dc7417ee0d3b57545981e52fe9ae0ff2b90d39c00b5ecabd9267 + md5: c1a605a5e876df49423df3699633dcfb + depends: + - cli11 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgz-cmake3 >=3.5.5,<4.0a0 + license: Apache-2.0 + license_family: APACHE + size: 63479 + timestamp: 1767701472558 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libhwloc-2.12.2-default_hafda6a7_1000.conda + sha256: 2cf160794dda62cf93539adf16d26cfd31092829f2a2757dbdd562984c1b110a + md5: 0ed3aa3e3e6bc85050d38881673a692f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libxml2 + - libxml2-16 >=2.14.6 + license: BSD-3-Clause + license_family: BSD + size: 2449916 + timestamp: 1765103845133 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h3b78370_2.conda + sha256: c467851a7312765447155e071752d7bf9bf44d610a5687e32706f480aad2833f + md5: 915f5995e94f60e9a4826e0b0920ee88 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: LGPL-2.1-only + size: 790176 + timestamp: 1754908768807 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.2-hb03c661_0.conda + sha256: cc9aba923eea0af8e30e0f94f2ad7156e2984d80d1e8e7fe6be5a1f257f0eb32 + md5: 8397539e3a0bbd1695584fb4f927485a + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + constrains: + - jpeg <0.0.0a + license: IJG AND BSD-3-Clause AND Zlib + size: 633710 + timestamp: 1762094827865 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libklu-2.3.5-h95ff59c_7100101.conda + sha256: 6b4d462642c240dc3671af74f7705b23f34eea0f71e0d9dbcf14b4ed008311ff + md5: efaa5e7dc6989363585fbb591480b256 + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + - metis >=5.1.0,<5.1.1.0a0 + - libcamd >=3.3.3,<4.0a0 + - liblapack >=3.9.0,<4.0a0 + - libcblas >=3.9.0,<4.0a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - libcolamd >=3.3.4,<4.0a0 + - libamd >=3.3.3,<4.0a0 + - libcholmod >=5.3.1,<6.0a0 + - libblas >=3.9.0,<4.0a0 + - libbtf >=2.3.2,<3.0a0 + - libccolamd >=3.3.4,<4.0a0 + license: LGPL-2.1-or-later + size: 131775 + timestamp: 1741963824816 +- conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.11.0-5_h47877c9_openblas.conda + build_number: 5 + sha256: c723b6599fcd4c6c75dee728359ef418307280fa3e2ee376e14e85e5bbdda053 + md5: b38076eb5c8e40d0106beda6f95d7609 + depends: + - libblas 3.11.0 5_h4a7cf45_openblas + constrains: + - blas 2.305 openblas + - liblapacke 3.11.0 5*_openblas + - libcblas 3.11.0 5*_openblas + license: BSD-3-Clause + license_family: BSD + size: 18200 + timestamp: 1765818857876 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libldl-3.3.2-hf02c80a_7100101.conda + sha256: 590232cd302047023ab31b80458833a71b10aeabee7474304dc65db322b5cd70 + md5: 19b71122fea7f6b1c4815f385b2da419 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: LGPL-2.1-or-later + size: 23391 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm21-21.1.8-hf7376ad_0.conda + sha256: 91bb4f5be1601b40b4995911d785e29387970f0b3c80f33f7f9028f95335399f + md5: 1a2708a460884d6861425b7f9a7bef99 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libxml2 + - libxml2-16 >=2.14.6 + - libzlib >=1.3.1,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 44333366 + timestamp: 1765959132513 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm22-22.1.0-hf7376ad_0.conda + sha256: 2efe1d8060c6afeb2df037fc61c182fb84e10f49cdbd29ed672e112d4d4ce2d7 + md5: 213f51bbcce2964ff2ec00d0fdd38541 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libxml2 + - libxml2-16 >=2.14.6 + - libzlib >=1.3.1,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 44236214 + timestamp: 1772009776202 +- conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.2-hb03c661_0.conda + sha256: 755c55ebab181d678c12e49cced893598f2bab22d582fbbf4d8b83c18be207eb + md5: c7c83eecbb72d88b940c249af56c8b17 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + constrains: + - xz 5.8.2.* + license: 0BSD + size: 113207 + timestamp: 1768752626120 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.67.0-had1ee68_0.conda + sha256: a4a7dab8db4dc81c736e9a9b42bdfd97b087816e029e221380511960ac46c690 + md5: b499ce4b026493a13774bcf0f4c33849 + depends: + - __glibc >=2.17,<3.0.a0 + - c-ares >=1.34.5,<2.0a0 + - libev >=4.33,<4.34.0a0 + - libev >=4.33,<5.0a0 + - libgcc >=14 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.2,<4.0a0 + license: MIT + license_family: MIT + size: 666600 + timestamp: 1756834976695 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hb9d3cd8_1.conda + sha256: 927fe72b054277cde6cb82597d0fcf6baf127dcbce2e0a9d8925a68f1265eef5 + md5: d864d34357c3b65a4b731f78c0801dc4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: LGPL-2.1-only + license_family: GPL + size: 33731 + timestamp: 1750274110928 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda + sha256: 3b3f19ced060013c2dd99d9d46403be6d319d4601814c772a3472fe2955612b0 + md5: 7c7927b404672409d9917d49bff5f2d6 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: LGPL-2.1-or-later + size: 33418 + timestamp: 1734670021371 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libogg-1.3.5-hd0c01bc_1.conda + sha256: ffb066ddf2e76953f92e06677021c73c85536098f1c21fcd15360dbc859e22e4 + md5: 68e52064ed3897463c0e958ab5c8f91b + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + license: BSD-3-Clause + license_family: BSD + size: 218500 + timestamp: 1745825989535 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libopenblas-0.3.30-pthreads_h94d23a6_4.conda + sha256: 199d79c237afb0d4780ccd2fbf829cea80743df60df4705202558675e07dd2c5 + md5: be43915efc66345cccb3c310b6ed0374 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libgfortran + - libgfortran5 >=14.3.0 + constrains: + - openblas >=0.3.30,<0.3.31.0a0 + license: BSD-3-Clause + license_family: BSD + size: 5927939 + timestamp: 1763114673331 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda + sha256: 215086c108d80349e96051ad14131b751d17af3ed2cb5a34edd62fa89bfe8ead + md5: 7df50d44d4a14d6c31a2c54f2cd92157 + depends: + - __glibc >=2.17,<3.0.a0 + - libglvnd 1.7.0 ha4b6fd6_2 + license: LicenseRef-libglvnd + size: 50757 + timestamp: 1731330993524 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-devel-1.7.0-ha4b6fd6_2.conda + sha256: b347798eba61ce8d7a65372cf0cf6066c328e5717ab69ae251c6822e6f664f23 + md5: 75b039b1e51525f4572f828be8441970 + depends: + - __glibc >=2.17,<3.0.a0 + - libopengl 1.7.0 ha4b6fd6_2 + license: LicenseRef-libglvnd + size: 15460 + timestamp: 1731331007610 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libopus-1.6.1-h280c20c_0.conda + sha256: f1061a26213b9653bbb8372bfa3f291787ca091a9a3060a10df4d5297aad74fd + md5: 2446ac1fe030c2aa6141386c1f5a6aed + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: BSD-3-Clause + license_family: BSD + size: 324993 + timestamp: 1768497114401 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libparu-1.0.0-hc6afc67_7100101.conda + sha256: 50144e87b95d1309d2043aa5bf02035b948b1ae9ec6ec44ee97b7aec1cccd70a + md5: fd1d3e26c1b12c70f7449369ae3d9c1a + depends: + - libgcc >=13 + - libstdcxx >=13 + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - libblas >=3.9.0,<4.0a0 + - libumfpack >=6.3.5,<7.0a0 + license: GPL-3.0-or-later + license_family: GPL + size: 89738 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hb9d3cd8_0.conda + sha256: 0bd91de9b447a2991e666f284ae8c722ffb1d84acb594dbd0c031bd656fa32b2 + md5: 70e3400cbbfa03e96dcde7fc13e38c7b + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 28424 + timestamp: 1749901812541 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.55-h421ea60_0.conda + sha256: 36ade759122cdf0f16e2a2562a19746d96cf9c863ffaa812f2f5071ebbe9c03c + md5: 5f13ffc7d30ffec87864e678df9957b4 + depends: + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libzlib >=1.3.1,<2.0a0 + license: zlib-acknowledgement + size: 317669 + timestamp: 1770691470744 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-18.2-hb80d175_0.conda + sha256: 5f857281d53334f1a400afae7ae915161eb8f796ddadb11c082839a4c47de6da + md5: fa63c385ddb50957d93bdb394e355be8 + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=78.2,<79.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=14 + - openldap >=2.6.10,<2.7.0a0 + - openssl >=3.5.5,<4.0a0 + license: PostgreSQL + size: 2809023 + timestamp: 1770915404394 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libraw-0.21.5-h074291d_0.conda + sha256: 7b11ab45e471ba77eab1a21872be3dce8cc81edc2500cd782a6ff49816bce6d4 + md5: c307c91b10217c31fc9d8e18cd58dc64 + depends: + - libgcc >=14 + - libstdcxx >=14 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + - libjpeg-turbo >=3.1.2,<4.0a0 + - libzlib >=1.3.1,<2.0a0 + - lcms2 >=2.18,<3.0a0 + - jasper >=4.2.8,<5.0a0 + license: LGPL-2.1-only + size: 705016 + timestamp: 1768379154800 +- conda: https://conda.anaconda.org/conda-forge/linux-64/librbio-4.3.4-hf02c80a_7100101.conda + sha256: c502b4203cc0d38f49005994b5c80c89660bcd40ff170c529cda90827ec6b1f4 + md5: 4b3a3d711d1c1f76f7f440e51458f512 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: GPL-2.0-or-later + license_family: GPL + size: 46633 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/librsvg-2.60.0-h61e6d4b_0.conda + sha256: 960b137673b2b8293e2a12d194add72967b3bf12fcdf691e7ad8bd5c8318cec3 + md5: 91e6d4d684e237fba31b9815c4b40edf + depends: + - __glibc >=2.17,<3.0.a0 + - cairo >=1.18.4,<2.0a0 + - gdk-pixbuf >=2.44.3,<3.0a0 + - libgcc >=14 + - libglib >=2.86.0,<3.0a0 + - libxml2-16 >=2.14.6 + - pango >=1.56.4,<2.0a0 + constrains: + - __glibc >=2.17 + license: LGPL-2.1-or-later + size: 3421977 + timestamp: 1759327942156 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-14.3.0-h8f1669f_17.conda + sha256: 48a1e008a44b7d630f1243915261628d72df1c1f477f44af2e93350937b496df + md5: 5edfb6baf1af52fa7c0a7072a42d1558 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14.3.0 + - libstdcxx >=14.3.0 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 7237991 + timestamp: 1770252070009 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsndfile-1.2.2-hc7d488a_2.conda + sha256: 57cb5f92110324c04498b96563211a1bca6a74b2918b1e8df578bfed03cc32e4 + md5: 067590f061c9f6ea7e61e3b2112ed6b3 + depends: + - __glibc >=2.17,<3.0.a0 + - lame >=3.100,<3.101.0a0 + - libflac >=1.5.0,<1.6.0a0 + - libgcc >=14 + - libogg >=1.3.5,<1.4.0a0 + - libopus >=1.5.2,<2.0a0 + - libstdcxx >=14 + - libvorbis >=1.3.7,<1.4.0a0 + - mpg123 >=1.32.9,<1.33.0a0 + license: LGPL-2.1-or-later + license_family: LGPL + size: 355619 + timestamp: 1765181778282 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libspex-3.2.3-h9226d62_7100101.conda + sha256: 24dffff614943c547ba094f8eb03b412a18cc4654663202f1aab9158bfa875ba + md5: 63323b258079a75133ccecbb0902614d + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 + - libamd >=3.3.3,<4.0a0 + - libcolamd >=3.3.4,<4.0a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - gmp >=6.3.0,<7.0a0 + - mpfr >=4.2.1,<5.0a0 + license: LGPL-2.0-or-later + license_family: LGPL + size: 79220 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libspqr-4.3.4-h23b7119_7100101.conda + sha256: 52851575496122f9088c9f5a4283da7fbb277d9a877b5ce60a939554df542f3c + md5: c1ee33a71065c1f0efd9c8174d5f18b0 + depends: + - libgcc >=13 + - libstdcxx >=13 + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libcholmod >=5.3.1,<6.0a0 + - libblas >=3.9.0,<4.0a0 + - liblapack >=3.9.0,<4.0a0 + - libsuitesparseconfig >=7.10.1,<8.0a0 + license: GPL-2.0-or-later + license_family: GPL + size: 203419 + timestamp: 1741963824816 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.51.2-hf4e2dac_0.conda + sha256: 04596fcee262a870e4b7c9807224680ff48d4d0cc0dac076a602503d3dc6d217 + md5: da5be73701eecd0e8454423fd6ffcf30 + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=78.2,<79.0a0 + - libgcc >=14 + - libzlib >=1.3.1,<2.0a0 + license: blessing + size: 942808 + timestamp: 1768147973361 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda + sha256: fa39bfd69228a13e553bd24601332b7cfeb30ca11a3ca50bb028108fe90a7661 + md5: eecce068c7e4eddeb169591baac20ac4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.0,<4.0a0 + license: BSD-3-Clause + license_family: BSD + size: 304790 + timestamp: 1745608545575 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-15.2.0-h934c35e_17.conda + sha256: 50c48cd3716a2e58e8e2e02edc78fef2d08fffe1e3b1ed40eb5f87e7e2d07889 + md5: 24c2fe35fa45cd71214beba6f337c071 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc 15.2.0 he0feb66_17 + constrains: + - libstdcxx-ng ==15.2.0=*_17 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 5852406 + timestamp: 1770252584235 +- conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-14.3.0-h9f08a49_117.conda + sha256: ffb164d31e09b18cf95c6330bfce9268c1ce799103e56b7c004250332e7f9ede + md5: 97f8b7e451f960200c057ca83d92f9be + depends: + - __unix + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 20497917 + timestamp: 1770251920997 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-15.2.0-hdf11a46_17.conda + sha256: ca3fb322dab3373946b1064da686ec076f5b1b9caf0a2823dad00d0b0f704928 + md5: ea12f5a6bf12c88c06750d9803e1a570 + depends: + - libstdcxx 15.2.0 h934c35e_17 + license: GPL-3.0-only WITH GCC-exception-3.1 + license_family: GPL + size: 27573 + timestamp: 1770252638797 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsuitesparseconfig-7.10.1-h901830b_7100101.conda + sha256: d8f32a0b0ee17fbace7af4bd34ad554cc855b9c18e0aeccf8395e1478c161f37 + md5: 57ae1dd979da7aa88a9b38bfa2e1d6b2 + depends: + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libgfortran5 >=13.3.0 + - libgfortran + - libgcc >=13 + - _openmp_mutex >=4.5 + license: BSD-3-Clause + license_family: BSD + size: 42708 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsystemd0-257.10-hd0affe5_4.conda + sha256: f0356bb344a684e7616fc84675cfca6401140320594e8686be30e8ac7547aed2 + md5: 1d4c18d75c51ed9d00092a891a547a7d + depends: + - __glibc >=2.17,<3.0.a0 + - libcap >=2.77,<2.78.0a0 + - libgcc >=14 + license: LGPL-2.1-or-later + size: 491953 + timestamp: 1770738638119 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.1-h9d88235_1.conda + sha256: e5f8c38625aa6d567809733ae04bb71c161a42e44a9fa8227abe61fa5c60ebe0 + md5: cd5a90476766d53e901500df9215e927 + depends: + - __glibc >=2.17,<3.0.a0 + - lerc >=4.0.0,<5.0a0 + - libdeflate >=1.25,<1.26.0a0 + - libgcc >=14 + - libjpeg-turbo >=3.1.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libstdcxx >=14 + - libwebp-base >=1.6.0,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: HPND + size: 435273 + timestamp: 1762022005702 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libumfpack-6.3.5-h873dde6_7100101.conda + sha256: 9a2c0049210c0223084c29b39404ad6da6538e7a4d1ed74ee8423212998fd686 + md5: 9626fc7667bc6c901c7a0a4004938c71 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libsuitesparseconfig >=7.10.1,<8.0a0 + - libcholmod >=5.3.1,<6.0a0 + - libblas >=3.9.0,<4.0a0 + - libamd >=3.3.3,<4.0a0 + license: GPL-2.0-or-later + license_family: GPL + size: 404065 + timestamp: 1741963824815 +- conda: https://conda.anaconda.org/conda-forge/linux-64/liburcu-0.14.0-hac33072_0.conda + sha256: 208ead1ed147f588c722ef9dec7656f538111b15fb85c04f645758fa4fa8e3c3 + md5: 0b2b4f99717fe8f82dc21a3b0c504923 + depends: + - libgcc-ng >=12 + license: LGPL-2.0-or-later + license_family: LGPL + size: 176874 + timestamp: 1718888439831 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.41.3-h5347b49_0.conda + sha256: 1a7539cfa7df00714e8943e18de0b06cceef6778e420a5ee3a2a145773758aee + md5: db409b7c1720428638e7c0d509d3e1b5 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: BSD-3-Clause + license_family: BSD + size: 40311 + timestamp: 1766271528534 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.51.0-hb03c661_1.conda + sha256: c180f4124a889ac343fc59d15558e93667d894a966ec6fdb61da1604481be26b + md5: 0f03292cc56bf91a077a134ea8747118 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 895108 + timestamp: 1753948278280 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libvorbis-1.3.7-h54a6638_2.conda + sha256: ca494c99c7e5ecc1b4cd2f72b5584cef3d4ce631d23511184411abcbb90a21a5 + md5: b4ecbefe517ed0157c37f8182768271c + depends: + - libogg + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - libogg >=1.3.5,<1.4.0a0 + license: BSD-3-Clause + license_family: BSD + size: 285894 + timestamp: 1753879378005 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.6.0-hd42ef1d_0.conda + sha256: 3aed21ab28eddffdaf7f804f49be7a7d701e8f0e46c856d801270b470820a37b + md5: aea31d2e5b1091feca96fcfe945c3cf9 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + constrains: + - libwebp 1.6.0 + license: BSD-3-Clause + license_family: BSD + size: 429011 + timestamp: 1752159441324 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda + sha256: 666c0c431b23c6cec6e492840b176dde533d48b7e6fb8883f5071223433776aa + md5: 92ed62436b625154323d40d5f2f11dd7 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - pthread-stubs + - xorg-libxau >=1.0.11,<2.0a0 + - xorg-libxdmcp + license: MIT + license_family: MIT + size: 395888 + timestamp: 1727278577118 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda + sha256: 6ae68e0b86423ef188196fff6207ed0c8195dd84273cb5623b85aa08033a410c + md5: 5aa797f8787fe7a17d1b0821485b5adc + depends: + - libgcc-ng >=12 + license: LGPL-2.1-or-later + size: 100393 + timestamp: 1702724383534 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.13.1-hca5e8e5_0.conda + sha256: d2195b5fbcb0af1ff7b345efdf89290c279b8d1d74f325ae0ac98148c375863c + md5: 2bca1fbb221d9c3c8e3a155784bbc2e9 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libxcb >=1.17.0,<2.0a0 + - libxml2 + - libxml2-16 >=2.14.6 + - xkeyboard-config + - xorg-libxau >=1.0.12,<2.0a0 + license: MIT/X11 Derivative + license_family: MIT + size: 837922 + timestamp: 1764794163823 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.15.1-he237659_1.conda + sha256: 047be059033c394bd32ae5de66ce389824352120b3a7c0eff980195f7ed80357 + md5: 417955234eccd8f252b86a265ccdab7f + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=78.1,<79.0a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + - liblzma >=5.8.1,<6.0a0 + - libxml2-16 2.15.1 hca6bf5a_1 + - libzlib >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 45402 + timestamp: 1766327161688 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-16-2.15.1-hca6bf5a_1.conda + sha256: 8331284bf9ae641b70cdc0e5866502dd80055fc3b9350979c74bb1d192e8e09e + md5: 3fdd8d99683da9fe279c2f4cecd1e048 + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=78.1,<79.0a0 + - libgcc >=14 + - libiconv >=1.18,<2.0a0 + - liblzma >=5.8.1,<6.0a0 + - libzlib >=1.3.1,<2.0a0 + constrains: + - libxml2 2.15.1 + license: MIT + license_family: MIT + size: 555747 + timestamp: 1766327145986 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.43-h711ed8c_1.conda + sha256: 0694760a3e62bdc659d90a14ae9c6e132b525a7900e59785b18a08bb52a5d7e5 + md5: 87e6096ec6d542d1c1f8b33245fe8300 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libxml2 + - libxml2-16 >=2.14.6 + license: MIT + license_family: MIT + size: 245434 + timestamp: 1757963724977 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda + sha256: d4bfe88d7cb447768e31650f06257995601f89076080e76df55e3112d4e47dc4 + md5: edb0dca6bc32e4f4789199455a1dbeb8 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + constrains: + - zlib 1.3.1 *_2 + license: Zlib + license_family: Other + size: 60963 + timestamp: 1727963148474 +- conda: https://conda.anaconda.org/conda-forge/linux-64/llvm-openmp-22.1.0-h4922eb0_0.conda + sha256: 543c9f17cf6ee6d7b635823fb9009df421d510c36739534df6ae43eadaf6ff4e + md5: 5e7da5333653c631d27732893b934351 + depends: + - __glibc >=2.17,<3.0.a0 + constrains: + - intel-openmp <0.0a0 + - openmp 22.1.0|22.1.0.* + license: Apache-2.0 WITH LLVM-exception + license_family: APACHE + size: 6136884 + timestamp: 1772024545 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lttng-ust-2.13.9-hf5eda4c_0.conda + sha256: 77ea6f9546bb8e4d6050b4ad8efb9bfb2177e9173a03b4d9eae6fd8ce1056431 + md5: bf1ee9cd230a64573a8b7745c6aaa593 + depends: + - liburcu + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - liburcu >=0.14.0,<0.15.0a0 + license: LGPL-2.1-only + size: 375355 + timestamp: 1745310024643 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lxml-6.0.2-py312h63ddcf0_2.conda + sha256: 60000e93b2d65072abe97a98c85f987ffd47fa1ee612eeafeb2ccd0f48f9c74c + md5: a12c2fbcb3a5a7fa24e5fb8468368b1b + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libxml2 + - libxml2-16 >=2.14.6 + - libxslt >=1.1.43,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause and MIT-CMU + size: 1605879 + timestamp: 1762506384758 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-4.4.5-py312h3d67a73_1.conda + sha256: e8ae9141c7afcc95555fca7ff5f91d7a84f094536715211e750569fd4bb2caa4 + md5: a669145a2c834895bdf3fcba1f1e5b9c + depends: + - python + - lz4-c + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - lz4-c >=1.10.0,<1.11.0a0 + license: BSD-3-Clause + license_family: BSD + size: 44154 + timestamp: 1765026394687 +- conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.10.0-h5888daf_1.conda + sha256: 47326f811392a5fd3055f0f773036c392d26fdb32e4d8e7a8197eed951489346 + md5: 9de5350a85c4a20c685259b889aa6393 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: BSD-2-Clause + license_family: BSD + size: 167055 + timestamp: 1733741040117 +- conda: https://conda.anaconda.org/conda-forge/noarch/mccabe-0.7.0-pyhd8ed1ab_1.conda + sha256: 9b0037171dad0100f0296699a11ae7d355237b55f42f9094aebc0f41512d96a1 + md5: 827064ddfe0de2917fb29f1da4f8f533 + depends: + - python >=3.9 + license: MIT + license_family: MIT + size: 12934 + timestamp: 1733216573915 +- conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda + sha256: e8a00971e6d00bd49f375c5d8d005b37a9abba0b1768533aed0f90a422bf5cc7 + md5: 28eb714416de4eb83e2cbc47e99a1b45 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: Apache-2.0 + license_family: APACHE + size: 3923560 + timestamp: 1728064567817 +- conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda + sha256: f25d2474dd557ca66c6231c8f5ace5af312efde1ba8290a6ea5e1732a4e669c0 + md5: 2eeb50cab6652538eee8fc0bc3340c81 + depends: + - __glibc >=2.17,<3.0.a0 + - gmp >=6.3.0,<7.0a0 + - libgcc >=13 + license: LGPL-3.0-only + license_family: LGPL + size: 634751 + timestamp: 1725746740014 +- conda: https://conda.anaconda.org/conda-forge/linux-64/mpg123-1.32.9-hc50e24c_0.conda + sha256: 39c4700fb3fbe403a77d8cc27352fa72ba744db487559d5d44bf8411bb4ea200 + md5: c7f302fd11eeb0987a6a5e1f3aed6a21 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: LGPL-2.1-only + license_family: LGPL + size: 491140 + timestamp: 1730581373280 +- conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda + sha256: 3fde293232fa3fca98635e1167de6b7c7fda83caf24b9d6c91ec9eefb4f4d586 + md5: 47e340acb35de30501a76c7c799c41d7 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: X11 AND BSD-3-Clause + size: 891641 + timestamp: 1738195959188 +- conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.13.2-h171cf75_0.conda + sha256: 6f7d59dbec0a7b00bf5d103a4306e8886678b796ff2151b62452d4582b2a53fb + md5: b518e9e92493721281a60fa975bddc65 + depends: + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: Apache-2.0 + license_family: APACHE + size: 186323 + timestamp: 1763688260928 +- conda: https://conda.anaconda.org/conda-forge/linux-64/nspr-4.38-h29cc59b_0.conda + sha256: e3664264bd936c357523b55c71ed5a30263c6ba278d726a75b1eb112e6fb0b64 + md5: e235d5566c9cc8970eb2798dd4ecf62f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + license: MPL-2.0 + license_family: MOZILLA + size: 228588 + timestamp: 1762348634537 +- conda: https://conda.anaconda.org/conda-forge/linux-64/nss-3.118-h445c969_0.conda + sha256: 44dd98ffeac859d84a6dcba79a2096193a42fc10b29b28a5115687a680dd6aea + md5: 567fbeed956c200c1db5782a424e58ee + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libsqlite >=3.51.0,<4.0a0 + - libstdcxx >=14 + - libzlib >=1.3.1,<2.0a0 + - nspr >=4.38,<5.0a0 + license: MPL-2.0 + license_family: MOZILLA + size: 2057773 + timestamp: 1763485556350 +- conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.4.2-py312h33ff503_1.conda + sha256: fec4d37e1a7c677ddc07bb968255df74902733398b77acc1d05f9dc599e879df + md5: 3569a8fca2dd3202e4ab08f42499f6d3 + depends: + - python + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - liblapack >=3.9.0,<4.0a0 + - python_abi 3.12.* *_cp312 + - libcblas >=3.9.0,<4.0a0 + - libblas >=3.9.0,<4.0a0 + constrains: + - numpy-base <0a0 + license: BSD-3-Clause + license_family: BSD + size: 8757566 + timestamp: 1770098484112 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openexr-3.4.6-h40f6f1d_0.conda + sha256: c733f18e2896920eddbd26aba28fd16dae5b25f272ede436672ad0ceb60e8603 + md5: 0a5f140bdbc5f7ab45568a0bc3431362 + depends: + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - openjph >=0.26.3,<0.27.0a0 + - libzlib >=1.3.1,<2.0a0 + - libdeflate >=1.25,<1.26.0a0 + - imath >=3.2.2,<3.2.3.0a0 + license: BSD-3-Clause + license_family: BSD + size: 1217961 + timestamp: 1772443688420 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.4-h55fea9a_0.conda + sha256: 3900f9f2dbbf4129cf3ad6acf4e4b6f7101390b53843591c53b00f034343bc4d + md5: 11b3379b191f63139e29c0d19dee24cd + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libpng >=1.6.50,<1.7.0a0 + - libstdcxx >=14 + - libtiff >=4.7.1,<4.8.0a0 + - libzlib >=1.3.1,<2.0a0 + license: BSD-2-Clause + license_family: BSD + size: 355400 + timestamp: 1758489294972 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openjph-0.26.3-h8d634f6_0.conda + sha256: 4587e7762f27cad93619de77fa0573e2e17a899892d4bed3010196093e343533 + md5: 792d5b6e99677177f5527a758a02bc07 + depends: + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - libtiff >=4.7.1,<4.8.0a0 + license: BSD-2-Clause + license_family: BSD + size: 279846 + timestamp: 1771349499024 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.10-he970967_0.conda + sha256: cb0b07db15e303e6f0a19646807715d28f1264c6350309a559702f4f34f37892 + md5: 2e5bf4f1da39c0b32778561c3c4e5878 + depends: + - __glibc >=2.17,<3.0.a0 + - cyrus-sasl >=2.1.27,<3.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - libstdcxx >=13 + - openssl >=3.5.0,<4.0a0 + license: OLDAP-2.8 + license_family: BSD + size: 780253 + timestamp: 1748010165522 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.6.1-h35e630c_1.conda + sha256: 44c877f8af015332a5d12f5ff0fb20ca32f896526a7d0cdb30c769df1144fb5c + md5: f61eb8cd60ff9057122a3d338b99c00f + depends: + - __glibc >=2.17,<3.0.a0 + - ca-certificates + - libgcc >=14 + license: Apache-2.0 + license_family: Apache + size: 3164551 + timestamp: 1769555830639 +- conda: https://conda.anaconda.org/conda-forge/linux-64/orocos-kdl-1.5.3-hecca717_0.conda + sha256: f1ac73e2a809a0e838e55afd521313a441d2d159621d2295a65700c7d519ead8 + md5: 9b780914fe0015a0d18631a4b32e5446 + depends: + - __glibc >=2.17,<3.0.a0 + - eigen + - libgcc >=14 + - libstdcxx >=14 + license: LGPL-2.1-or-later + license_family: LGPL + size: 387599 + timestamp: 1760695564119 +- conda: https://conda.anaconda.org/conda-forge/noarch/packaging-26.0-pyhcf101f3_0.conda + sha256: c1fc0f953048f743385d31c468b4a678b3ad20caffdeaa94bed85ba63049fd58 + md5: b76541e68fea4d511b1ac46a28dcd2c6 + depends: + - python >=3.8 + - python + license: Apache-2.0 + license_family: APACHE + size: 72010 + timestamp: 1769093650580 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pango-1.56.4-hadf4263_0.conda + sha256: 3613774ad27e48503a3a6a9d72017087ea70f1426f6e5541dbdb59a3b626eaaf + md5: 79f71230c069a287efe3a8614069ddf1 + depends: + - __glibc >=2.17,<3.0.a0 + - cairo >=1.18.4,<2.0a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - fribidi >=1.0.10,<2.0a0 + - harfbuzz >=11.0.1 + - libexpat >=2.7.0,<3.0a0 + - libfreetype >=2.13.3 + - libfreetype6 >=2.13.3 + - libgcc >=13 + - libglib >=2.84.2,<3.0a0 + - libpng >=1.6.49,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + license: LGPL-2.1-or-later + size: 455420 + timestamp: 1751292466873 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pcre-8.45-h9c3ff4c_0.tar.bz2 + sha256: 8f35c244b1631a4f31fb1d66ab6e1d9bfac0ca9b679deced1112c7225b3ad138 + md5: c05d1820a6d34ff07aaaab7a9b7eddaa + depends: + - libgcc-ng >=9.3.0 + - libstdcxx-ng >=9.3.0 + license: BSD-3-Clause + license_family: BSD + size: 259377 + timestamp: 1623788789327 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.47-haa7fec5_0.conda + sha256: 5e6f7d161356fefd981948bea5139c5aa0436767751a6930cb1ca801ebb113ff + md5: 7a3bff861a6583f1889021facefc08b1 + depends: + - __glibc >=2.17,<3.0.a0 + - bzip2 >=1.0.8,<2.0a0 + - libgcc >=14 + - libzlib >=1.3.1,<2.0a0 + license: BSD-3-Clause + license_family: BSD + size: 1222481 + timestamp: 1763655398280 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.4-h54a6638_1.conda + sha256: 43d37bc9ca3b257c5dd7bf76a8426addbdec381f6786ff441dc90b1a49143b6a + md5: c01af13bdc553d1a8fbfff6e8db075f0 + depends: + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: MIT + license_family: MIT + size: 450960 + timestamp: 1754665235234 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda + sha256: c9601efb1af5391317e04eca77c6fe4d716bf1ca1ad8da2a05d15cb7c28d7d4e + md5: 1bee70681f504ea424fb07cdb090c001 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc-ng >=12 + license: GPL-2.0-or-later + license_family: GPL + size: 115175 + timestamp: 1720805894943 +- conda: https://conda.anaconda.org/conda-forge/noarch/pluggy-1.6.0-pyhf9edf01_1.conda + sha256: e14aafa63efa0528ca99ba568eaf506eb55a0371d12e6250aaaa61718d2eb62e + md5: d7585b6550ad04c8c5e21097ada2888e + depends: + - python >=3.9 + - python + license: MIT + license_family: MIT + size: 25877 + timestamp: 1764896838868 +- conda: https://conda.anaconda.org/conda-forge/linux-64/psutil-7.2.2-py312h5253ce2_0.conda + sha256: d834fd656133c9e4eaf63ffe9a117c7d0917d86d89f7d64073f4e3a0020bd8a7 + md5: dd94c506b119130aef5a9382aed648e7 + depends: + - python + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + license_family: BSD + size: 225545 + timestamp: 1769678155334 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda + sha256: 9c88f8c64590e9567c6c80823f0328e58d3b1efb0e1c539c0315ceca764e0973 + md5: b3c17d95b5a10c6e64a21fa17573e70e + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 8252 + timestamp: 1726802366959 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pugixml-1.15-h3f63f65_0.conda + sha256: 23c98a5000356e173568dc5c5770b53393879f946f3ace716bbdefac2a8b23d2 + md5: b11a4c6bf6f6f44e5e143f759ffa2087 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: MIT + license_family: MIT + size: 118488 + timestamp: 1736601364156 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pulseaudio-client-17.0-h9a6aba3_3.conda + sha256: 0a0858c59805d627d02bdceee965dd84fde0aceab03a2f984325eec08d822096 + md5: b8ea447fdf62e3597cb8d2fae4eb1a90 + depends: + - __glibc >=2.17,<3.0.a0 + - dbus >=1.16.2,<2.0a0 + - libgcc >=14 + - libglib >=2.86.1,<3.0a0 + - libiconv >=1.18,<2.0a0 + - libsndfile >=1.2.2,<1.3.0a0 + - libsystemd0 >=257.10 + - libxcb >=1.17.0,<2.0a0 + constrains: + - pulseaudio 17.0 *_3 + license: LGPL-2.1-or-later + license_family: LGPL + size: 750785 + timestamp: 1763148198088 +- conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-3.0.1-pyh7a1b43c_0.conda + sha256: 2558727093f13d4c30e124724566d16badd7de532fd8ee7483628977117d02be + md5: 70ece62498c769280f791e836ac53fff + depends: + - python >=3.8 + - pybind11-global ==3.0.1 *_0 + - python + constrains: + - pybind11-abi ==11 + license: BSD-3-Clause + license_family: BSD + size: 232875 + timestamp: 1755953378112 +- conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-11-hc364b38_1.conda + sha256: 9e7fe12f727acd2787fb5816b2049cef4604b7a00ad3e408c5e709c298ce8bf1 + md5: f0599959a2447c1e544e216bddf393fa + license: BSD-3-Clause + license_family: BSD + size: 14671 + timestamp: 1752769938071 +- conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-global-3.0.1-pyhc7ab6ef_0.conda + sha256: f11a5903879fe3a24e0d28329cb2b1945127e85a4cdb444b45545cf079f99e2d + md5: fe10b422ce8b5af5dab3740e4084c3f9 + depends: + - python >=3.8 + - __unix + - python + constrains: + - pybind11-abi ==11 + license: BSD-3-Clause + license_family: BSD + size: 228871 + timestamp: 1755953338243 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pybullet-3.25-py312hf49885f_5.conda + sha256: 849bbe715c3d3e3c89f19a096d0158ce712022f387829ba222c327c533b747d4 + md5: 82f56eb2ea7b24643993dea9f715b101 + depends: + - __glibc >=2.17,<3.0.a0 + - bullet-cpp 3.25 hcbe3ca9_5 + - libgcc >=13 + - libstdcxx >=13 + - libzlib >=1.3.1,<2.0a0 + - numpy >=1.23,<3 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + license: Zlib + size: 62838622 + timestamp: 1761041325516 +- conda: https://conda.anaconda.org/conda-forge/noarch/pycodestyle-2.14.0-pyhd8ed1ab_0.conda + sha256: 1950f71ff44e64163e176b1ca34812afc1a104075c3190de50597e1623eb7d53 + md5: 85815c6a22905c080111ec8d56741454 + depends: + - python >=3.9 + license: MIT + license_family: MIT + size: 35182 + timestamp: 1750616054854 +- conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda + sha256: 79db7928d13fab2d892592223d7570f5061c192f27b9febd1a418427b719acc6 + md5: 12c566707c80111f9799308d9e265aef + depends: + - python >=3.9 + - python + license: BSD-3-Clause + license_family: BSD + size: 110100 + timestamp: 1733195786147 +- conda: https://conda.anaconda.org/conda-forge/noarch/pydocstyle-6.3.0-pyhd8ed1ab_1.conda + sha256: 83ab8434e3baf6a018914da4f1c2ae9023e23fb41e131b68b3e3f9ca41ecef61 + md5: a36aa6e0119331d3280f4bba043314c7 + depends: + - python >=3.9 + - snowballstemmer >=2.2.0 + - tomli >=1.2.3 + license: MIT + license_family: MIT + size: 40236 + timestamp: 1733261742916 +- conda: https://conda.anaconda.org/conda-forge/noarch/pyflakes-3.4.0-pyhd8ed1ab_0.conda + sha256: 4b6fb3f7697b4e591c06149671699777c71ca215e9ec16d5bd0767425e630d65 + md5: dba204e749e06890aeb3756ef2b1bf35 + depends: + - python >=3.9 + license: MIT + license_family: MIT + size: 59592 + timestamp: 1750492011671 +- conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.2-pyhd8ed1ab_0.conda + sha256: 5577623b9f6685ece2697c6eb7511b4c9ac5fb607c9babc2646c811b428fd46a + md5: 6b6ece66ebcae2d5f326c77ef2c5a066 + depends: + - python >=3.9 + license: BSD-2-Clause + license_family: BSD + size: 889287 + timestamp: 1750615908735 +- conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.3.2-pyhcf101f3_0.conda + sha256: 417fba4783e528ee732afa82999300859b065dc59927344b4859c64aae7182de + md5: 3687cc0b82a8b4c17e1f0eb7e47163d5 + depends: + - python >=3.10 + - python + license: MIT + license_family: MIT + size: 110893 + timestamp: 1769003998136 +- conda: https://conda.anaconda.org/conda-forge/noarch/pytest-9.0.2-pyhcf101f3_0.conda + sha256: 9e749fb465a8bedf0184d8b8996992a38de351f7c64e967031944978de03a520 + md5: 2b694bad8a50dc2f712f5368de866480 + depends: + - pygments >=2.7.2 + - python >=3.10 + - iniconfig >=1.0.1 + - packaging >=22 + - pluggy >=1.5,<2 + - tomli >=1 + - colorama >=0.4 + - exceptiongroup >=1 + - python + constrains: + - pytest-faulthandler >=2 + license: MIT + license_family: MIT + size: 299581 + timestamp: 1765062031645 +- conda: https://conda.anaconda.org/conda-forge/noarch/pytest-cov-7.0.0-pyhcf101f3_1.conda + sha256: d0f45586aad48ef604590188c33c83d76e4fc6370ac569ba0900906b24fd6a26 + md5: 6891acad5e136cb62a8c2ed2679d6528 + depends: + - coverage >=7.10.6 + - pluggy >=1.2 + - pytest >=7 + - python >=3.10 + - python + license: MIT + license_family: MIT + size: 29016 + timestamp: 1757612051022 +- conda: https://conda.anaconda.org/conda-forge/noarch/pytest-repeat-0.9.4-pyhd8ed1ab_0.conda + sha256: cea7b0555c22a734d732f98a3b256646f3d82d926a35fa2bfd16f11395abd83b + md5: 9e8871313f26d8b6f0232522b3bc47a5 + depends: + - pytest >=5 + - python >=3.9 + license: MPL-2.0 + license_family: MOZILLA + size: 10537 + timestamp: 1744061283541 +- conda: https://conda.anaconda.org/conda-forge/noarch/pytest-rerunfailures-16.1-pyhd8ed1ab_0.conda + sha256: 437f0e7805e471dcc57afd4b122d5025fa2162e4c031dc9e8c6f2c05c4d50cc0 + md5: b57fe0c7e03b97c3554e6cea827e2058 + depends: + - packaging >=17.1 + - pytest >=7.4,!=8.2.2 + - python >=3.10 + license: MPL-2.0 + license_family: OTHER + size: 19613 + timestamp: 1760091441792 +- conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.12-hd63d673_2_cpython.conda + build_number: 2 + sha256: 6621befd6570a216ba94bc34ec4618e4f3777de55ad0adc15fc23c28fadd4d1a + md5: c4540d3de3fa228d9fa95e31f8e97f89 + depends: + - __glibc >=2.17,<3.0.a0 + - bzip2 >=1.0.8,<2.0a0 + - ld_impl_linux-64 >=2.36.1 + - libexpat >=2.7.3,<3.0a0 + - libffi >=3.5.2,<3.6.0a0 + - libgcc >=14 + - liblzma >=5.8.2,<6.0a0 + - libnsl >=2.0.1,<2.1.0a0 + - libsqlite >=3.51.2,<4.0a0 + - libuuid >=2.41.3,<3.0a0 + - libxcrypt >=4.4.36 + - libzlib >=1.3.1,<2.0a0 + - ncurses >=6.5,<7.0a0 + - openssl >=3.5.4,<4.0a0 + - readline >=8.3,<9.0a0 + - tk >=8.6.13,<8.7.0a0 + - tzdata + constrains: + - python_abi 3.12.* *_cp312 + license: Python-2.0 + size: 31457785 + timestamp: 1769472855343 +- conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhe01879c_2.conda + sha256: d6a17ece93bbd5139e02d2bd7dbfa80bee1a4261dced63f65f679121686bf664 + md5: 5b8d21249ff20967101ffa321cab24e8 + depends: + - python >=3.9 + - six >=1.5 + - python + license: Apache-2.0 + license_family: APACHE + size: 233310 + timestamp: 1751104122689 +- conda: https://conda.anaconda.org/conda-forge/linux-64/python-orocos-kdl-1.5.3-py312h1289d80_0.conda + sha256: 90710092b39029c891934aa03076123a191365a2821c60e3e9c8540f320f4792 + md5: 5621a85f434696dbbf66dbb6a4d47343 + depends: + - __glibc >=2.17,<3.0.a0 + - eigen + - libgcc >=14 + - libstdcxx >=14 + - orocos-kdl + - pybind11 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + license: LGPL-2.1-or-later + license_family: LGPL + size: 346120 + timestamp: 1760695946175 +- conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-8_cp312.conda + build_number: 8 + sha256: 80677180dd3c22deb7426ca89d6203f1c7f1f256f2d5a94dc210f6e758229809 + md5: c3efd25ac4d74b1584d2f7a57195ddf1 + constrains: + - python 3.12.* *_cpython + license: BSD-3-Clause + license_family: BSD + size: 6958 + timestamp: 1752805918820 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.3-py312h8a5da7c_1.conda + sha256: cb142bfd92f6e55749365ddc244294fa7b64db6d08c45b018ff1c658907bfcbf + md5: 15878599a87992e44c059731771591cb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python >=3.12,<3.13.0a0 + - python_abi 3.12.* *_cp312 + - yaml >=0.2.5,<0.3.0a0 + license: MIT + license_family: MIT + size: 198293 + timestamp: 1770223620706 +- conda: https://conda.anaconda.org/conda-forge/linux-64/qt-main-5.15.15-hc240232_7.conda + sha256: 401cc7f9ff78ee12097fcda8c09dcf269847a8a55b17b7c0a973f322c7bd5fbc + md5: fa3bbe293d907990f3ca5b8b9d4b10f0 + depends: + - __glibc >=2.17,<3.0.a0 + - alsa-lib >=1.2.15.3,<1.3.0a0 + - dbus >=1.16.2,<2.0a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - gst-plugins-base >=1.26.10,<1.27.0a0 + - gstreamer >=1.26.10,<1.27.0a0 + - harfbuzz >=12.3.2 + - icu >=78.2,<79.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libclang-cpp21.1 >=21.1.8,<21.2.0a0 + - libclang13 >=21.1.8 + - libcups >=2.3.3,<2.4.0a0 + - libdrm >=2.4.125,<2.5.0a0 + - libegl >=1.7.0,<2.0a0 + - libevent >=2.1.12,<2.1.13.0a0 + - libexpat >=2.7.3,<3.0a0 + - libfreetype >=2.14.1 + - libfreetype6 >=2.14.1 + - libgcc >=13 + - libgl >=1.7.0,<2.0a0 + - libglib >=2.86.3,<3.0a0 + - libjpeg-turbo >=3.1.2,<4.0a0 + - libllvm21 >=21.1.8,<21.2.0a0 + - libpng >=1.6.55,<1.7.0a0 + - libpq >=18.1,<19.0a0 + - libsqlite >=3.51.2,<4.0a0 + - libstdcxx >=13 + - libxcb >=1.17.0,<2.0a0 + - libxkbcommon >=1.13.1,<2.0a0 + - libxml2 + - libxml2-16 >=2.14.6 + - libzlib >=1.3.1,<2.0a0 + - nspr >=4.38,<5.0a0 + - nss >=3.118,<4.0a0 + - openssl >=3.5.5,<4.0a0 + - pulseaudio-client >=17.0,<17.1.0a0 + - xcb-util >=0.4.1,<0.5.0a0 + - xcb-util-image >=0.4.0,<0.5.0a0 + - xcb-util-keysyms >=0.4.1,<0.5.0a0 + - xcb-util-renderutil >=0.3.10,<0.4.0a0 + - xcb-util-wm >=0.4.2,<0.5.0a0 + - xorg-libice >=1.1.2,<2.0a0 + - xorg-libsm >=1.2.6,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxdamage >=1.1.6,<2.0a0 + - xorg-libxext >=1.3.7,<2.0a0 + - xorg-libxxf86vm >=1.1.7,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + constrains: + - qt 5.15.15 + license: LGPL-3.0-only + license_family: LGPL + size: 52414725 + timestamp: 1770722572283 +- conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.3-h853b02a_0.conda + sha256: 12ffde5a6f958e285aa22c191ca01bbd3d6e710aa852e00618fa6ddc59149002 + md5: d7d95fc8287ea7bf33e0e7116d2b95ec + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ncurses >=6.5,<7.0a0 + license: GPL-3.0-only + license_family: GPL + size: 345073 + timestamp: 1765813471974 +- conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.6-hb9d3cd8_1.conda + sha256: d5c73079c1dd2c2a313c3bfd81c73dbd066b7eb08d213778c8bff520091ae894 + md5: c1c9b02933fdb2cfb791d936c20e887e + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 193775 + timestamp: 1748644872902 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-action-msgs-2.0.3-np2py312h2ed9cc7_14.conda + sha256: df3a7c99d1444ff2c0d73c512b1c75f4ba8e181fd275fa96f9e98dacda20fa92 + md5: d1505737d684a86fc85f8eeb63972d07 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros-jazzy-service-msgs + - ros-jazzy-unique-identifier-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 152330 + timestamp: 1768976295979 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-actionlib-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 780d2d4208a70c28c606b6f1b7c7014fc7b95dc6ab68085efdedf94bb130ab71 + md5: 8b1d6999c5a0cf9cecb18d467abb7a95 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 111418 + timestamp: 1768976645128 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 0483bf4dbda7d507bf3684f7cf3c82ffe0b62a2d2beb3fa35b8ee60946411b69 + md5: 61722fcf171b18e7747e078f4aabfd23 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-export-definitions + - ros-jazzy-ament-cmake-export-dependencies + - ros-jazzy-ament-cmake-export-include-directories + - ros-jazzy-ament-cmake-export-interfaces + - ros-jazzy-ament-cmake-export-libraries + - ros-jazzy-ament-cmake-export-link-flags + - ros-jazzy-ament-cmake-export-targets + - ros-jazzy-ament-cmake-gen-version-h + - ros-jazzy-ament-cmake-libraries + - ros-jazzy-ament-cmake-python + - ros-jazzy-ament-cmake-target-dependencies + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-cmake-version + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - cmake + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 23313 + timestamp: 1768974327623 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-auto-2.5.4-np2py312h2ed9cc7_14.conda + sha256: b6bf021026abb899f4d5e5d8469c485ff37ecf0b6ff9c16d2d7ddeb4d815d6de + md5: 33178ee4503fb01faaa9e08785bf803d + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-cmake-gmock + - ros-jazzy-ament-cmake-gtest + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 27448 + timestamp: 1768974379286 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-copyright-0.17.3-np2py312h2ed9cc7_14.conda + sha256: e5e04b78e1d12eeb55b66824cd752c66094c9e5716a68642f9c09c18b112da1f + md5: 6fca677b0d5e63f107b33ad284bba68b + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-copyright + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 22772 + timestamp: 1768974507285 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-core-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 07fcb434cde42ce56a1f8d9000ed4644739440b13cb40ad5f64d4152294f370a + md5: caba5f805c0d02b1c2c1cd5127a5409f + depends: + - catkin_pkg + - python + - ros-jazzy-ament-package + - ros2-distro-mutex 0.13.* jazzy_* + - cmake + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 44941 + timestamp: 1768973804943 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-cppcheck-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 61f32281b0c6555512eba814391ec8ad906d8b3877a0e3679f7473bcd5f9251a + md5: 93150956627cda97aa49c5e22d5007c4 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-cppcheck + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 24402 + timestamp: 1768974657890 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-cpplint-0.17.3-np2py312h2ed9cc7_14.conda + sha256: d925d3bd2e1735630f2cadcafe326b5da9169df3b84f627bea8c84cf733684ac + md5: c8b2fe40893b13b45a448624384d20b6 + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-cpplint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 23397 + timestamp: 1768974681917 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-definitions-2.5.4-np2py312h2ed9cc7_14.conda + sha256: c37fdb7f20845eb52ceec3620816cd612df528c16cb0473e84453e531659fd25 + md5: 4f5e14b421cd29eacb0e9178cee0e2c6 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 22111 + timestamp: 1768973898519 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-dependencies-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 6cfd134559e7c9d9931bf0261dd1d694c8beee75d785fc887ca18308d220860c + md5: b6738bdd18b92f77fec8b1ffc59c1778 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-libraries + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 23036 + timestamp: 1768974002217 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-include-directories-2.5.4-np2py312h2ed9cc7_14.conda + sha256: b163259291e71f3ef04fc586533cf238799d1e6f37637913182cd5617365f066 + md5: 32a2ea42771a88d81c7f28e1dfaaf0c6 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 22539 + timestamp: 1768973895208 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-interfaces-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 668a1e12b2b3aef58f3a76898a5a2dcedeb57b8804d98592648b16f7d4882e8e + md5: 6546163a1ec767fab158b1fe06eea916 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-export-libraries + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 22732 + timestamp: 1768973980127 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-libraries-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 09f0a7910a43d95e06f8793bc18d3408ac802c044b2b152c5cca5f3d4df8790f + md5: 2252fdd73a7bc0e17da5466ec5e7519b + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24052 + timestamp: 1768973874336 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-link-flags-2.5.4-np2py312h2ed9cc7_14.conda + sha256: ddbe0b429365f8156fe688c951a24525fcebe69747f36aa42deb89a2d2733de1 + md5: a5ce8d4392f00f4e3ad12ff825116238 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 22071 + timestamp: 1768973891967 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-export-targets-2.5.4-np2py312h2ed9cc7_14.conda + sha256: d158f7e1a3c844cb7b5ce4e0aa290221391a4f674027354f9a06c91606ceef5b + md5: bb50cff564c681b4ddf38936d3db5f10 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-export-libraries + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 22844 + timestamp: 1768974009783 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-flake8-0.17.3-np2py312h2ed9cc7_14.conda + sha256: d111df8b9015895e396b440b8fa6014b4a0c440fd735df031b6e61eef5c56dd8 + md5: a8056d911d1c1ecab61e798e1be9396f + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-flake8 + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 24451 + timestamp: 1768974678382 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gen-version-h-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 172606d033950edc96bbfd9a56a3192059ac209945c772922b5aecf0c1ab1ce4 + md5: b8239858edebc212393b8857ff35e8cd + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24822 + timestamp: 1768974213242 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gmock-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 871e41eecd15c52e6e832f34619dd69efc8a74a9273cb7400c0d5dae76e6cb22 + md5: f2d7e8f8c44b480cbad46eadac138aa0 + depends: + - gmock + - python + - ros-jazzy-ament-cmake-gtest + - ros-jazzy-ament-cmake-test + - ros-jazzy-gmock-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 25011 + timestamp: 1768974220078 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-gtest-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 3ffcfd7d2698b4fd07d338a506d1989268acb33597981a60296094111e8922ed + md5: fb1de1fa0649477e15dd6938c604ffcf + depends: + - gtest + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-gtest-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - gtest >=1.17.0,<1.17.1.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24765 + timestamp: 1768974098821 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-include-directories-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 79f0867a76db6cf0ecd3f84e3b55b3ebd76a7e5f5c9f09bc36b687cc0fbfeebf + md5: 24e25685a96f7c6e0403b0263430f7b2 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 22003 + timestamp: 1768973898638 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-libraries-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 10f4db6478ebfbd1b7b7f040d3ef3d5a23ebb4dfce810c4325f3fa3e0ec9b15e + md5: 100398d5b43e180b756d1bd667494799 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 21680 + timestamp: 1768973895746 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-lint-cmake-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 59eaf2799416c2e4813890449353c0dd5347fd60718af91e171152e8dfeada5d + md5: 1310ed2b9b36a3ebc534c5a287029793 + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-lint-cmake + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 22470 + timestamp: 1768974379705 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-pep257-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 9155ded7e163a741eee5e9257190391aa678b6a3674e79a16cee4dd434f4b013 + md5: 8e2be3c3247dcb234d0a6d6779dea2fa + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-pep257 + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 23126 + timestamp: 1768974674965 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-pytest-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 419bb650491a1c1531e40980d0d4a860b91ce71b414f501f4e94ed659cbd9734 + md5: ac9303daf5026ea167e7e9c4f0ab1bae + depends: + - pytest + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-test + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24849 + timestamp: 1768974083180 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-python-2.5.4-np2py312h2ed9cc7_14.conda + sha256: c2b04144eafb6e5b5a499818f763d023f7e56bd6452f30c66f812cd6e9189743 + md5: 17ad11b28c28cc34b00b82734a7fddee + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24222 + timestamp: 1768973887099 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-ros-0.12.0-np2py312h2ed9cc7_14.conda + sha256: 94ac539e1592e3bd408c072966126a681bf3b8e50d714bdd1034e8caa8084a4d + md5: 97961fc35f3e355fd5dc9e345e25d1c0 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-cmake-gmock + - ros-jazzy-ament-cmake-gtest + - ros-jazzy-ament-cmake-pytest + - ros-jazzy-domain-coordinator + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 31382 + timestamp: 1768975009128 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-target-dependencies-2.5.4-np2py312h2ed9cc7_14.conda + sha256: a1ff5c48f1b5f2a0959a2c2f1ec83fe47c46dc009f272f8b5c0c4d02bedd47a8 + md5: b75991741593b5ce011b29678c8071d6 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-include-directories + - ros-jazzy-ament-cmake-libraries + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 23731 + timestamp: 1768974006080 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-test-2.5.4-np2py312h2ed9cc7_14.conda + sha256: 4080080ee8041c8e79168d9d4f70a340ef34ab7e426648d9da200f225be0f663 + md5: cec3ecc93585d253286748ba4ac7c9b8 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 36159 + timestamp: 1768973994025 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-uncrustify-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 989916930b82b9511a796c5edae1c7644bf7b751ba3a69cb5434784422f0dcce + md5: 48ac82ecea8eaa3db530b85a510c4a75 + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-uncrustify + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 23714 + timestamp: 1768974671543 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-version-2.5.4-np2py312h2ed9cc7_14.conda + sha256: fd62143bac65a77e58d5d4a81d25335db8cc060150b9dbabea28549d957b2298 + md5: 52b93d3de8bde7b875db54db2057ade5 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 21853 + timestamp: 1768973887986 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cmake-xmllint-0.17.3-np2py312h2ed9cc7_14.conda + sha256: ec922395c78e8501719eab800358727f50bb06f150952ad7bd1fdeed88476221 + md5: 6aa4b183d08d2faf9e4177742b4bfb76 + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-ament-xmllint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 23151 + timestamp: 1768974656681 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-copyright-0.17.3-np2py312h2ed9cc7_14.conda + sha256: c570b0af4d9a050af2a8c50674c585bdaaba431a1044ed5603271041763d04aa + md5: 10e8f53dd90ac657537a20f5c8f047c7 + depends: + - importlib-metadata + - python + - ros-jazzy-ament-lint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 66626 + timestamp: 1768974198181 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cppcheck-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 9d22d33d0f6685da9324e8440f13813fe3a9b5a1d408599e1bafa189c433a3a7 + md5: 04dde38951a5581722b524e78d2f519a + depends: + - cppcheck + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 29962 + timestamp: 1768974343747 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-cpplint-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 617083ee655a503b50af3e4969b1642996af5c23367dec4a81124774d6adb6cd + md5: 3d04592013e3421c450e5c54c7f6545f + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR BSD-3-Clause + size: 168773 + timestamp: 1768974339137 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-flake8-0.17.3-np2py312h2ed9cc7_14.conda + sha256: abc5c3c8da0c45022f0dbd8ad258a8bb9dd779dcbc0791f44e53ece45632452c + md5: 4ca32a573ccfb7d26e50a7859ff11ac0 + depends: + - flake8 + - flake8-builtins + - flake8-comprehensions + - flake8-docstrings + - flake8-import-order + - flake8-quotes + - python + - ros-jazzy-ament-lint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 28405 + timestamp: 1768973981180 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-index-cpp-1.8.1-np2py312h2ed9cc7_14.conda + sha256: 5098ee870238bf1dae3245e0beb3f3b91d2fc0d0ee41b99c0c7f0f88a28d2ec9 + md5: 6f91d8e4237b0d64f263133e633c167b + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 47033 + timestamp: 1768975298861 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-index-python-1.8.1-np2py312h2ed9cc7_14.conda + sha256: e8226eb54557eadd191638a9bde1dd2c3cd45c6a45f85893b8d453b54afbf49a + md5: aef7d4e7d566506e1d2fd7cec44badcd + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 29732 + timestamp: 1768974311071 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 838cf72a27a506f3c22a60b2fe3b1e81fc4f65b6d36530b1886c24fd52eabf69 + md5: 4671d659d6c4424ab8428a06df1553b2 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 18330 + timestamp: 1768973871545 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-auto-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 1be1c17902578bd7f7cd0d01070b1e26f519d3eb3cdb5c11c2db8483f4ae5559 + md5: 9c903c772cf822fbf4daaf77fcc67139 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-test + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 22080 + timestamp: 1768974114189 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-cmake-0.17.3-np2py312h2ed9cc7_14.conda + sha256: d7b5cdc8912e3fbc004031b6c5a61c3a48fdf48c694bbc5032891254e51fd130 + md5: 730bba0b74c52705a0e36b466fbebf7c + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 39548 + timestamp: 1768974311366 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-lint-common-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 696d4804513bdf5102e259aefbea8d000d6dea9ff8bf62780d02e259f4dad813 + md5: 22ae156bc07365cbd4bd1f1a0075c8f1 + depends: + - python + - ros-jazzy-ament-cmake-copyright + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-cmake-cppcheck + - ros-jazzy-ament-cmake-cpplint + - ros-jazzy-ament-cmake-flake8 + - ros-jazzy-ament-cmake-lint-cmake + - ros-jazzy-ament-cmake-pep257 + - ros-jazzy-ament-cmake-uncrustify + - ros-jazzy-ament-cmake-xmllint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 22345 + timestamp: 1768974718131 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-package-0.16.4-np2py312h2ed9cc7_14.conda + sha256: de7fd8bb838ebde86b4bb5ae8b44aa3a4f86d8d92194832d307603f9c4116b55 + md5: a1594609fe03afc07aa6287044fb6c4d + depends: + - importlib-metadata + - importlib_resources + - python + - ros2-distro-mutex 0.13.* jazzy_* + - setuptools + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 43044 + timestamp: 1768973793208 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-pep257-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 43ae962ff83a00169ce6e6b44b781cb370e02f1d7a7afcfdd51732cc1601be78 + md5: 81d2813f6c6197a7ffc10fd43959c9a7 + depends: + - pydocstyle + - python + - ros-jazzy-ament-lint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 OR MIT + size: 27110 + timestamp: 1768974083190 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-uncrustify-0.17.3-np2py312h2ed9cc7_14.conda + sha256: f66d63e0afcabd2c6da0043826a1c9a1471f0b4f24c3a2f929ca47c67cd6c002 + md5: db6a33415c8419fe5eb148cc7905fcf9 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-uncrustify-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 68218 + timestamp: 1768974524311 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ament-xmllint-0.17.3-np2py312h2ed9cc7_14.conda + sha256: 03d8a3d591763b4891a2685a7d21e4542643e3ee187238d412b050baa7ecc855 + md5: 91a8abf2641d3a9da33416d4fc5d9c6b + depends: + - libxml2 + - python + - ros-jazzy-ament-lint + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 28165 + timestamp: 1768974334577 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-builtin-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + sha256: a59309c935653a53b41aa55a47be10e87eeb06e69a17e804e72a79aec001e2dd + md5: 381e6b2ad2c4e6d0ff23fe35b9ee3916 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 80018 + timestamp: 1768976227318 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-class-loader-2.7.0-np2py312h2ed9cc7_14.conda + sha256: c69d53568d70b5a8c1c58082d894fa73ec09c0da1559416806ccb5687832b53d + md5: b1c2db69a8940aff64c88d471490fef6 + depends: + - console_bridge + - python + - ros-jazzy-console-bridge-vendor + - ros-jazzy-rcpputils + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - console_bridge >=1.0.2,<1.1.0a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 74325 + timestamp: 1768975645437 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-common-interfaces-5.3.6-np2py312h2ed9cc7_14.conda + sha256: e188c2566ea6f265a348a5aba11c3589c0f91371f2d51936baa40ab20f2c957b + md5: 694bb527dec6886bb6474d5eb02c89a3 + depends: + - python + - ros-jazzy-actionlib-msgs + - ros-jazzy-builtin-interfaces + - ros-jazzy-diagnostic-msgs + - ros-jazzy-geometry-msgs + - ros-jazzy-nav-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-shape-msgs + - ros-jazzy-std-msgs + - ros-jazzy-std-srvs + - ros-jazzy-stereo-msgs + - ros-jazzy-trajectory-msgs + - ros-jazzy-visualization-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 26797 + timestamp: 1768978054215 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-composition-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + sha256: d35e8b9bfa6b4f49a9938661edd52938084ccbacb161e742d966a3aadb9f2350 + md5: a8ada4e5ee4ba505c3f1d9e0d5848cd4 + depends: + - python + - ros-jazzy-rcl-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 224475 + timestamp: 1768976648065 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-console-bridge-vendor-1.7.1-np2py312h2ed9cc7_14.conda + sha256: 59b7544f6a9fb313972ce6997012393adfdcbfa7a9b76c3f37cc600c699ec6a8 + md5: e1f8e37aed54c54de40a3e86fcf9ec3b + depends: + - console_bridge + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - console_bridge >=1.0.2,<1.1.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR BSD-3-Clause + size: 27841 + timestamp: 1768975369434 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-cyclonedds-0.10.5-np2py312h2ed9cc7_14.conda + sha256: 6bb21234dd801560eec120dc5dd0bf93e741fb1aab5c6396813981abab99acee + md5: 81dbc2a5e9cd0aba5c633e8e5efb7192 + depends: + - openssl + - python + - ros-jazzy-iceoryx-binding-c + - ros-jazzy-iceoryx-hoofs + - ros-jazzy-iceoryx-posh + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - openssl >=3.6.0,<4.0a0 + license: EPL-2.0 OR BSD-3-Clause + size: 1198707 + timestamp: 1768974223640 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-diagnostic-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 14a64e7d671c810ae93d18bf6d2984b9c77de73671712d94ae1f3cc52ac8dd13 + md5: 3d95a06eaf205864d759bf39dec65202 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 209501 + timestamp: 1768976788907 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-domain-coordinator-0.12.0-np2py312h2ed9cc7_14.conda + sha256: 9f4c63a2cbc6496f20eea8e39da663afb36ee3dbffcc70063f244a63ae4de30f + md5: a9b2ab72cfe9abb2b34520bd890e21b1 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 21162 + timestamp: 1768974323947 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-eigen3-cmake-module-0.3.0-np2py312h2ed9cc7_14.conda + sha256: 726a961f0c0bd4054f1f55a96f15551b841670605bdf2da96863faaf393dcab6 + md5: 3c03cec7abb43f8d59cfb66da82ebe63 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 23600 + timestamp: 1768974679364 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastcdr-2.2.5-np2py312h2ed9cc7_14.conda + sha256: 3ac561ca2fe4b128f27aca8aa16ea67937c82bce7adf874ad7cd2730e1119a1d + md5: a50c063080d7508d868127bc8d9f0060 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 88720 + timestamp: 1768974411517 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastrtps-2.14.5-np2py312h2ed9cc7_14.conda + sha256: fcba94d0c98353bffe9bfb22c440e6edde1b64df147eb6d750990b380c31721e + md5: 6c9772f854b8fb47ecea078d08334053 + depends: + - openssl + - python + - ros-jazzy-fastcdr + - ros-jazzy-foonathan-memory-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - tinyxml2 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - openssl >=3.6.0,<4.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - tinyxml2 >=11.0.0,<11.1.0a0 + license: Apache-2.0 + size: 4288878 + timestamp: 1768974993912 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-fastrtps-cmake-module-3.6.3-np2py312h2ed9cc7_14.conda + sha256: a8fdcb0309f4fe1df42c06bd498ad9701749204af2b147ae8371f5a424611a6d + md5: 110199549e41801294b59bc4e6c843b7 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 27574 + timestamp: 1768974982016 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-foonathan-memory-vendor-1.3.1-np2py312h2ed9cc7_14.conda + sha256: 91978bdc4e8c592845c953806b8461279b323fe7a2453e37b42d449d436fc371 + md5: b440b4ea79648b6fdc2e07b608e166c2 + depends: + - foonathan-memory + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - cmake + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - foonathan-memory >=0.7.3,<0.7.4.0a0 + license: Apache-2.0 OR Zlib + size: 19613 + timestamp: 1768974732543 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-geometry-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 45d223f66db6e9084a0d8a15106c3b4b5ad272bfd30b41888cb3924e91202099 + md5: 30a1ecf3d7eca9afe781cedb010ef31b + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 378328 + timestamp: 1768976665376 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-geometry2-0.36.18-np2py312h2ed9cc7_14.conda + sha256: aeb424213f4c4dd437513261f7ae7600864dee672aa247e11c207398e5937d70 + md5: 59a030556fde2921263d070ccf37f14c + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-bullet + - ros-jazzy-tf2-eigen + - ros-jazzy-tf2-eigen-kdl + - ros-jazzy-tf2-geometry-msgs + - ros-jazzy-tf2-kdl + - ros-jazzy-tf2-msgs + - ros-jazzy-tf2-py + - ros-jazzy-tf2-ros + - ros-jazzy-tf2-sensor-msgs + - ros-jazzy-tf2-tools + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 22579 + timestamp: 1768980322783 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gmock-vendor-1.14.9000-np2py312h2ed9cc7_14.conda + sha256: ae4d290f1f62038dea2d8067f47132491fefda516adac12f96a95ecebe9e4eb0 + md5: a1906688ae2da9d0244b93387662bd83 + depends: + - python + - ros-jazzy-gtest-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 122498 + timestamp: 1768973994404 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gtest-vendor-1.14.9000-np2py312h2ed9cc7_14.conda + sha256: 2f85954cfa7f6412fa66bd8b8eeef7a26153773155c30ff5281f9db20f7009b5 + md5: 6d62ac403f26154961e0efcf164bf02a + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 208884 + timestamp: 1768973893170 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gtsam-4.2.0-py312hfb442f0_14.conda + sha256: b65856e449839395b26c5edf262d7fa423e52c9d05831ab207228069f9a53f37 + md5: d1d8029c63ac32f562241d91c232e3d8 + depends: + - eigen + - gtsam >=4.2.0,<4.3.0a0 + - libboost-devel + - libboost-python-devel + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - tbb + - tbb-devel + - libboost-python >=1.88.0,<1.89.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libboost >=1.88.0,<1.89.0a0 + - tbb >=2022.3.0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 8974 + timestamp: 1768973884573 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-cmake-vendor-0.0.10-np2py312h2ed9cc7_14.conda + sha256: 9909360d63cfb933fdceb72c791e3f405835e007f0d1a8607caa225491b42ca1 + md5: a0257594d1efe75f1508dfce9bd48469 + depends: + - gz-cmake3 + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libgz-cmake3 >=3.5.5,<4.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 24763 + timestamp: 1768974736897 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-math-vendor-0.0.8-np2py312h2ed9cc7_14.conda + sha256: d6329fb58bddb759b5ec3511680a77d5ff5285d0f3e5897862c7ce17351e2831 + md5: 79ceaf5f8294f02e113a059b7d5aeb6b + depends: + - eigen + - gz-math7 + - python + - ros-jazzy-gz-cmake-vendor + - ros-jazzy-gz-utils-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgz-math7 >=7.5.2,<8.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 28108 + timestamp: 1768975346422 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-gz-utils-vendor-0.0.5-np2py312h2ed9cc7_14.conda + sha256: cb8d7c9417b0faecaa7c2b0cca8e68c8d6f87b9045ffebb235e9173503c3e3ab + md5: 4f317c6a5dcf52c866d3826214c5f6f5 + depends: + - gz-utils2 + - python + - ros-jazzy-gz-cmake-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - libgz-utils2 >=2.2.1,<3.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 26181 + timestamp: 1768975009289 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-binding-c-2.0.6-np2py312h2ed9cc7_14.conda + sha256: 8f010888b7ea6b9875445af532fab0859673107a70fb7f5c3a4767d95c312015 + md5: aa351521475dbea357447318c72eecfe + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 93049 + timestamp: 1768974102613 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-hoofs-2.0.6-np2py312h2ed9cc7_14.conda + sha256: a3ecb7c3bad08d61cac049f17fa08f539ad7313efc308445ef18256bdf59f999 + md5: f58696012dc006e97b4b83ee20f563ef + depends: + - libacl + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - libacl >=2.3.2,<2.4.0a0 + license: Apache-2.0 + size: 263886 + timestamp: 1768973871610 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-iceoryx-posh-2.0.6-np2py312h2ed9cc7_14.conda + sha256: ac7b6b1e2bf01d21fc28719ef509f8535fc078ac439738dc832ee7789f2e60ac + md5: ceab222eb87fcd6896336b24914cab84 + depends: + - python + - ros-jazzy-iceoryx-hoofs + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 573882 + timestamp: 1768973997324 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-image-transport-5.1.7-np2py312h2ed9cc7_14.conda + sha256: b1160bba9c4a83d5ebc3d22a678e4784cda0959b60aa06604a66080ac60712dd + md5: c037c91a9d24569547f4e8a21e7bc6b2 + depends: + - python + - ros-jazzy-message-filters + - ros-jazzy-pluginlib + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 579122 + timestamp: 1768979167412 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-interactive-markers-2.5.5-np2py312h2ed9cc7_14.conda + sha256: c7241cabc60b41053ca2c05e2e313e13410f4905f2d54c51f9f801a103ba3a94 + md5: 31acd36893365f55707a8cd92a6ab901 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-rclcpp + - ros-jazzy-rclpy + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-std-msgs + - ros-jazzy-tf2 + - ros-jazzy-tf2-geometry-msgs + - ros-jazzy-visualization-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: BSD-3-Clause + size: 306955 + timestamp: 1768979892451 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-kdl-parser-2.11.0-np2py312h2ed9cc7_14.conda + sha256: cb216c6777e04ae1993b9e65e4169c0e3071a69d08ca655b4e10d30937ed31d0 + md5: cdcf417482aa5451d665eeed7ea2bb73 + depends: + - python + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-urdf + - ros-jazzy-urdfdom-headers + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 47346 + timestamp: 1768976075902 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-keyboard-handler-0.3.1-np2py312h2ed9cc7_14.conda + sha256: b376f89823533483cffb3e41ad81346a4f62ecd69951351bc2bf3dc2279c52c4 + md5: 1e3381a670c96da20d3a5275cdd8b29e + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 56303 + timestamp: 1768975031999 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-laser-geometry-2.7.2-np2py312h2ed9cc7_14.conda + sha256: b64921a1723e46872f881bd3675a1031742b261e30a774aeff995fb83fce4d63 + md5: 3ee05aecb92144881b48053608362125 + depends: + - eigen + - numpy + - python + - ros-jazzy-eigen3-cmake-module + - ros-jazzy-rclcpp + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-sensor-msgs-py + - ros-jazzy-tf2 + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 61545 + timestamp: 1768978489268 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-3.4.9-np2py312h2ed9cc7_14.conda + sha256: a7b7ca6d7c915792b84a2dd6e40e2f8ca9b7d2b440a15c83b30d46f40ed18641 + md5: eece9b9118bda0c5bae30681a3267ef5 + depends: + - importlib-metadata + - lark-parser + - python + - pyyaml + - ros-jazzy-ament-index-python + - ros-jazzy-osrf-pycommon + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 235443 + timestamp: 1768974397719 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-ros-0.26.10-np2py312h2ed9cc7_14.conda + sha256: c160af2015648c7d6b4811e71503fd3464138fe322f4f917f625f34d0dcd62d8 + md5: 194c6e171fa85836d6f461afae155c46 + depends: + - importlib-metadata + - python + - pyyaml + - ros-jazzy-ament-index-python + - ros-jazzy-composition-interfaces + - ros-jazzy-launch + - ros-jazzy-lifecycle-msgs + - ros-jazzy-osrf-pycommon + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 128002 + timestamp: 1768978481518 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-3.4.9-np2py312h2ed9cc7_14.conda + sha256: 49949bf40443150f07f34fd0762a86acd2e2870ee4a8cffcdae28a5551c2bd88 + md5: e025ba63f56fc312b2e6470867a64d4f + depends: + - pytest + - python + - ros-jazzy-ament-index-python + - ros-jazzy-launch + - ros-jazzy-launch-xml + - ros-jazzy-launch-yaml + - ros-jazzy-osrf-pycommon + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 115977 + timestamp: 1768974672239 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-ament-cmake-3.4.9-np2py312h2ed9cc7_14.conda + sha256: f967b76acff72df08cf6028a7e6794a73f8f74cee238ff2e1d2391003d8bdaf2 + md5: 80dbdaf04ea1a78698258e2a6bab433e + depends: + - python + - ros-jazzy-ament-cmake-test + - ros-jazzy-launch-testing + - ros-jazzy-python-cmake-module + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 OR BSD-3-Clause + size: 27342 + timestamp: 1768975330125 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-testing-ros-0.26.10-np2py312h2ed9cc7_14.conda + sha256: b538c003f443fb610a36c1e8ecde0405d1a04f10f4ce3b727726ad71bcbd13cd + md5: 51cabc505aafe4e61c1e533d5da2bf08 + depends: + - python + - ros-jazzy-ament-index-python + - ros-jazzy-launch-ros + - ros-jazzy-launch-testing + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 52124 + timestamp: 1768978670276 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-xml-3.4.9-np2py312h2ed9cc7_14.conda + sha256: 41671c6138e27d3dfa04c59b952ec0f084b01f813da674be77166e3e30a9af7a + md5: f70b975a10ced6a1031ede610f3e2ad6 + depends: + - python + - ros-jazzy-launch + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 26211 + timestamp: 1768974536054 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-launch-yaml-3.4.9-np2py312h2ed9cc7_14.conda + sha256: 3f1a44cdfabb9114f6cb554e97218d59d5e586d3eb4688bfebd860aeaa3f45a6 + md5: 51a9ae73837b23e9ed3cb22733f3e09e + depends: + - python + - ros-jazzy-launch + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 26763 + timestamp: 1768974530568 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libcurl-vendor-3.4.4-np2py312h2ed9cc7_14.conda + sha256: 83d8b640abc07769de68c488ae41fd6abb0bf95d4da0d86710e6bfe0098c9e69 + md5: 02eb1bc519dd239ee17bd704e3443243 + depends: + - libcurl + - pkg-config + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - libcurl >=8.18.0,<9.0a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR MIT + size: 24022 + timestamp: 1768974398717 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-liblz4-vendor-0.26.9-np2py312h2ed9cc7_14.conda + sha256: ecd9439a6b2bd9ccd1b7f0d4989433d890ca1fbea7aadedc1614d5de5b966328 + md5: 90a5dc8f9898a82eee68beca3724ec7f + depends: + - lz4 + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 OR BSD-3-Clause OR GPL-2.0-only + size: 24164 + timestamp: 1768974412856 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libstatistics-collector-1.7.4-np2py312h2ed9cc7_14.conda + sha256: d62517ec97ae1f6092dd2c9671fb679af5559002ee0478c1b584a64ac9f6d4a0 + md5: ef16f94cbbc4a58ef8531b326bf69a69 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-rcl + - ros-jazzy-rcpputils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-statistics-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 58653 + timestamp: 1768978155993 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-libyaml-vendor-1.6.3-np2py312h2ed9cc7_14.conda + sha256: 7d78f69d773ce404c673608accad28589976a7f641c74cc7f0cb4a494a501e60 + md5: 275fd48396be8b164dcd049157bd6e03 + depends: + - pkg-config + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - yaml + - yaml-cpp + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - yaml >=0.2.5,<0.3.0a0 + - numpy >=1.23,<3 + - yaml-cpp >=0.8.0,<0.9.0a0 + license: Apache-2.0 OR MIT + size: 29785 + timestamp: 1768975364622 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-lifecycle-msgs-2.0.3-np2py312h2ed9cc7_14.conda + sha256: d9260b8b62217c2115b3c2d182b82c3e60eede9e27f2d0149a7a647547ea450c + md5: 24696c77b54e41934b37fbb9b74193c1 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 268422 + timestamp: 1768976385186 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-map-msgs-2.4.1-np2py312h2ed9cc7_14.conda + sha256: c3928bd8e8506e259d8d5a46b71be8b2a403a8e550fede229b486feba53f8f0c + md5: dd224650948f01fc110335a46f3f8bc2 + depends: + - python + - ros-jazzy-nav-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 346433 + timestamp: 1768977054937 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-mcap-vendor-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 50435a59b378cb15653089279278c3a19ec8306a79d19899f215d77729586dfb + md5: 28a79a8794c4b272324cfb6dfcd2c3e4 + depends: + - python + - ros-jazzy-liblz4-vendor + - ros-jazzy-ros-workspace + - ros-jazzy-zstd-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 172905 + timestamp: 1768974539988 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-message-filters-4.11.9-np2py312h2ed9cc7_14.conda + sha256: 163f1ac45d52683833d38d0313a38f7e331a58330923250a4f020edd809126df + md5: 6027ba4d12cd1d9b6c50ea8298b506d8 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-rclcpp + - ros-jazzy-rclpy + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 82853 + timestamp: 1768978685416 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-nav-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 22dfe512aae9adb3d125f324a0fa5c31a74d8518a728c714778fbc1c9e0faa1a + md5: f7f9f73ec85a7d89b47d6eb13415c486 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 315493 + timestamp: 1768976736613 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-orocos-kdl-vendor-0.5.1-np2py312h2ed9cc7_14.conda + sha256: 6f5f48757332fd68c511fbe26e0e135de9fc3386a376f689f1426a0cc72ba7c5 + md5: c4f6a3580fb31dce3c1dfff78ef3b268 + depends: + - eigen + - orocos-kdl + - python + - ros-jazzy-eigen3-cmake-module + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - orocos-kdl >=1.5.3,<1.6.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR LGPL-2.1-or-later + size: 28189 + timestamp: 1768975024091 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-osrf-pycommon-2.1.7-np2py312h2ed9cc7_14.conda + sha256: 1f901727bc29bc4dc8525d5f026147addcf3292856236d7aee5906a75801daa5 + md5: 6c1b85c9a373e69eca4501b6c7426b18 + depends: + - importlib-metadata + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 64649 + timestamp: 1768973918027 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-pluginlib-5.4.4-np2py312h2ed9cc7_14.conda + sha256: 1cda406671991a3930216562d77a6e60112a4275b6cfe6fad34288f828e070ef + md5: 6f19d678c419bd2058f90df84b4b9569 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-class-loader + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-tinyxml2-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 138704 + timestamp: 1768975727582 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-point-cloud-transport-4.0.6-np2py312h2ed9cc7_14.conda + sha256: 8ffa7058cfc6fabb2bc90152f08cd6215719d1508c7e47a54c8c85899bc1be0f + md5: fca56ea1c3c0d87d0f8af7de5de2a28f + depends: + - python + - ros-jazzy-message-filters + - ros-jazzy-pluginlib + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-rcpputils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 457512 + timestamp: 1768979117761 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-pybind11-vendor-3.1.3-np2py312h2ed9cc7_14.conda + sha256: 56c8ee3cda3cd21ca27f32da429c7e58799c739360e17f4a20c816e0497f99c3 + md5: a100e13e94fe4405aaa8827e398709dc + depends: + - pybind11 + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 OR BSD-3-Clause + size: 23260 + timestamp: 1768974403067 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-python-cmake-module-0.11.1-np2py312h2ed9cc7_14.conda + sha256: e0047fff1c399850a62227f329833e78789d03ae4ba6c257ed3d739a1ba84a28 + md5: eb952691c28706d73bad84c95fd8d1c6 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 27935 + timestamp: 1768974983495 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-python-orocos-kdl-vendor-0.5.1-np2py312h2ed9cc7_14.conda + sha256: f54fd4ef91e05bb46d7c2926b24a300b83e94c24f8061941cf4712661a97ae63 + md5: ca2187fc758bbad2251a80c59c49dbb2 + depends: + - python + - python-orocos-kdl + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-pybind11-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - python-orocos-kdl >=1.5.3,<1.6.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR LGPL-2.1-or-later + size: 27812 + timestamp: 1768975351921 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-9.2.8-np2py312h2ed9cc7_14.conda + sha256: 1c7cde7016ad5ad1be6e41ed390bcc5c8ffc4dafacab55bc088a0f8c650aba58 + md5: 06b959e1b92ef2d77470956ccbc7b850 + depends: + - python + - ros-jazzy-libyaml-vendor + - ros-jazzy-rcl-interfaces + - ros-jazzy-rcl-logging-interface + - ros-jazzy-rcl-logging-spdlog + - ros-jazzy-rcl-yaml-param-parser + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-implementation + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-service-msgs + - ros-jazzy-tracetools + - ros-jazzy-type-description-interfaces + - ros2-distro-mutex 0.13.* jazzy_* + - yaml + - yaml-cpp + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - yaml >=0.2.5,<0.3.0a0 + - python_abi 3.12.* *_cp312 + - yaml-cpp >=0.8.0,<0.9.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 201622 + timestamp: 1768977844926 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-action-9.2.8-np2py312h2ed9cc7_14.conda + sha256: fe369f5896b6103ff61d8aa6c027f649c434c998e0a99e9fbd4507bf364ca1ab + md5: a1ea8b44b9ae35faa3819677a94550d2 + depends: + - python + - ros-jazzy-action-msgs + - ros-jazzy-rcl + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 81163 + timestamp: 1768978180405 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + sha256: aa7783d0cf05302de58e975d1eef6fbf0368d7bc16b2f6fdd221172a4e40f421 + md5: 2bce0706b67791d52af863956ca949c8 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 569511 + timestamp: 1768976453398 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-lifecycle-9.2.8-np2py312h2ed9cc7_14.conda + sha256: 053688b26ebcdd475ecb5010340c392beecda070ad1042d3c6aa7747bd8b0cc9 + md5: 7930c8d143261bcac343020cadeac459 + depends: + - python + - ros-jazzy-lifecycle-msgs + - ros-jazzy-rcl + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 58370 + timestamp: 1768978173912 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-logging-interface-3.1.1-np2py312h2ed9cc7_14.conda + sha256: 967429a426b0809ddb8ac6feba05964e9a35bd5bf26ef5e05f74af619d2f56b2 + md5: d50a835756fbddb6c515bd9d364526a9 + depends: + - python + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 35777 + timestamp: 1768975640279 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-logging-spdlog-3.1.1-np2py312h918b84f_14.conda + sha256: 47fc35efa603542d51f36b3b38cea752473c08fb3add167fb8337bd3631e3723 + md5: 754c71354eac1429fb7b1ff4c8ad1b87 + depends: + - fmt + - python + - ros-jazzy-rcl-logging-interface + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-spdlog-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - spdlog + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - fmt >=12.1.0,<12.2.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - spdlog >=1.17.0,<1.18.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 46361 + timestamp: 1768975763128 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcl-yaml-param-parser-9.2.8-np2py312h2ed9cc7_14.conda + sha256: 1ebc21df430035e1d1a3dce22a6c3eb42f0015e27e76cd8d436d86e3aa66e1e6 + md5: cba13abce8198c1dab68eaad4c46b178 + depends: + - python + - ros-jazzy-libyaml-vendor + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - yaml + - yaml-cpp + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - yaml-cpp >=0.8.0,<0.9.0a0 + - numpy >=1.23,<3 + - yaml >=0.2.5,<0.3.0a0 + license: Apache-2.0 + size: 51898 + timestamp: 1768975891823 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-28.1.15-np2py312h2ed9cc7_14.conda + sha256: e256e3ab02c258c5bcaf91e98fe9d62c9be698781f255dbac097410e5050aac1 + md5: f87f9a6cf86a992947efa5b26d5fcd10 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-builtin-interfaces + - ros-jazzy-libstatistics-collector + - ros-jazzy-rcl + - ros-jazzy-rcl-interfaces + - ros-jazzy-rcl-logging-interface + - ros-jazzy-rcl-yaml-param-parser + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosgraph-msgs + - ros-jazzy-rosidl-dynamic-typesupport + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-c + - ros-jazzy-rosidl-typesupport-cpp + - ros-jazzy-statistics-msgs + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 1095467 + timestamp: 1768978260712 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-action-28.1.15-np2py312h2ed9cc7_14.conda + sha256: 6341d98fb8c77cbfcc1921d83d30878eb80fca2ea14eb06a2bc682bbb2bcf6a8 + md5: 3ad40873435938a024ff0bee421343c7 + depends: + - python + - ros-jazzy-action-msgs + - ros-jazzy-ament-cmake + - ros-jazzy-rcl + - ros-jazzy-rcl-action + - ros-jazzy-rclcpp + - ros-jazzy-rcpputils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 116958 + timestamp: 1768978503206 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-components-28.1.15-np2py312h2ed9cc7_14.conda + sha256: f2e855351daab270fd6dda12cf1fff28fdb4d4c3d170844981a9c78142eb900b + md5: b2a094803b3ff245fe62718c1b6e4d45 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-class-loader + - ros-jazzy-composition-interfaces + - ros-jazzy-rclcpp + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 140530 + timestamp: 1768978451108 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclcpp-lifecycle-28.1.15-np2py312h2ed9cc7_14.conda + sha256: 00a2e724cefdbbb1e25bdd5e1df14e66b11d78f4c009b9574068b8d9864a1681 + md5: 828de2495d3c3981d27d4f895b593743 + depends: + - python + - ros-jazzy-lifecycle-msgs + - ros-jazzy-rcl + - ros-jazzy-rcl-interfaces + - ros-jazzy-rcl-lifecycle + - ros-jazzy-rclcpp + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-typesupport-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 131343 + timestamp: 1768978488167 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rclpy-7.1.8-np2py312h2ed9cc7_14.conda + sha256: e4a4ae0ea390bee4b59b536290999e459858618669a586521cb40cb1b8d91d8c + md5: ff3460adf5e2ab3279507dd480e2f40a + depends: + - python + - pyyaml + - ros-jazzy-action-msgs + - ros-jazzy-ament-index-python + - ros-jazzy-builtin-interfaces + - ros-jazzy-lifecycle-msgs + - ros-jazzy-rcl + - ros-jazzy-rcl-action + - ros-jazzy-rcl-interfaces + - ros-jazzy-rcl-lifecycle + - ros-jazzy-rcl-logging-interface + - ros-jazzy-rcl-yaml-param-parser + - ros-jazzy-rmw + - ros-jazzy-rmw-implementation + - ros-jazzy-ros-workspace + - ros-jazzy-rosgraph-msgs + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rpyutils + - ros-jazzy-unique-identifier-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 735886 + timestamp: 1768978360779 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcpputils-2.11.2-np2py312h2ed9cc7_14.conda + sha256: ffe1935988dffcbe6f501b508adb5de33de1b44695a373f8262ab0fcc73c892e + md5: dacbfb3bb7ec86747ccde9085b112ae9 + depends: + - python + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 OR BSD-3-Clause + size: 80726 + timestamp: 1768975554650 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rcutils-6.7.5-np2py312h2ed9cc7_14.conda + sha256: df6214a2a2ba8352257795789e2ac94eab5ff079a32620cc9cf63198ce578168 + md5: 9319e625a9560b6cb5e430684918015c + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 122709 + timestamp: 1768975435896 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-resource-retriever-3.4.4-np2py312h2ed9cc7_14.conda + sha256: 13c832809294f4d0b612ea872c9f877884180dcbdfa0d18743337be8dd55a30b + md5: 59ed11c685187e4ababa21b34bf752e2 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-ament-index-python + - ros-jazzy-libcurl-vendor + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 45325 + timestamp: 1768975357212 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-7.3.2-np2py312h2ed9cc7_14.conda + sha256: 9c4858a19b525799a5d9a92d45130e731b5bc858b3317c1a230b37d7345eded5 + md5: 1f0a131e3d46459cb835cb9c9c0181b1 + depends: + - python + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-dynamic-typesupport + - ros-jazzy-rosidl-runtime-c + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 97299 + timestamp: 1768975743550 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-connextdds-0.22.2-np2py312h2ed9cc7_14.conda + sha256: f99e36af7b2961ab959d6cfd151fa1b2a6a689b8781e1929a6d65d4b7422c9c6 + md5: 5acb79abe4c14bb0bd0825ddca097e19 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-rmw-connextdds-common + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 32329 + timestamp: 1768976798404 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-connextdds-common-0.22.2-np2py312h2ed9cc7_14.conda + sha256: 0dfad90cab5264a20e14068cd32cc46a446c520c3c8a764dfda1ae79a5324c3d + md5: 34618631f78db85598103b9be7c45978 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-fastcdr + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-dds-common + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-fastrtps-c + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros-jazzy-rti-connext-dds-cmake-module + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 54193 + timestamp: 1768976624369 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-cyclonedds-cpp-2.2.3-np2py312h2ed9cc7_14.conda + sha256: 66a74e037b0dbbbc4e85a081e29ceb027aec5ee8d4c1651ae80b23546d4b8fef + md5: 3c54ed21c169d85959876c929656057b + depends: + - python + - ros-jazzy-cyclonedds + - ros-jazzy-iceoryx-binding-c + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-dds-common + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 266229 + timestamp: 1768976629746 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-dds-common-3.1.0-np2py312h2ed9cc7_14.conda + sha256: 2905a5a97b0f5af1477f8715096fc094e95c16cec3e0f9af4667fef229dd97ed + md5: 770e58be48620344ebcbdf2095d63ef9 + depends: + - python + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 178466 + timestamp: 1768976384062 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-cpp-8.4.3-np2py312h2ed9cc7_14.conda + sha256: efd857334e45824b8fcf5189a696ff0ed053791393c8a965f8839c9007f0884e + md5: ec8b88678387d7950d826f099e03eaf3 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps + - ros-jazzy-fastrtps-cmake-module + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-dds-common + - ros-jazzy-rmw-fastrtps-shared-cpp + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-dynamic-typesupport + - ros-jazzy-rosidl-dynamic-typesupport-fastrtps + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-fastrtps-c + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 160248 + timestamp: 1768976774645 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-dynamic-cpp-8.4.3-np2py312h2ed9cc7_14.conda + sha256: 6e27fd7258807a84422e3e00e405f4167b3d6c84cefeaae956c897c3bb9fb8a3 + md5: f751d214875063e22b465eac98efc164 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps + - ros-jazzy-fastrtps-cmake-module + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-dds-common + - ros-jazzy-rmw-fastrtps-shared-cpp + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 187563 + timestamp: 1768976737754 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-fastrtps-shared-cpp-8.4.3-np2py312h2ed9cc7_14.conda + sha256: 7dae7103e2d8376606cd5d96c344b610dd7eedc85b787ccc716a4ba7a78ac37e + md5: ed4609ca17536cec026a80f03659db9b + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps + - ros-jazzy-fastrtps-cmake-module + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-dds-common + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-dynamic-typesupport + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros-jazzy-tracetools + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 232149 + timestamp: 1768976570653 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-implementation-2.15.6-np2py312h2ed9cc7_14.conda + sha256: ffe0334f688571b9cbc3c1b63cf3b16ce657a3ab140bf839238f30a3e73a7ca7 + md5: a2254994d551b9a2c35aff135be00073 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw-connextdds + - ros-jazzy-rmw-cyclonedds-cpp + - ros-jazzy-rmw-fastrtps-cpp + - ros-jazzy-rmw-fastrtps-dynamic-cpp + - ros-jazzy-rmw-implementation-cmake + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 54560 + timestamp: 1768977041693 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rmw-implementation-cmake-7.3.2-np2py312h2ed9cc7_14.conda + sha256: 62e26c18b49c744bbac3f56046f0d8b97954cdddd508dfeacc61715c4bf0a339 + md5: 2343037a0def9aff02f5142283e17c4c + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 29430 + timestamp: 1768975295492 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-robot-state-publisher-3.3.3-np2py312h2ed9cc7_14.conda + sha256: eb91744342b96655dfa06322e6d4b1aa944aa1b0fb0f1db0c3d7c59870a415e5 + md5: f51ae7fe899d397419a15746d7c2eb27 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-kdl-parser + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-rcl-interfaces + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros-jazzy-tf2-ros + - ros-jazzy-urdf + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 271296 + timestamp: 1768979391154 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-base-0.11.0-np2py312h2ed9cc7_14.conda + sha256: f1bd438015474daa1109d638f4fc8c173f7db9ee1aabe99469d6c9e9de3bdd3e + md5: 0df82d497e19bb2eea4762cb233f2deb + depends: + - python + - ros-jazzy-geometry2 + - ros-jazzy-kdl-parser + - ros-jazzy-robot-state-publisher + - ros-jazzy-ros-core + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2 + - ros-jazzy-urdf + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 22419 + timestamp: 1768983028479 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-core-0.11.0-np2py312h2ed9cc7_14.conda + sha256: bbf46b1cdb2bab21b5be2b4eb5951d6cd972d16c360479b88b35faa8a335959f + md5: 90dc3d179fee8315101f475142a819f6 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-cmake-auto + - ros-jazzy-ament-cmake-gmock + - ros-jazzy-ament-cmake-gtest + - ros-jazzy-ament-cmake-pytest + - ros-jazzy-ament-cmake-ros + - ros-jazzy-ament-index-cpp + - ros-jazzy-ament-index-python + - ros-jazzy-ament-lint-auto + - ros-jazzy-ament-lint-common + - ros-jazzy-class-loader + - ros-jazzy-common-interfaces + - ros-jazzy-launch + - ros-jazzy-launch-ros + - ros-jazzy-launch-testing + - ros-jazzy-launch-testing-ament-cmake + - ros-jazzy-launch-testing-ros + - ros-jazzy-launch-xml + - ros-jazzy-launch-yaml + - ros-jazzy-pluginlib + - ros-jazzy-rcl-lifecycle + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-action + - ros-jazzy-rclcpp-lifecycle + - ros-jazzy-rclpy + - ros-jazzy-ros-environment + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli-common-extensions + - ros-jazzy-ros2launch + - ros-jazzy-rosidl-default-generators + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-sros2 + - ros-jazzy-sros2-cmake + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 23140 + timestamp: 1768981484745 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-environment-4.2.1-np2py312h2ed9cc7_14.conda + sha256: 0a8a48bfbd5c8d55589dca785eb33e34dcb5407e8d6f3713bd5895b20d49b309 + md5: a8f3763b9bf80f2655c88f33c3676378 + depends: + - python + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 21436 + timestamp: 1768973849657 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros-workspace-1.0.3-np2py312h2ed9cc7_14.conda + sha256: b5a698ba2d85f3165078b53b3323944bbad903f92dfe212445fa7d2f7d2690d9 + md5: 5b8de3785c7ed4184311fb3c675a6b74 + depends: + - python + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 35477 + timestamp: 1768973829714 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2action-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 74f3bfac8edbe66cdcef9c250915358acf92166015f514dccfacd171f79a613e + md5: 726695d6b6deddec938ac5c214d3fab5 + depends: + - python + - ros-jazzy-action-msgs + - ros-jazzy-ament-index-python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-rosidl-runtime-py + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 47789 + timestamp: 1768979163443 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2bag-0.26.9-np2py312h2ed9cc7_14.conda + sha256: c442fedaad1166c88c1187cb67b94108ae92517abd1bf674026e111ccdde01af + md5: a04d69c6d7ce9714b980eb632eb21d4c + depends: + - python + - pyyaml + - ros-jazzy-ament-index-python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-rosbag2-py + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 71169 + timestamp: 1768982313466 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2cli-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 2d7839340e9ab8f1968689bdca4279000e317d26431fe5292d1baaa513266b16 + md5: 4b5d39304c2cf7893ea83b0e6da8af88 + depends: + - argcomplete + - importlib-metadata + - packaging + - psutil + - python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 75931 + timestamp: 1768978512534 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2cli-common-extensions-0.3.1-np2py312h2ed9cc7_14.conda + sha256: f4abb3569ce5278a1f6aef4009ba7e26c59def78535a8a18696ec9a709c52360 + md5: 7ebd190255f639df0a53f1bb04e69e9d + depends: + - python + - ros-jazzy-launch-xml + - ros-jazzy-launch-yaml + - ros-jazzy-ros-workspace + - ros-jazzy-ros2action + - ros-jazzy-ros2cli + - ros-jazzy-ros2component + - ros-jazzy-ros2doctor + - ros-jazzy-ros2interface + - ros-jazzy-ros2launch + - ros-jazzy-ros2lifecycle + - ros-jazzy-ros2multicast + - ros-jazzy-ros2node + - ros-jazzy-ros2param + - ros-jazzy-ros2pkg + - ros-jazzy-ros2plugin + - ros-jazzy-ros2run + - ros-jazzy-ros2service + - ros-jazzy-ros2topic + - ros-jazzy-sros2 + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 26910 + timestamp: 1768981120245 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2component-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 5d1332cf1460418d6dd97549145fd85a9ebaa45be861a84944d6b8537b95d59c + md5: 2656018ebe4ad9a411a63e5ed5f7edd0 + depends: + - python + - ros-jazzy-ament-index-python + - ros-jazzy-composition-interfaces + - ros-jazzy-rcl-interfaces + - ros-jazzy-rclcpp-components + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2node + - ros-jazzy-ros2param + - ros-jazzy-ros2pkg + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 38279 + timestamp: 1768980306819 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2doctor-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 0f045edab2401b62f061b57a1aa40a3965bb4735c4c5ccb4d70d4fdb4513a6d9 + md5: c2ff63f58f9f6f3d8aff63563202a6c6 + depends: + - catkin_pkg + - importlib-metadata + - psutil + - python + - ros-jazzy-ament-index-python + - ros-jazzy-rclpy + - ros-jazzy-ros-environment + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - rosdistro + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 68443 + timestamp: 1768979157888 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2interface-0.32.7-np2py312h2ed9cc7_14.conda + sha256: b5cdff8b886ec4c20bf145f9f57b8d8f3d028b9a5635421828bbcbb8e5f282e7 + md5: 1a7ddf9dbb4d1d83d9438170d2905af3 + depends: + - python + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-rosidl-adapter + - ros-jazzy-rosidl-runtime-py + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 46839 + timestamp: 1768979152130 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2launch-0.26.10-np2py312h2ed9cc7_14.conda + sha256: 0e8bd91e9a6f2cb17c48668c36ea9fc0ab15ad799cdb161f1c0b9103177229cf + md5: fef4dd172bf26b5f08cecb136dc98c6b + depends: + - python + - ros-jazzy-ament-index-python + - ros-jazzy-launch + - ros-jazzy-launch-ros + - ros-jazzy-launch-xml + - ros-jazzy-launch-yaml + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2pkg + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 46593 + timestamp: 1768979370088 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2lifecycle-0.32.7-np2py312h2ed9cc7_14.conda + sha256: e1e14b1ee5cd275cdaf1d713f56b6f14b6917f30f70837acbd3b359f4a462594 + md5: ac35e99c47b0c9a5ef58b1a1084c075f + depends: + - python + - ros-jazzy-lifecycle-msgs + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2node + - ros-jazzy-ros2service + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 45451 + timestamp: 1768979856824 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2multicast-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 536c638f2ab4139c0b97a726f9abe0f8ea83f279ac6ed3774db4b671c4087425 + md5: 4b261b2f8019822f218b11eddce47638 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 25808 + timestamp: 1768978680139 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2node-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 3dd8be7535c99fcae36bd80209b606fa84d98fc9fbd7cb7d4396f26012b0fb4b + md5: 7e7449de96b9a9734b7607d6ec819f2d + depends: + - python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 43253 + timestamp: 1768979146214 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2param-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 7659291272c73cb608156607ab946cfe67025d73d45337c5d6d93920c76917ee + md5: 962196896c34d1130afb27097dfed20f + depends: + - python + - ros-jazzy-rcl-interfaces + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2node + - ros-jazzy-ros2service + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 50525 + timestamp: 1768979843742 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2pkg-0.32.7-np2py312h2ed9cc7_14.conda + sha256: c5b2e611d182f476b3101977859aaa18e72a5fbf9ad026f528ea1aa90d92d04c + md5: 64b34fb408cbfc74cfbf17a777428412 + depends: + - catkin_pkg + - empy + - importlib_resources + - python + - ros-jazzy-ament-copyright + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 60620 + timestamp: 1768979118240 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2plugin-5.4.4-np2py312h2ed9cc7_14.conda + sha256: 7b6e84afb6cd102a1e203e5e98a12b8f498099d01bef26074f9af42e73bb1047 + md5: bb1978c4602798737792a0375b4865cb + depends: + - python + - ros-jazzy-ament-index-python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2pkg + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 25880 + timestamp: 1768979366072 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2run-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 9a34174bd5c99b792a184b85e7f81f66ffeea4e8053441438b9bbb842b8fa1a9 + md5: 6f1a3359f62f6111702c2983065fa3ba + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2pkg + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 24950 + timestamp: 1768979350305 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2service-0.32.7-np2py312h2ed9cc7_14.conda + sha256: bcb8e62b446606bfb1d275e8bb9c31c6c64e19ab1a2bbc33ab71d19c70f00a2f + md5: 0c700b76c3c1dd06442fe97fde6654c3 + depends: + - python + - pyyaml + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-ros2topic + - ros-jazzy-rosidl-runtime-py + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 51706 + timestamp: 1768979384169 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-ros2topic-0.32.7-np2py312h2ed9cc7_14.conda + sha256: 6a1701fe55d9964758fbd7a5e20c263ef7923f42537e9521f443cbe5e3cf9490 + md5: bc807ac515c9d12cc9adbbcb75156e74 + depends: + - numpy + - python + - pyyaml + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-rosidl-runtime-py + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 OR BSD-3-Clause + size: 74302 + timestamp: 1768979139036 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-0.26.9-np2py312h2ed9cc7_14.conda + sha256: d0b941cec22903796337ea5054b364513bdfb0fd1da92ed2e907d191967a9499 + md5: d44d51ef022b3459559ab1f9a05773e2 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2bag + - ros-jazzy-rosbag2-compression + - ros-jazzy-rosbag2-compression-zstd + - ros-jazzy-rosbag2-cpp + - ros-jazzy-rosbag2-py + - ros-jazzy-rosbag2-storage + - ros-jazzy-rosbag2-storage-default-plugins + - ros-jazzy-rosbag2-transport + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 35532 + timestamp: 1768982902781 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-compression-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 9d523a536912ed7231d341f4277e218e96e23d52053e1c1f65aec87b43a6ed6d + md5: 4cf874239c0c3fb205989e776b3b0b4a + depends: + - python + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-cpp + - ros-jazzy-rosbag2-storage + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 205561 + timestamp: 1768980984145 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-compression-zstd-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 6650a00225f38700f6da7b7dcaf134d1536e4437175712bcb6ad77e78b348b9e + md5: c6894ccc75c7d6975372d932bb944a4a + depends: + - python + - ros-jazzy-pluginlib + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-compression + - ros-jazzy-zstd-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 70349 + timestamp: 1768981273167 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-cpp-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 88d7f8ffd92136b831ef6d893b158ef819b528cb71971faebea9818ac77146e3 + md5: 1854620413f284709a03f423663f9c87 + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-pluginlib + - ros-jazzy-rclcpp + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-rmw-implementation + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-storage + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-cpp + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 349674 + timestamp: 1768979792947 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-interfaces-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 7df07c0b6234c29e6bfdb6c649721a92d76309cc80fdb3f2bd37192e4f4c01a4 + md5: fb64daf44557ba93b764a3454e9b7c6a + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 461260 + timestamp: 1768976441609 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-py-0.26.9-np2py312h2ed9cc7_14.conda + sha256: edfc54c0480ce6c76f59c7c397496f86d90d4ae7afb73569447d66c2edd07893 + md5: eab13fee43c44aa057505d4d483dcf00 + depends: + - python + - ros-jazzy-pybind11-vendor + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-compression + - ros-jazzy-rosbag2-cpp + - ros-jazzy-rosbag2-storage + - ros-jazzy-rosbag2-transport + - ros-jazzy-rpyutils + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 792173 + timestamp: 1768982060888 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 39645728f1c552a2b6de88174581b0360286d7db543b97b3322c4bd72f6c40fe + md5: d20b8b409371befbda6aedc8c412b9a4 + depends: + - python + - ros-jazzy-pluginlib + - ros-jazzy-rclcpp + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-yaml-cpp-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 278354 + timestamp: 1768978669281 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-default-plugins-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 8b1e0efd7f2e161d1a8270c6e130cd886af08aa4a9011c2892c60075952924ef + md5: a83bead6bfb0f35f03f0d8f1ea752464 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-storage-mcap + - ros-jazzy-rosbag2-storage-sqlite3 + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 22417 + timestamp: 1768979573287 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-mcap-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 37bc64fe623edf5daaa92a3a7267f02ec27d8cd76d6c9e03f2fd6cf03d9a2661 + md5: e4610f952374ba5a640834dbe0ada84c + depends: + - python + - ros-jazzy-ament-index-cpp + - ros-jazzy-mcap-vendor + - ros-jazzy-pluginlib + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-storage + - ros-jazzy-yaml-cpp-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 197761 + timestamp: 1768979284026 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-storage-sqlite3-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 10e9dd3d17b366cb59856823b34cb0c94458c1df7dfb0edf3351a603afd2cfd0 + md5: 20b889a8c2525da8cf98e9d22c01edad + depends: + - python + - ros-jazzy-pluginlib + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-storage + - ros-jazzy-sqlite3-vendor + - ros-jazzy-yaml-cpp-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 244572 + timestamp: 1768979265156 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosbag2-transport-0.26.9-np2py312h2ed9cc7_14.conda + sha256: 51f1e1b65efc0d9f9dda6d3de864ee2d79731e6139d26f099194c9f852c75fd5 + md5: 49e5cc6805831c8812e7b3cc89942c85 + depends: + - python + - ros-jazzy-keyboard-handler + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosbag2-compression + - ros-jazzy-rosbag2-cpp + - ros-jazzy-rosbag2-interfaces + - ros-jazzy-rosbag2-storage + - ros-jazzy-yaml-cpp-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 526898 + timestamp: 1768981484610 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosgraph-msgs-2.0.3-np2py312h2ed9cc7_14.conda + sha256: e071cbd996676ea80a16876ee5d54f089f5bb7592bc370c1baa3923dc6402958 + md5: f6a637814ac8250610871de351c1fab9 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 72255 + timestamp: 1768976417882 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-adapter-4.6.7-np2py312h2ed9cc7_14.conda + sha256: d3259806850fed34eeb2ec720089c123a5c00aab2a7aa88acb5b065298901459 + md5: 1e0671c1e71a1ec9abab278082aada67 + depends: + - empy + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 63643 + timestamp: 1768974996605 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-cli-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 6686be6bdcc5869cde6dc7b56620ec7511f221f5825657afb05e6ef768c3b156 + md5: 48cba4506b616a6b5b3e7212f33b5ef6 + depends: + - argcomplete + - importlib-metadata + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 42873 + timestamp: 1768974405863 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-cmake-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 60586ac2acae5ba308c386621c7f4ed2a8948d17e81655ff8834dba94fe635c9 + md5: 2e9927816b7628d3c57b5fc4d392d88e + depends: + - empy + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-pycommon + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 36343 + timestamp: 1768975550378 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-core-generators-0.2.0-np2py312h2ed9cc7_14.conda + sha256: 0b9395eca64e7f09fc12b0e34f1bfdf1741e1252dabeee43e9e07445a6a25e8f + md5: ff6ec3bd789ae50a8dedd82e398399e4 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cmake + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-generator-cpp + - ros-jazzy-rosidl-generator-py + - ros-jazzy-rosidl-generator-type-description + - ros-jazzy-rosidl-typesupport-c + - ros-jazzy-rosidl-typesupport-cpp + - ros-jazzy-rosidl-typesupport-fastrtps-c + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 32409 + timestamp: 1768976223308 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-core-runtime-0.2.0-np2py312h2ed9cc7_14.conda + sha256: cf165575f3a3e17a37f17db719b3bf425c89d6d235ed33e020b01ddab793162b + md5: 9122797cdce8baad9ae6d685a0a09be4 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-generator-py + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-c + - ros-jazzy-rosidl-typesupport-cpp + - ros-jazzy-rosidl-typesupport-fastrtps-c + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-rosidl-typesupport-introspection-c + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 31468 + timestamp: 1768976201624 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-default-generators-1.6.0-np2py312h2ed9cc7_14.conda + sha256: 6b19ead996df328f3b712c4bc40cbc884f18ad8ecd8173533ae2499b9bc5d3f6 + md5: abc7b251bd74db97187c701fd8febce7 + depends: + - python + - ros-jazzy-action-msgs + - ros-jazzy-ament-cmake-core + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-generators + - ros-jazzy-service-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 32655 + timestamp: 1768976362545 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-default-runtime-1.6.0-np2py312h2ed9cc7_14.conda + sha256: dd1116305775715cc6b713007dba47e509c75d30dde45cbc6daae596a6f42ede + md5: a315d882f66f9913720bf6c956f1f1de + depends: + - python + - ros-jazzy-action-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros-jazzy-service-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 32082 + timestamp: 1768976348452 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-dynamic-typesupport-0.1.2-np2py312h2ed9cc7_14.conda + sha256: 3dd527db71843c75520b5e682032585166d6e2f2741d3e9ffa2ec9839dad63b6 + md5: a64fefcf3641dcbb4cd2372a03315d12 + depends: + - python + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 63075 + timestamp: 1768975635417 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-dynamic-typesupport-fastrtps-0.1.0-np2py312h2ed9cc7_14.conda + sha256: d6e6848393179d67e7025fe07c6132ee0bcf33a756caf280917d5ad77795fd4e + md5: 3088d0ce08c604414d6ee746e16c8c6a + depends: + - python + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-dynamic-typesupport + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 86542 + timestamp: 1768975753839 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-c-4.6.7-np2py312h2ed9cc7_14.conda + sha256: b068ddee6e5b8f809c79805e834fdecd6007c3326aa7c8ddb3d414bf36af6338 + md5: b27a8c8ea2ed0687a1dc84138a988edc + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-index-python + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-cmake + - ros-jazzy-rosidl-generator-type-description + - ros-jazzy-rosidl-parser + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-typesupport-interface + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 53317 + timestamp: 1768975630096 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-cpp-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 6c01977fc91eb4532d8da01d8d9535711280aef10b823513704dad7e282b22b9 + md5: 184ac8d7b9a2c5692324adf22e656596 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-cmake + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-generator-type-description + - ros-jazzy-rosidl-parser + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 50171 + timestamp: 1768975727423 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-py-0.22.2-np2py312h2ed9cc7_14.conda + sha256: 0a6b80154cc2ceb65e9c9534c7f0e7d52ec2d6ab0eb8760bc010d6b0cb99f917 + md5: 14c7ad681afe3b3d8de82549a20d4f3a + depends: + - numpy + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-cmake-cppcheck + - ros-jazzy-ament-cmake-cpplint + - ros-jazzy-ament-cmake-flake8 + - ros-jazzy-ament-cmake-pep257 + - ros-jazzy-ament-cmake-uncrustify + - ros-jazzy-ament-index-python + - ros-jazzy-python-cmake-module + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-parser + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-typesupport-c + - ros-jazzy-rosidl-typesupport-interface + - ros-jazzy-rpyutils + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 60302 + timestamp: 1768976170924 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-generator-type-description-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 62658037401a2e6ec188cf2b9ef5509ca0816020d424658251518650ae83ce47 + md5: ddf070ad895e9dadad344c32101b8ac0 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-parser + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 48926 + timestamp: 1768975455962 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-parser-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 367e1112971d86a7995c88928a66f24a97fc83c8792c3f3db7d855e60f11eb14 + md5: 713f5af5decfe127084b72052599fcbc + depends: + - lark-parser + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-adapter + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 60375 + timestamp: 1768975351221 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-pycommon-4.6.7-np2py312h2ed9cc7_14.conda + sha256: de1ff664687167e7af5203b66df0b748e5432a55e8805ad750f1e46f21698213 + md5: 4ee78d143cb687d7c6dd05970ba4ccc2 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-parser + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 25379 + timestamp: 1768975451977 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-c-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 195d2e9203e78720105eac13e233b66a8299c4b6545bced55d3e93a69574c640 + md5: 5dadd0a01dba00817e67f4b6d868503e + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-typesupport-interface + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 83732 + timestamp: 1768975532038 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-cpp-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 9c3972285f34d9e65485841e5cc681d62d177546d45ba1e546758d574293c9b2 + md5: 618f6dd5b08e0a46e3aecc8869f1c6f1 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-c + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 41075 + timestamp: 1768975615071 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-runtime-py-0.13.1-np2py312h2ed9cc7_14.conda + sha256: 5c6e84a44eefed39343e6e6ace12660bc7d16a67782a62681924e7e514c37534 + md5: e29e6f8c0cf347e79f19fcd7979c2e78 + depends: + - numpy + - python + - pyyaml + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-parser + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 47637 + timestamp: 1768976570527 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-c-3.2.2-np2py312h2ed9cc7_14.conda + sha256: 80a1e07e393a60e90e1abe9f7f981525c9442150ddd6a048c242a1a09c728ad5 + md5: 1d9461e0ad5882c23be4c1ebcf65bbb3 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-index-python + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-typesupport-fastrtps-c + - ros-jazzy-rosidl-typesupport-interface + - ros-jazzy-rosidl-typesupport-introspection-c + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 51300 + timestamp: 1768976122441 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-cpp-3.2.2-np2py312h2ed9cc7_14.conda + sha256: 69dfc33c071318accc937361c45ccd035dfd0b18f0c389a2a98a6f35374c8e2a + md5: 34e03f7686eda69d240414f52d961585 + depends: + - python + - ros-jazzy-ament-cmake-core + - ros-jazzy-ament-index-python + - ros-jazzy-rcpputils + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-generator-type-description + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-c + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-rosidl-typesupport-interface + - ros-jazzy-rosidl-typesupport-introspection-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 50373 + timestamp: 1768976165572 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-fastrtps-c-3.6.3-np2py312h2ed9cc7_14.conda + sha256: 616080dc794d849f1bc95f3f737f686013b193728506ab88066bd98883f4c029 + md5: de8a082e570de0acfd0490d0818a8a85 + depends: + - python + - ros-jazzy-ament-cmake-ros + - ros-jazzy-ament-index-python + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps-cmake-module + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-fastrtps-cpp + - ros-jazzy-rosidl-typesupport-interface + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 51987 + timestamp: 1768976049147 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-fastrtps-cpp-3.6.3-np2py312h2ed9cc7_14.conda + sha256: ebc03d086473fbbba1c88da64c28a5d0f1d3b19fd8f5fd413c931fc1b7ee6b51 + md5: 59a45dacb967b5c7a206ed9744c385af + depends: + - python + - ros-jazzy-ament-cmake-ros + - ros-jazzy-ament-index-python + - ros-jazzy-fastcdr + - ros-jazzy-fastrtps-cmake-module + - ros-jazzy-rmw + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-generator-cpp + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-interface + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 54052 + timestamp: 1768975861649 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-interface-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 300c2a948a0da7a3932f342e08837116dddbbb6503dd112c178e2a870860e7b0 + md5: 7a32cff7d1a5b69451dd6a7ec97ae260 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 29380 + timestamp: 1768975013654 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-introspection-c-4.6.7-np2py312h2ed9cc7_14.conda + sha256: 94f349bafc0315739d987f6ac7be5e32d8711e08479ebac47c80ce484c55e1dc + md5: 099afff89882fa2ebdb54ac1ba9bad91 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-cmake + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-parser + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-typesupport-interface + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 48428 + timestamp: 1768975749573 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rosidl-typesupport-introspection-cpp-4.6.7-np2py312h2ed9cc7_14.conda + sha256: f7fe7bbd4a91b2c0875c2ba372c8908546c229bd5540758051149f24611bd4a1 + md5: 5faba9b20f481175270e48fc307f58b6 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-index-python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-cli + - ros-jazzy-rosidl-cmake + - ros-jazzy-rosidl-generator-c + - ros-jazzy-rosidl-generator-cpp + - ros-jazzy-rosidl-parser + - ros-jazzy-rosidl-pycommon + - ros-jazzy-rosidl-runtime-c + - ros-jazzy-rosidl-runtime-cpp + - ros-jazzy-rosidl-typesupport-interface + - ros-jazzy-rosidl-typesupport-introspection-c + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 48647 + timestamp: 1768975885152 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rpyutils-0.4.2-np2py312h2ed9cc7_14.conda + sha256: ec46df788261a480ea44c61f5664b50f9d9e7ccd8a085b289e5728d77ecefd89 + md5: e28ef177572cf8ea1dbe59399a041a1d + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 26458 + timestamp: 1768974380541 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rti-connext-dds-cmake-module-0.22.2-np2py312h2ed9cc7_14.conda + sha256: 296710e45267ff030ef2f78513e2572210cd2cfc8026c63d56c2d01421354453 + md5: df2cb55d63e74745a98834c8db119802 + depends: + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 31692 + timestamp: 1768975289885 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-assimp-vendor-14.1.19-np2py312h2ed9cc7_14.conda + sha256: 638a687c077b053f590d60603ce8a145678002c189796c4886262af1bac735f6 + md5: 317ab4a4b664da5a8d8c2efe8dff4157 + depends: + - assimp + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - assimp >=5.4.3,<5.4.4.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR BSD-3-Clause + size: 25085 + timestamp: 1768974952518 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-common-14.1.19-np2py312h2ed9cc7_14.conda + sha256: 093507b34fd37260a516e093147b0dcd6f840034115cd886f77b61f5df0751b2 + md5: d94e867c83061d558633fef59ed5bc99 + depends: + - libgl-devel + - libopengl-devel + - python + - qt-main + - ros-jazzy-geometry-msgs + - ros-jazzy-message-filters + - ros-jazzy-pluginlib + - ros-jazzy-rclcpp + - ros-jazzy-resource-retriever + - ros-jazzy-ros-workspace + - ros-jazzy-rviz-ogre-vendor + - ros-jazzy-rviz-rendering + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros-jazzy-std-srvs + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros-jazzy-tinyxml2-vendor + - ros-jazzy-urdf + - ros-jazzy-yaml-cpp-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgl >=1.7.0,<2.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libopengl >=1.7.0,<2.0a0 + - qt-main >=5.15.15,<5.16.0a0 + license: BSD-3-Clause + size: 889458 + timestamp: 1768979368739 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-default-plugins-14.1.19-np2py312h2ed9cc7_14.conda + sha256: c7c91b9e804902c4e46ed24d52cf372108b5325d1a6325726bcb722c36b989bc + md5: 984013bbdb27c8d26b388b0eb8923041 + depends: + - libgl-devel + - libopengl-devel + - python + - qt-main + - ros-jazzy-geometry-msgs + - ros-jazzy-gz-math-vendor + - ros-jazzy-image-transport + - ros-jazzy-interactive-markers + - ros-jazzy-laser-geometry + - ros-jazzy-map-msgs + - ros-jazzy-nav-msgs + - ros-jazzy-pluginlib + - ros-jazzy-point-cloud-transport + - ros-jazzy-rclcpp + - ros-jazzy-resource-retriever + - ros-jazzy-ros-workspace + - ros-jazzy-rviz-common + - ros-jazzy-rviz-ogre-vendor + - ros-jazzy-rviz-rendering + - ros-jazzy-tf2 + - ros-jazzy-tf2-geometry-msgs + - ros-jazzy-tf2-ros + - ros-jazzy-urdf + - ros-jazzy-visualization-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libgl >=1.7.0,<2.0a0 + - qt-main >=5.15.15,<5.16.0a0 + - numpy >=1.23,<3 + - libopengl >=1.7.0,<2.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 2286747 + timestamp: 1768980484930 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-ogre-vendor-14.1.19-np2py312hf3be069_14.conda + sha256: a2f6e01ef771f0c955eac5a7b0d88327dc2412658da5d0a350e775d84932fc5f + md5: f551bbe3ab963c91345345e01b0f885e + depends: + - assimp + - freetype + - glew + - libgl-devel + - libopengl-devel + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - xorg-libx11 + - xorg-libxaw + - xorg-libxrandr + - xorg-xorgproto + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libzlib >=1.3.1,<2.0a0 + - pugixml >=1.15,<1.16.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libglu >=9.0.3,<9.1.0a0 + - assimp >=5.4.3,<5.4.4.0a0 + - libfreetype >=2.14.1 + - libfreetype6 >=2.14.1 + - xorg-libxrandr >=1.5.4,<2.0a0 + - zziplib >=0.13.69,<0.14.0a0 + - freeimage >=3.18.0,<3.19.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - libopengl >=1.7.0,<2.0a0 + - libgl >=1.7.0,<2.0a0 + - python_abi 3.12.* *_cp312 + - glew >=2.3.0,<2.4.0a0 + license: Apache-2.0 OR MIT + size: 5377899 + timestamp: 1768974741145 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz-rendering-14.1.19-np2py312h2ed9cc7_14.conda + sha256: 5872cb2b9d544a8e05c89ac91a259d80120c0a779b96bd0104c28eeceb9772eb + md5: c4fc24931095bdbb76ff9a095a462a87 + depends: + - eigen + - libgl-devel + - libopengl-devel + - python + - qt-main + - ros-jazzy-ament-index-cpp + - ros-jazzy-eigen3-cmake-module + - ros-jazzy-resource-retriever + - ros-jazzy-ros-workspace + - ros-jazzy-rviz-assimp-vendor + - ros-jazzy-rviz-ogre-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - qt-main >=5.15.15,<5.16.0a0 + - glew >=2.3.0,<2.4.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libgl >=1.7.0,<2.0a0 + - libopengl >=1.7.0,<2.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 935692 + timestamp: 1768975461577 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-rviz2-14.1.19-np2py312h2ed9cc7_14.conda + sha256: c49f3f1b2ae5caf66859446668ab7def793fb4c51dcfbc5fbb0c4bf1618ecfc5 + md5: 4fb3d8012696062219c1da8a5576170b + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rviz-common + - ros-jazzy-rviz-default-plugins + - ros-jazzy-rviz-ogre-vendor + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libgl >=1.7.0,<2.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - libopengl >=1.7.0,<2.0a0 + - qt-main >=5.15.15,<5.16.0a0 + license: BSD-3-Clause + size: 76201 + timestamp: 1768981252070 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sensor-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: ee0859957992f3910f34fac3254ebdbd71764585472bf9a1fb464a0745e972b0 + md5: 89a7a6e3349f2d78349c7bac2eded259 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 546181 + timestamp: 1768976803769 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sensor-msgs-py-5.3.6-np2py312h2ed9cc7_14.conda + sha256: b930b4b924bbf383d7a0ad85dca48b47ccda605a0ce28af9066a605b804e8993 + md5: 15c18ca474aa917020c19072566d811d + depends: + - numpy + - python + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 30731 + timestamp: 1768977042011 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-service-msgs-2.0.3-np2py312h2ed9cc7_14.conda + sha256: 97109e64f4aa38bc632726ad7726086ea616db1a59cd7ce4bd770401dafbd515 + md5: 701048cd10cd00dfae1ac0602f831c37 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 80803 + timestamp: 1768976271809 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-shape-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 99b3ceff00e8064f792fbb463b5a84e7ae6f03d060771fd511dfd3e5e3a0c3a1 + md5: cb2bf185c2bd707b3faeba786a1fee84 + depends: + - python + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 128269 + timestamp: 1768976806291 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-spdlog-vendor-1.6.1-np2py312h918b84f_14.conda + sha256: 4725102e66c4a2d0089dafa54f767c89a0cc2da0812dd58e306d072a4f3d2caa + md5: 3826650a48bb219f4f56804524ab8a9c + depends: + - fmt + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - spdlog + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - fmt >=12.1.0,<12.2.0a0 + - spdlog >=1.17.0,<1.18.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 OR MIT + size: 27447 + timestamp: 1768974995526 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sqlite3-vendor-0.26.9-np2py312h2ed9cc7_14.conda + sha256: f8a56a5eae7585e7f10c9288f29b103889573efb94034c1c2e7661aa537a4ebb + md5: 177f046c3d1034502e5484c8f439fc48 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - sqlite + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - libsqlite >=3.51.2,<4.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 24554 + timestamp: 1768974408485 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sros2-0.13.4-np2py312h2ed9cc7_14.conda + sha256: 7aad1b03e0a52894d9359e9fd416d16b693b305ffef9af1b5ce35bce93064aff + md5: 23f16a30c5a1266554c864ffd3072a62 + depends: + - argcomplete + - cryptography + - importlib_resources + - lxml + - python + - ros-jazzy-ament-index-python + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 75922 + timestamp: 1768979850997 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-sros2-cmake-0.13.4-np2py312h2ed9cc7_14.conda + sha256: d69055e813c394da21bea92ca9283bf39059c875f5a7cdf468be385e95934d07 + md5: 9e0396901e12ee585b97388028acbf74 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-ros2cli + - ros-jazzy-sros2 + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 39864 + timestamp: 1768980461706 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-statistics-msgs-2.0.3-np2py312h2ed9cc7_14.conda + sha256: eb971e6dc45338139f9dcc50efe7833b50dbd17eda988aff59a19a58ac7f3bbe + md5: c02c27b6b19e833ea428d5014d1157f8 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 109245 + timestamp: 1768976528840 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-std-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: d643a5d459fd291afdc2f5494598d3f5dbe3a72aa6b151a6d559f505a426c14d + md5: f11cc514ac3dba9c6ab35154580cb889 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 340113 + timestamp: 1768976491799 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-std-srvs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 1178f6f924be8ea716f8f4e038d30ee4d6ec03ee6f7a02f25e54fe2399522f7c + md5: 97e8c19113d873d62ee44a974510140e + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 169027 + timestamp: 1768976426146 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-stereo-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: c5215b34bce939e6cb4b054015857ddef6939d4327ec174a7b44fda001de7f24 + md5: 62c78b3d674a5b6ab0b4780c5a4521a0 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 83425 + timestamp: 1768977193815 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-0.36.18-np2py312h2ed9cc7_14.conda + sha256: e8c2685e16710f9e9369cbd39fa2df46d8004e051bd0de0d0f98a74c319c4e50 + md5: 552df13a86e6e62b07938a1e0cf84b65 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-rcutils + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-runtime-cpp + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 135237 + timestamp: 1768976780129 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-bullet-0.36.18-np2py312h2ed9cc7_14.conda + sha256: c858a3a635a94673b373c568bb381d211a65218890ebb9607c840692ebd7f861 + md5: 769be4b1c1bce287be902c436390a40c + depends: + - bullet + - python + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 44738 + timestamp: 1768979406307 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-eigen-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 1cf28f7c0aaf9645b12e7001a66be70d7d03663682b95f5fb2b453581e1b5079 + md5: dbab85a1b3d7fc6e3ad023dc7f9e0096 + depends: + - eigen + - python + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 46144 + timestamp: 1768979351035 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-eigen-kdl-0.36.18-np2py312h2ed9cc7_14.conda + sha256: d5e0b16289c41ca59ba8960fe7fc93a6a3a0a0e5b41422eef56360b4ff1eb8e7 + md5: 9a6849ee338c7a138d9f9a59695bbcdf + depends: + - eigen + - python + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 41614 + timestamp: 1768977081982 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-geometry-msgs-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 815eb482136c17fb0d46e61c5a5195d1eee0e2564ba537b53b1c617313fa84f5 + md5: d1c567648f14b870f339f5ed922ee91c + depends: + - numpy + - python + - ros-jazzy-geometry-msgs + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros-jazzy-tf2-ros-py + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 58124 + timestamp: 1768979431905 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-kdl-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 10fb592a2ec32a9c813e1645135ea6e6953fe75be81db22ac1f675f0da32b8a6 + md5: c579fbfe5683245eeb66f08eb799b5f6 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-orocos-kdl-vendor + - ros-jazzy-python-orocos-kdl-vendor + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros-jazzy-tf2-ros-py + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 47574 + timestamp: 1768979381132 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-msgs-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 6ada4a035bb06f3fdf062bfc1c412dcaa6366acc32123527856f0e0eeb58cd6e + md5: c56e132c717f298fdba76d20f717839f + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 256319 + timestamp: 1768976737716 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-py-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 346b604330890f60dc5b7fa4ee066539a5d5138da514e21d99910dc62393cb22 + md5: 07d49d4419f00e26a8b3892ba3c338ae + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-rpyutils + - ros-jazzy-tf2 + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 59215 + timestamp: 1768978478550 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-ros-0.36.18-np2py312h2ed9cc7_14.conda + sha256: e4a14eb8b4db2be77b16647a60f18abf112265f4b8cd56b566023da389fe8fbf + md5: 9cda41a6263286bd8cd3a3aabcc2fa70 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-message-filters + - ros-jazzy-rcl-interfaces + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-action + - ros-jazzy-rclcpp-components + - ros-jazzy-ros-workspace + - ros-jazzy-tf2 + - ros-jazzy-tf2-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 467356 + timestamp: 1768979151034 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-ros-py-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 2b8bac286a18c3b53d97ab4eb01b76f9e7b264bb07269a9296f60c2254547228 + md5: 42407e60839a4411b733aba21ca52b4c + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros-jazzy-tf2-msgs + - ros-jazzy-tf2-py + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: BSD-3-Clause + size: 49024 + timestamp: 1768978651320 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-sensor-msgs-0.36.18-np2py312h2ed9cc7_14.conda + sha256: e0d39034af365dc8ae3d46290b8f7eef33771c3fe2d59f748195f3b73d01b5dd + md5: 21c859f67f10197aea0a397b34ec53f6 + depends: + - eigen + - numpy + - python + - ros-jazzy-eigen3-cmake-module + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros-jazzy-sensor-msgs-py + - ros-jazzy-std-msgs + - ros-jazzy-tf2 + - ros-jazzy-tf2-ros + - ros-jazzy-tf2-ros-py + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: BSD-3-Clause + size: 51652 + timestamp: 1768979842567 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tf2-tools-0.36.18-np2py312h2ed9cc7_14.conda + sha256: 8cfacaa1c18e27dd39481f6ec1438376a8ca57f353ec89301c84b6d05db33a8a + md5: 56c41a755a92fa1fdaaa06b389c8fcd9 + depends: + - graphviz + - python + - pyyaml + - ros-jazzy-rclpy + - ros-jazzy-ros-workspace + - ros-jazzy-tf2-msgs + - ros-jazzy-tf2-py + - ros-jazzy-tf2-ros-py + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 24212 + timestamp: 1768979118014 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tinyxml2-vendor-0.9.2-np2py312h2ed9cc7_14.conda + sha256: dd3365bb71b174b7f13baae09809b5224cc6b0e950efaf71c671809e632b39e5 + md5: 0c9bb6718153a3067b97a30018043bb7 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - tinyxml2 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - tinyxml2 >=11.0.0,<11.1.0a0 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 24667 + timestamp: 1768974418792 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-tracetools-8.2.4-np2py312h2ed9cc7_14.conda + sha256: 4284a87296e550ffdda07ef91dc0933a215f36248b854c6bdeb1504d76426a58 + md5: 3292ba5058e700629d2c4c2ca7b0b2a1 + depends: + - lttng-ust + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - lttng-ust >=2.13.9,<2.14.0a0 + - python_abi 3.12.* *_cp312 + license: Apache-2.0 + size: 73002 + timestamp: 1768975358676 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-trajectory-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: bf3cbbd46f01173280d0b856a5a0ffe6334c80474e23524d0a2ff3a69479ea7c + md5: 6a0d989dec3e4b4080b64ddc6fa20ea3 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 150655 + timestamp: 1768976857459 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-type-description-interfaces-2.0.3-np2py312h2ed9cc7_14.conda + sha256: fd118b689b63c4aece70e23cae91b568f9354017da85ced5687d335a1622d4e8 + md5: f92c8cec2d8183091a8d243314d179f6 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros-jazzy-service-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 + size: 232353 + timestamp: 1768976307478 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-uncrustify-vendor-3.0.1-np2py312h2ed9cc7_14.conda + sha256: cbcc02dd96f1fe9a98a1c533824862445c8f2f350eb97fbaa21a5323972b9e77 + md5: 82188bc12f938a9d494c18d4c54e0bb9 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - uncrustify + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - uncrustify >=0.81.0,<0.82.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + license: Apache-2.0 OR GPL-2.0-only + size: 23250 + timestamp: 1768974393518 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-unique-identifier-msgs-2.5.0-np2py312h2ed9cc7_14.conda + sha256: 92de1c0bd7c860920dea52d301507da4a76ef717655146189784443e2a8b87d1 + md5: c27db941a29aa3d29bbc4967c6c9b936 + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-core-runtime + - ros2-distro-mutex 0.13.* jazzy_* + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: BSD-3-Clause + size: 74062 + timestamp: 1768976238206 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdf-2.10.0-np2py312h2ed9cc7_14.conda + sha256: cc3d50459aa436eb69955124336e0099a4aabba3abded7bb77c87f1eacdcd624 + md5: fa8a1e60d54e95f43779457f361e2f1a + depends: + - python + - ros-jazzy-pluginlib + - ros-jazzy-ros-workspace + - ros-jazzy-tinyxml2-vendor + - ros-jazzy-urdf-parser-plugin + - ros-jazzy-urdfdom + - ros-jazzy-urdfdom-headers + - ros2-distro-mutex 0.13.* jazzy_* + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - numpy >=1.23,<3 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: BSD-3-Clause + size: 156220 + timestamp: 1768975901965 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdf-parser-plugin-2.10.0-np2py312h2ed9cc7_14.conda + sha256: 0c5e0e7c836869f8992e59244502e0c3b15d9d3aee2ff9f5568b875d4836b72a + md5: 1f2e2ac3c0a47ab3d568e404e9a583fd + depends: + - python + - ros-jazzy-ros-workspace + - ros-jazzy-urdfdom-headers + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 32147 + timestamp: 1768975332064 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdfdom-4.0.1-py312h24bf083_14.conda + sha256: c55d7fb615b702ae186ad39f3d484b38f4add0d66b4281680e5f2ebe8201f1e5 + md5: fb7e257640c55c1cfaf0928b7a5d11c9 + depends: + - console_bridge + - python + - ros-jazzy-console-bridge-vendor + - ros-jazzy-ros-workspace + - ros-jazzy-tinyxml2-vendor + - ros-jazzy-urdfdom-headers + - ros2-distro-mutex 0.13.* jazzy_* + - tinyxml2 + - urdfdom >=4.0.1,<4.1.0a0 + - console_bridge >=1.0.2,<1.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: BSD-3-Clause + size: 8332 + timestamp: 1768975460182 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-urdfdom-headers-1.1.2-py312h24bf083_14.conda + sha256: 6d73d9c046db8eda448ae4d9417c236d01431350df2384554c6066d8bb872dda + md5: 636dfa139b88e459deba5ae607dbe0ab + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - urdfdom_headers >=1.1.2,<1.2.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - python_abi 3.12.* *_cp312 + license: BSD-3-Clause + size: 7454 + timestamp: 1768973890125 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-visualization-msgs-5.3.6-np2py312h2ed9cc7_14.conda + sha256: 8d080fa0488084ea46b1e26b49acc342e3b29076a967e5a4e2b111ef183d1e48 + md5: eb75c8ffb46841a6d41ed58e4df84a82 + depends: + - python + - ros-jazzy-builtin-interfaces + - ros-jazzy-geometry-msgs + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-runtime + - ros-jazzy-sensor-msgs + - ros-jazzy-std-msgs + - ros2-distro-mutex 0.13.* jazzy_* + - libstdcxx >=14 + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + - numpy >=1.23,<3 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + license: Apache-2.0 + size: 370089 + timestamp: 1768977161239 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-yaml-cpp-vendor-9.0.1-np2py312h2ed9cc7_14.conda + sha256: aa9e085b0df02c96335b3b736b14e2c6b5ea7d84c71c986db5f4edbf368a166c + md5: 8cd0ab75744b00a294515720398c1d34 + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - yaml-cpp + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - yaml-cpp >=0.8.0,<0.9.0a0 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + license: Apache-2.0 OR MIT + size: 23171 + timestamp: 1768974400024 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros-jazzy-zstd-vendor-0.26.9-np2py312h2ed9cc7_14.conda + sha256: b43773d3c7e9f376cdea7e6a4a390b058b1fa0197949f98b961b53259d6b68b9 + md5: 9bb07ab4028160b88c768ea2c67a150c + depends: + - python + - ros-jazzy-ros-workspace + - ros2-distro-mutex 0.13.* jazzy_* + - zstd + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - libgcc >=14 + - python_abi 3.12.* *_cp312 + - ros2-distro-mutex >=0.13.0,<0.14.0a0 + - numpy >=1.23,<3 + - zstd >=1.5.7,<1.6.0a0 + license: Apache-2.0 OR BSD-3-Clause + size: 24046 + timestamp: 1768974406454 +- conda: https://conda.anaconda.org/robostack-jazzy/linux-64/ros2-distro-mutex-0.13.0-jazzy_14.conda + sha256: c350fd0ee9a1274907cff03137e09f18c08b03b58d886b7a8d622ef4cb8d9a24 + md5: a9ea72dd3fbe2b854e30c0206323caee + constrains: + - libboost 1.88.* + - libboost-devel 1.88.* + - pcl 1.15.1.* + - gazebo 11.* + - libprotobuf 6.31.1.* + - vtk 9.5.2.* + license: BSD-3-Clause + size: 2337 + timestamp: 1768973793122 +- conda: https://conda.anaconda.org/conda-forge/noarch/rosdistro-1.0.1-pyhd8ed1ab_0.conda + sha256: bff3b2fe7afe35125669ffcb7d6153db78070a753e1e4ac3b3d8d198eb6d6982 + md5: b7ed380a9088b543e06a4f73985ed03a + depends: + - catkin_pkg + - python >=3.9 + - pyyaml + - rospkg + - setuptools + license: BSD-3-Clause + license_family: BSD + size: 47691 + timestamp: 1747826651335 +- conda: https://conda.anaconda.org/conda-forge/noarch/rospkg-1.6.1-pyhd8ed1ab_0.conda + sha256: 4d930bee9f6a6d0fb7e5c9bb644b2b168787e907014deb49a3e00c0552934447 + md5: d530f2ffe740578a5ece44b1004067cc + depends: + - catkin_pkg + - distro + - python >=3.10 + - pyyaml + license: BSD-3-Clause + license_family: BSD + size: 31852 + timestamp: 1766125246079 +- conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda + sha256: 5ebc4bb71fbdc8048b08848519150c8d44b8eb18445711d3258c9d402ba87a2c + md5: fa6669cc21abd4b7b6c5393b7bc71914 + depends: + - python >=3.9 + license: MIT + license_family: MIT + size: 787541 + timestamp: 1745484086827 +- conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhe01879c_1.conda + sha256: 458227f759d5e3fcec5d9b7acce54e10c9e1f4f4b7ec978f3bfd54ce4ee9853d + md5: 3339e3b65d58accf4ca4fb8748ab16b3 + depends: + - python >=3.9 + - python + license: MIT + license_family: MIT + size: 18455 + timestamp: 1753199211006 +- conda: https://conda.anaconda.org/conda-forge/noarch/snowballstemmer-3.0.1-pyhd8ed1ab_0.conda + sha256: 17007a4cfbc564dc3e7310dcbe4932c6ecb21593d4fec3c68610720f19e73fb2 + md5: 755cf22df8693aa0d1aec1c123fa5863 + depends: + - python >=3.9 + license: BSD-3-Clause + license_family: BSD + size: 73009 + timestamp: 1747749529809 +- conda: https://conda.anaconda.org/conda-forge/linux-64/spdlog-1.17.0-hab81395_1.conda + sha256: c650f3df027afde77a5fbf58600ec4ed81a9edddf81f323cfb3e260f6dc19f56 + md5: a3b0e874fa56f72bc54e5c595712a333 + depends: + - __glibc >=2.17,<3.0.a0 + - fmt >=12.1.0,<12.2.0a0 + - libgcc >=14 + - libstdcxx >=14 + license: MIT + license_family: MIT + size: 196681 + timestamp: 1767781665629 +- conda: https://conda.anaconda.org/conda-forge/linux-64/sqlite-3.51.2-h04a0ce9_0.conda + sha256: ccce47d8fe3a817eac5b95f34ca0fcb12423b0c7c5eee249ffb32ac8013e9692 + md5: bb88d9335d09e54c7e6b5529d1856917 + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=78.2,<79.0a0 + - libgcc >=14 + - libsqlite 3.51.2 hf4e2dac_0 + - libzlib >=1.3.1,<2.0a0 + - ncurses >=6.5,<7.0a0 + - readline >=8.3,<9.0a0 + license: blessing + size: 183298 + timestamp: 1768147986603 +- conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.10.1-h5b2951e_7100101.conda + sha256: 7c1c5bd2ba8385202ac3cb4c9c7f9bb87a2e677e977afd72c910314c014b28be + md5: e927e0f248a498050443dab8bb1203a9 + depends: + - libsuitesparseconfig ==7.10.1 h901830b_7100101 + - libamd ==3.3.3 h456b2da_7100101 + - libbtf ==2.3.2 hf02c80a_7100101 + - libcamd ==3.3.3 hf02c80a_7100101 + - libccolamd ==3.3.4 hf02c80a_7100101 + - libcolamd ==3.3.4 hf02c80a_7100101 + - libcholmod ==5.3.1 h9cf07ce_7100101 + - libcxsparse ==4.4.1 hf02c80a_7100101 + - libldl ==3.3.2 hf02c80a_7100101 + - libklu ==2.3.5 h95ff59c_7100101 + - libumfpack ==6.3.5 h873dde6_7100101 + - libparu ==1.0.0 hc6afc67_7100101 + - librbio ==4.3.4 hf02c80a_7100101 + - libspex ==3.2.3 h9226d62_7100101 + - libspqr ==4.3.4 h23b7119_7100101 + license: LGPL-2.1-or-later AND BSD-3-Clause AND GPL-2.0-or-later AND Apache-2.0 + size: 12135 + timestamp: 1741963824816 +- conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.28-h4ee821c_9.conda + sha256: c47299fe37aebb0fcf674b3be588e67e4afb86225be4b0d452c7eb75c086b851 + md5: 13dc3adbc692664cd3beabd216434749 + depends: + - __glibc >=2.28 + - kernel-headers_linux-64 4.18.0 he073ed8_9 + - tzdata + license: LGPL-2.0-or-later AND LGPL-2.0-or-later WITH exceptions AND GPL-2.0-or-later + license_family: GPL + size: 24008591 + timestamp: 1765578833462 +- conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-2022.3.0-hb700be7_2.conda + sha256: 975710e4b7f1b13c3c30b7fbf21e22f50abe0463b6b47a231582fdedcc45c961 + md5: 8f7278ca5f7456a974992a8b34284737 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libhwloc >=2.12.2,<2.12.3.0a0 + - libstdcxx >=14 + license: Apache-2.0 + license_family: APACHE + size: 181329 + timestamp: 1767886632911 +- conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-devel-2022.3.0-h51de99f_2.conda + sha256: 7e21321b8e901458dbcd97b0588c5d5398a5ab205d7b948d5fa811dc132355bc + md5: 2c0e74f5f9143fe2e9dc9e1ffac20efa + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - tbb 2022.3.0 hb700be7_2 + size: 1115399 + timestamp: 1767886655300 +- conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda + sha256: 3ae98c2ca54928b2c72dbb4bd8ea229d3c865ad39367d377908294d9fb1e6f2c + md5: aeb0b91014ac8c5d468e32b7a5ce8ac2 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + - libgcc >=13 + license: Zlib + size: 131351 + timestamp: 1742246125630 +- conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h366c992_103.conda + sha256: cafeec44494f842ffeca27e9c8b0c27ed714f93ac77ddadc6aaf726b5554ebac + md5: cffd3bdd58090148f4cfcd831f4b26ab + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libzlib >=1.3.1,<2.0a0 + constrains: + - xorg-libx11 >=1.8.12,<2.0a0 + license: TCL + license_family: BSD + size: 3301196 + timestamp: 1769460227866 +- conda: https://conda.anaconda.org/conda-forge/noarch/tomli-2.4.0-pyhcf101f3_0.conda + sha256: 62940c563de45790ba0f076b9f2085a842a65662268b02dd136a8e9b1eaf47a8 + md5: 72e780e9aa2d0a3295f59b1874e3768b + depends: + - python >=3.10 + - python + license: MIT + license_family: MIT + size: 21453 + timestamp: 1768146676791 +- conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.15.0-pyhcf101f3_0.conda + sha256: 032271135bca55aeb156cee361c81350c6f3fb203f57d024d7e5a1fc9ef18731 + md5: 0caa1af407ecff61170c9437a808404d + depends: + - python >=3.10 + - python + license: PSF-2.0 + license_family: PSF + size: 51692 + timestamp: 1756220668932 +- conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025c-hc9c84f9_1.conda + sha256: 1d30098909076af33a35017eed6f2953af1c769e273a0626a04722ac4acaba3c + md5: ad659d0a2b3e47e38d829aa8cad2d610 + license: LicenseRef-Public-Domain + size: 119135 + timestamp: 1767016325805 +- conda: https://conda.anaconda.org/conda-forge/linux-64/uncrustify-0.81.0-h5888daf_0.conda + sha256: f0b3ad46b173de03c45134b16d7be0b5bdaff344cccb6a4d205850809c1a4dca + md5: c2310445798370fe622fc6b03d79a3a4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: GPL-2.0-only + license_family: GPL + size: 650318 + timestamp: 1747514389910 +- conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda + sha256: 70b1e7322bf6306de6186e91fb87c15f7ba5c1aeb6d0fd31780e088c42025fc4 + md5: a7830d1b7ade9d3f8c35191084fe7022 + depends: + - urdfdom_headers + - libstdcxx >=13 + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - tinyxml2 >=11.0.0,<11.1.0a0 + - console_bridge >=1.0.2,<1.1.0a0 + license: BSD-3-Clause + license_family: BSD + size: 118733 + timestamp: 1743679555211 +- conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda + sha256: 9f4090616ed1cb509bb65f1edb11b23c86d929db0ea3af2bf84277caa4337c40 + md5: 4872efb515124284f8cee0f957f3edce + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + license: BSD-3-Clause + license_family: BSD + size: 19201 + timestamp: 1726152409175 +- conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.24.0-hd6090a7_1.conda + sha256: 3aa04ae8e9521d9b56b562376d944c3e52b69f9d2a0667f77b8953464822e125 + md5: 035da2e4f5770f036ff704fa17aace24 + depends: + - __glibc >=2.17,<3.0.a0 + - libexpat >=2.7.1,<3.0a0 + - libffi >=3.5.2,<3.6.0a0 + - libgcc >=14 + - libstdcxx >=14 + license: MIT + license_family: MIT + size: 329779 + timestamp: 1761174273487 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-h4f16b4b_2.conda + sha256: ad8cab7e07e2af268449c2ce855cbb51f43f4664936eff679b1f3862e6e4b01d + md5: fdc27cb255a7a2cc73b7919a968b48f0 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libxcb >=1.17.0,<2.0a0 + license: MIT + license_family: MIT + size: 20772 + timestamp: 1750436796633 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-image-0.4.0-hb711507_2.conda + sha256: 94b12ff8b30260d9de4fd7a28cca12e028e572cbc504fd42aa2646ec4a5bded7 + md5: a0901183f08b6c7107aab109733a3c91 + depends: + - libgcc-ng >=12 + - libxcb >=1.16,<2.0.0a0 + - xcb-util >=0.4.1,<0.5.0a0 + license: MIT + license_family: MIT + size: 24551 + timestamp: 1718880534789 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda + sha256: 546e3ee01e95a4c884b6401284bb22da449a2f4daf508d038fdfa0712fe4cc69 + md5: ad748ccca349aec3e91743e08b5e2b50 + depends: + - libgcc-ng >=12 + - libxcb >=1.16,<2.0.0a0 + license: MIT + license_family: MIT + size: 14314 + timestamp: 1718846569232 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda + sha256: 2d401dadc43855971ce008344a4b5bd804aca9487d8ebd83328592217daca3df + md5: 0e0cbe0564d03a99afd5fd7b362feecd + depends: + - libgcc-ng >=12 + - libxcb >=1.16,<2.0.0a0 + license: MIT + license_family: MIT + size: 16978 + timestamp: 1718848865819 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda + sha256: 31d44f297ad87a1e6510895740325a635dd204556aa7e079194a0034cdd7e66a + md5: 608e0ef8256b81d04456e8d211eee3e8 + depends: + - libgcc-ng >=12 + - libxcb >=1.16,<2.0.0a0 + license: MIT + license_family: MIT + size: 51689 + timestamp: 1718844051451 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.46-hb03c661_0.conda + sha256: aa03b49f402959751ccc6e21932d69db96a65a67343765672f7862332aa32834 + md5: 71ae752a748962161b4740eaff510258 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + license: MIT + license_family: MIT + size: 396975 + timestamp: 1759543819846 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda + sha256: c12396aabb21244c212e488bbdc4abcdef0b7404b15761d9329f5a4a39113c4b + md5: fb901ff28063514abb6046c9ec2c4a45 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 58628 + timestamp: 1734227592886 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda + sha256: 277841c43a39f738927145930ff963c5ce4c4dacf66637a3d95d802a64173250 + md5: 1c74ff8c35dcadf952a16f752ca5aa49 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libuuid >=2.38.1,<3.0a0 + - xorg-libice >=1.1.2,<2.0a0 + license: MIT + license_family: MIT + size: 27590 + timestamp: 1741896361728 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.13-he1eb515_0.conda + sha256: 516d4060139dbb4de49a4dcdc6317a9353fb39ebd47789c14e6fe52de0deee42 + md5: 861fb6ccbc677bb9a9fb2468430b9c6a + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libxcb >=1.17.0,<2.0a0 + license: MIT + license_family: MIT + size: 839652 + timestamp: 1770819209719 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxau-1.0.12-hb03c661_1.conda + sha256: 6bc6ab7a90a5d8ac94c7e300cc10beb0500eeba4b99822768ca2f2ef356f731b + md5: b2895afaf55bf96a8c8282a2e47a5de0 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 15321 + timestamp: 1762976464266 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxaw-1.0.16-hb9d3cd8_0.conda + sha256: 105ff923b60286188978d7b3aa159b555e2baf4c736801f62602d4127159f06d + md5: 7c0a9bf62d573409d12ad14b362a96e5 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxmu >=1.2.1,<2.0a0 + - xorg-libxpm >=3.5.17,<4.0a0 + - xorg-libxt >=1.3.0,<2.0a0 + license: MIT + license_family: MIT + size: 307032 + timestamp: 1727870272246 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxcomposite-0.4.7-hb03c661_0.conda + sha256: 048c103000af9541c919deef03ae7c5e9c570ffb4024b42ecb58dbde402e373a + md5: f2ba4192d38b6cef2bb2c25029071d90 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxfixes >=6.0.2,<7.0a0 + license: MIT + license_family: MIT + size: 14415 + timestamp: 1770044404696 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxcursor-1.2.3-hb9d3cd8_0.conda + sha256: 832f538ade441b1eee863c8c91af9e69b356cd3e9e1350fff4fe36cc573fc91a + md5: 2ccd714aa2242315acaf0a67faea780b + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libxfixes >=6.0.1,<7.0a0 + - xorg-libxrender >=0.9.11,<0.10.0a0 + license: MIT + license_family: MIT + size: 32533 + timestamp: 1730908305254 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdamage-1.1.6-hb9d3cd8_0.conda + sha256: 43b9772fd6582bf401846642c4635c47a9b0e36ca08116b3ec3df36ab96e0ec0 + md5: b5fcc7172d22516e1f965490e65e33a4 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxfixes >=6.0.1,<7.0a0 + license: MIT + license_family: MIT + size: 13217 + timestamp: 1727891438799 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb03c661_1.conda + sha256: 25d255fb2eef929d21ff660a0c687d38a6d2ccfbcbf0cc6aa738b12af6e9d142 + md5: 1dafce8548e38671bea82e3f5c6ce22f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 20591 + timestamp: 1762976546182 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxext-1.3.7-hb03c661_0.conda + sha256: 79c60fc6acfd3d713d6340d3b4e296836a0f8c51602327b32794625826bd052f + md5: 34e54f03dfea3e7a2dcf1453a85f1085 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + license: MIT + license_family: MIT + size: 50326 + timestamp: 1769445253162 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxfixes-6.0.2-hb03c661_0.conda + sha256: 83c4c99d60b8784a611351220452a0a85b080668188dce5dfa394b723d7b64f4 + md5: ba231da7fccf9ea1e768caf5c7099b84 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + license: MIT + license_family: MIT + size: 20071 + timestamp: 1759282564045 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxi-1.8.2-hb9d3cd8_0.conda + sha256: 1a724b47d98d7880f26da40e45f01728e7638e6ec69f35a3e11f92acd05f9e7a + md5: 17dcc85db3c7886650b8908b183d6876 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxfixes >=6.0.1,<7.0a0 + license: MIT + license_family: MIT + size: 47179 + timestamp: 1727799254088 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxinerama-1.1.6-hecca717_0.conda + sha256: 3a9da41aac6dca9d3ff1b53ee18b9d314de88add76bafad9ca2287a494abcd86 + md5: 93f5d4b5c17c8540479ad65f206fea51 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - libstdcxx >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + license: MIT + license_family: MIT + size: 14818 + timestamp: 1769432261050 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxmu-1.3.1-hb03c661_0.conda + sha256: 2feca3d789b6ad46bd40f71c135cc2f05cb17648a523ffa5f773a0add5bc21fe + md5: c68a1319c4e98c0504614f0abc6e8274 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.7,<2.0a0 + - xorg-libxt >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 90301 + timestamp: 1769675723651 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxpm-3.5.18-hb03c661_0.conda + sha256: 635a3fed88a5e77997ebff4f3595755d027bc21d3dc9bf0cc420331c569df784 + md5: 1e93b6e9ab969e1ec5bac4021bc44e9b + depends: + - __glibc >=2.17,<3.0.a0 + - gettext + - libasprintf >=0.25.1,<1.0a0 + - libgcc >=14 + - libgettextpo >=0.25.1,<1.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxt >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 64726 + timestamp: 1769445214628 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrandr-1.5.5-hb03c661_0.conda + sha256: 80ed047a5cb30632c3dc5804c7716131d767089f65877813d4ae855ee5c9d343 + md5: e192019153591938acf7322b6459d36e + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxrender >=0.9.12,<0.10.0a0 + license: MIT + license_family: MIT + size: 30456 + timestamp: 1769445263457 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda + sha256: 044c7b3153c224c6cedd4484dd91b389d2d7fd9c776ad0f4a34f099b3389f4a1 + md5: 96d57aba173e878a2089d5638016dc5e + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + license: MIT + license_family: MIT + size: 33005 + timestamp: 1734229037766 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxshmfence-1.3.3-hb9d3cd8_0.conda + sha256: c0830fe9fa78d609cd9021f797307e7e0715ef5122be3f784765dad1b4d8a193 + md5: 9a809ce9f65460195777f2f2116bae02 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 12302 + timestamp: 1734168591429 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxt-1.3.1-hb9d3cd8_0.conda + sha256: a8afba4a55b7b530eb5c8ad89737d60d60bc151a03fbef7a2182461256953f0e + md5: 279b0de5f6ba95457190a1c459a64e31 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libice >=1.1.1,<2.0a0 + - xorg-libsm >=1.2.4,<2.0a0 + - xorg-libx11 >=1.8.10,<2.0a0 + license: MIT + license_family: MIT + size: 379686 + timestamp: 1731860547604 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda + sha256: 752fdaac5d58ed863bbf685bb6f98092fe1a488ea8ebb7ed7b606ccfce08637a + md5: 7bbe9a0cc0df0ac5f5a8ad6d6a11af2f + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxi >=1.7.10,<2.0a0 + license: MIT + license_family: MIT + size: 32808 + timestamp: 1727964811275 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.7-hb03c661_0.conda + sha256: 64db17baaf36fa03ed8fae105e2e671a7383e22df4077486646f7dbf12842c9f + md5: 665d152b9c6e78da404086088077c844 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + license: MIT + license_family: MIT + size: 18701 + timestamp: 1769434732453 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-xorgproto-2025.1-hb03c661_0.conda + sha256: 7a8c64938428c2bfd016359f9cb3c44f94acc256c6167dbdade9f2a1f5ca7a36 + md5: aa8d21be4b461ce612d8f5fb791decae + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=14 + license: MIT + license_family: MIT + size: 570010 + timestamp: 1766154256151 +- conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h280c20c_3.conda + sha256: 6d9ea2f731e284e9316d95fa61869fe7bbba33df7929f82693c121022810f4ad + md5: a77f85f77be52ff59391544bfe73390a + depends: + - libgcc >=14 + - __glibc >=2.17,<3.0.a0 + license: MIT + license_family: MIT + size: 85189 + timestamp: 1753484064210 +- conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-cpp-0.8.0-h3f2d84a_0.conda + sha256: 4b0b713a4308864a59d5f0b66ac61b7960151c8022511cdc914c0c0458375eca + md5: 92b90f5f7a322e74468bb4909c7354b5 + depends: + - libstdcxx >=13 + - libgcc >=13 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + license: MIT + license_family: MIT + size: 223526 + timestamp: 1745307989800 +- conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.23.0-pyhcf101f3_1.conda + sha256: b4533f7d9efc976511a73ef7d4a2473406d7f4c750884be8e8620b0ce70f4dae + md5: 30cd29cb87d819caead4d55184c1d115 + depends: + - python >=3.10 + - python + license: MIT + license_family: MIT + size: 24194 + timestamp: 1764460141901 +- conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda + sha256: 5d7c0e5f0005f74112a34a7425179f4eb6e73c92f5d109e6af4ddeca407c92ab + md5: c9f075ab2f33b3bbee9e62d4ad0a6cd8 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libzlib 1.3.1 hb9d3cd8_2 + license: Zlib + license_family: Other + size: 92286 + timestamp: 1727963153079 +- conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.7-hb78ec9c_6.conda + sha256: 68f0206ca6e98fea941e5717cec780ed2873ffabc0e1ed34428c061e2c6268c7 + md5: 4a13eeac0b5c8e5b8ab496e6c4ddd829 + depends: + - __glibc >=2.17,<3.0.a0 + - libzlib >=1.3.1,<2.0a0 + license: BSD-3-Clause + license_family: BSD + size: 601375 + timestamp: 1764777111296 +- conda: https://conda.anaconda.org/conda-forge/linux-64/zziplib-0.13.69-he45264a_2.conda + sha256: a7c3ba25f384c7eb30c4f4c2d390f62714e0b4946d315aa852749f927b4b03ff + md5: 6d2d107e0fb8bc381acd4e9c68dbeae7 + depends: + - libgcc-ng >=12 + - libzlib >=1.3.1,<2.0a0 + license: LGPL-2.0-or-later OR MPL-1.1 + size: 106915 + timestamp: 1719242059793 diff --git a/ros/pixi.toml b/ros/pixi.toml new file mode 100644 index 0000000..fb5ff4d --- /dev/null +++ b/ros/pixi.toml @@ -0,0 +1,26 @@ +[workspace] +authors = ["Easton Potokar "] +channels = ["robostack-jazzy", "conda-forge"] +name = "ros" +platforms = ["linux-64"] +version = "0.1.0" + +[activation] +scripts = ["install/setup.sh"] + +[tasks] +build = "colcon build --event-handlers console_direct+" +oxford = "ros2 launch form odometry.launch.py bagfile:=$EVALIO_DATA/oxford_spires/blenheim_palace_01 topic:=/hesai/pandar num_rows:=64 num_columns:=1200 max_range:=60.0" + +[dependencies] +ros-jazzy-ros-base = ">=0.11.0,<0.12" +ros-jazzy-ament-cmake-auto = ">=2.5.4,<3" +compilers = ">=1.11.0,<2" +pkg-config = ">=0.29.2,<0.30" +cmake = ">=4.2.3,<5" +ninja = ">=1.13.2,<2" +colcon-common-extensions = ">=0.3.0,<0.4" +ros-jazzy-gtsam = ">=4.2.0,<5" +ros-jazzy-rviz2 = ">=14.1.19,<15" +clang = ">=22.1.0,<23" +clang-tools = ">=22.1.0,<23" diff --git a/ros/rviz/form.rviz b/ros/rviz/form.rviz new file mode 100644 index 0000000..6d9e02f --- /dev/null +++ b/ros/rviz/form.rviz @@ -0,0 +1,288 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 270 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: map_planar +Visualization Manager: + Class: "" + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 61; 229; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: kp_planar + Position Transformer: XYZ + Selectable: true + Size (Pixels): 5 + Size (m): 0.03999999910593033 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: form/kp_planar + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 127; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: kp_point + Position Transformer: XYZ + Selectable: true + Size (Pixels): 5 + Size (m): 0.03999999910593033 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: form/kp_point + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 61; 229; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: map_planar + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: form/map_planar + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 127; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: map_point + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.20000000298023224 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: form/map_point + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: point_clouds + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 100 + Name: LiDAR Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: form/odometry + Value: true + Enabled: true + Global Options: + Background Color: 0; 0; 0 + Fixed Frame: odom_lidar + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 51.88520812988281 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7853981852531433 + Target Frame: odom_lidar + Value: Orbit (rviz_default_plugins) + Yaw: 0.7853981852531433 + Saved: ~ +Window Geometry: + Displays: + collapsed: true + Height: 2752 + Hide Left Dock: true + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000379fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003b000003790000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000379fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000003790000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000013700000005afc0100000002fb0000000800540069006d00650100000000000013700000048300fffffffb0000000800540069006d0065010000000000000450000000000000000000001370000009be00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 4976 + X: 144 + Y: 54 diff --git a/ros/src/node.cpp b/ros/src/node.cpp new file mode 100644 index 0000000..902af0a --- /dev/null +++ b/ros/src/node.cpp @@ -0,0 +1,214 @@ +// MIT License +// +// Copyright (c) 2025 Easton Potokar, Taylor Pool, and Michael Kaess +// +// Adapted from KISS-ICP ROS 2 node +// (Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill +// Stachniss) +#include +#include + +// FORM-ROS +#include "node.hpp" +#include "ros_pc2.h" +#include "utils.hpp" + +// FORM +#include "form/form.hpp" + +// ROS 2 headers +#include + +#include +#include +#include +#include +#include +#include + +namespace { +gtsam::Pose3 LookupTransform(const std::string &target_frame, + const std::string &source_frame, + const std::unique_ptr &tf2_buffer) { + std::string err_msg; + if (tf2_buffer->canTransform(target_frame, source_frame, tf2::TimePointZero, + &err_msg)) { + try { + auto tf = tf2_buffer->lookupTransform(target_frame, source_frame, + tf2::TimePointZero); + return tf2::transformToGtsam(tf); + } catch (tf2::TransformException &ex) { + RCLCPP_WARN(rclcpp::get_logger("LookupTransform"), "%s", ex.what()); + } + } + RCLCPP_WARN(rclcpp::get_logger("LookupTransform"), "Failed to find tf. Reason=%s", + err_msg.c_str()); + return gtsam::Pose3::Identity(); +} +} // namespace + +namespace form_ros { + +EstimatorNode::EstimatorNode(const rclcpp::NodeOptions &options) + : rclcpp::Node("form_node", options) { + // clang-format off + + // ROS parameters + base_frame_ = declare_parameter("base_frame", base_frame_); + lidar_odom_frame_ = declare_parameter("lidar_odom_frame", lidar_odom_frame_); + publish_odom_tf_ = declare_parameter("publish_odom_tf", true); + invert_odom_tf_ = declare_parameter("invert_odom_tf", true); + publish_debug_clouds_ = declare_parameter("publish_debug_clouds", false); + position_covariance_ = declare_parameter("position_covariance", 0.1); + orientation_covariance_ = declare_parameter("orientation_covariance", 0.1); + + // FORM parameters + form::Estimator::Params params; + + // LiDAR geometry (required) + params.extraction.num_rows = declare_parameter("num_rows", params.extraction.num_rows); + params.extraction.num_columns = declare_parameter("num_columns", params.extraction.num_columns); + auto min_range = declare_parameter("min_range", 1.0); + auto max_range = declare_parameter("max_range", 100.0); + params.extraction.min_norm_squared = min_range * min_range; + params.extraction.max_norm_squared = max_range * max_range; + + // Feature extraction + params.extraction.neighbor_points = declare_parameter("neighbor_points", params.extraction.neighbor_points); + params.extraction.num_sectors = declare_parameter("num_sectors", params.extraction.num_sectors); + params.extraction.planar_threshold = declare_parameter("planar_threshold", params.extraction.planar_threshold); + params.extraction.planar_feats_per_sector = declare_parameter("planar_feats_per_sector", params.extraction.planar_feats_per_sector); + params.extraction.point_feats_per_sector = declare_parameter("point_feats_per_sector", params.extraction.point_feats_per_sector); + params.extraction.radius = declare_parameter("radius", params.extraction.radius); + params.extraction.min_points = declare_parameter("min_points", params.extraction.min_points); + + // Optimization + params.matcher.max_dist_matching = declare_parameter("max_dist_matching", params.matcher.max_dist_matching); + params.matcher.new_pose_threshold = declare_parameter("new_pose_threshold", params.matcher.new_pose_threshold); + params.matcher.max_num_rematches = declare_parameter("max_num_rematches", params.matcher.max_num_rematches); + + // Constraints + params.constraints.disable_smoothing = + declare_parameter("disable_smoothing", params.constraints.disable_smoothing); + + // Mapping + params.scans.max_num_keyscans = declare_parameter("max_num_keyscans", params.scans.max_num_keyscans); + params.scans.max_num_recent_scans = declare_parameter("max_num_recent_scans", params.scans.max_num_recent_scans); + params.scans.max_steps_unused_keyscan = declare_parameter("max_steps_unused_keyscan", params.scans.max_steps_unused_keyscan); + params.scans.keyscan_match_ratio = declare_parameter("keyscan_match_ratio", params.scans.keyscan_match_ratio); + params.map.min_dist_map = declare_parameter("min_dist_map", params.map.min_dist_map); + + // Misc + params.num_threads = declare_parameter("num_threads", params.num_threads); + + // Construct the FORM estimator + estimator_ = form::Estimator(params); + + // Initialize subscribers + pointcloud_sub_ = create_subscription( + "pointcloud_topic", rclcpp::SensorDataQoS(), + std::bind(&EstimatorNode::register_frame, this, std::placeholders::_1)); + + // Initialize publishers + rclcpp::QoS qos((rclcpp::SystemDefaultsQoS().keep_last(1).durability_volatile())); + odom_publisher_ = create_publisher("form/odometry", qos); + if (publish_debug_clouds_) { + planar_publisher_ = create_publisher("form/kp_planar", qos); + point_publisher_ = create_publisher("form/kp_point", qos); + + map_planar_publisher_ = create_publisher("form/map_planar", qos); + map_point_publisher_ = create_publisher("form/map_point", qos); + } + + // Initialize the transform broadcaster + tf_broadcaster_ = std::make_unique(*this); + tf2_buffer_ = std::make_unique(this->get_clock()); + tf2_buffer_->setUsingDedicatedThread(true); + tf2_listener_ = std::make_unique(*tf2_buffer_); + + RCLCPP_INFO(this->get_logger(), "FORM ROS 2 odometry node initialized"); + // clang-format on +} + +void EstimatorNode::register_frame( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) { + // Convert PointCloud2 -> organized vector using pc2_conversions + const auto points = + form_ros::PointCloud2ToForm(msg, estimator_.m_params.extraction.num_rows, + estimator_.m_params.extraction.num_columns); + + // Register frame with FORM + const auto &[planar_kp, point_kp] = estimator_.register_scan(points); + + // Get the current pose estimate + const gtsam::Pose3 pose = estimator_.current_lidar_estimate(); + + // Publish odometry + publish_odometry(pose, msg->header); + + // Publish debug clouds if requested + if (publish_debug_clouds_) { + // current keypoints + publish_clouds(planar_kp, planar_publisher_, msg->header); + publish_clouds(point_kp, point_publisher_, msg->header); + // current map + const auto [map_planar, map_point] = estimator_.current_map(); + auto local_map_header = msg->header; + local_map_header.frame_id = lidar_odom_frame_; + publish_clouds(map_planar, map_planar_publisher_, local_map_header); + publish_clouds(map_point, map_point_publisher_, local_map_header); + } +} + +void EstimatorNode::publish_odometry(const gtsam::Pose3 &form_pose, + const std_msgs::msg::Header &header) { + // If necessary, transform the ego-centric pose to the specified + // base_link/base_footprint frame + const auto cloud_frame_id = utils::FixFrameId(header.frame_id); + const auto egocentric_estimation = + (base_frame_.empty() || base_frame_ == cloud_frame_id); + const auto moving_frame = egocentric_estimation ? cloud_frame_id : base_frame_; + const auto pose = [&]() -> gtsam::Pose3 { + if (egocentric_estimation) + return form_pose; + const gtsam::Pose3 cloud2base = + LookupTransform(base_frame_, cloud_frame_id, tf2_buffer_); + return cloud2base * form_pose * cloud2base.inverse(); + }(); + + // Broadcast the tf + if (publish_odom_tf_) { + geometry_msgs::msg::TransformStamped transform_msg; + transform_msg.header.stamp = header.stamp; + if (invert_odom_tf_) { + transform_msg.header.frame_id = moving_frame; + transform_msg.child_frame_id = lidar_odom_frame_; + transform_msg.transform = tf2::gtsamToTransform(pose.inverse()); + } else { + transform_msg.header.frame_id = lidar_odom_frame_; + transform_msg.child_frame_id = moving_frame; + transform_msg.transform = tf2::gtsamToTransform(pose); + } + tf_broadcaster_->sendTransform(transform_msg); + } + + // Publish odometry msg + nav_msgs::msg::Odometry odom_msg; + odom_msg.header.stamp = header.stamp; + odom_msg.header.frame_id = lidar_odom_frame_; + odom_msg.child_frame_id = moving_frame; + odom_msg.pose.pose = tf2::gtsamToPose(pose); + odom_msg.pose.covariance.fill(0.0); + odom_msg.pose.covariance[0] = position_covariance_; + odom_msg.pose.covariance[7] = position_covariance_; + odom_msg.pose.covariance[14] = position_covariance_; + odom_msg.pose.covariance[21] = orientation_covariance_; + odom_msg.pose.covariance[28] = orientation_covariance_; + odom_msg.pose.covariance[35] = orientation_covariance_; + odom_publisher_->publish(std::move(odom_msg)); +} + +} // namespace form_ros + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(form_ros::EstimatorNode) diff --git a/ros/src/node.hpp b/ros/src/node.hpp new file mode 100644 index 0000000..6b0a5cd --- /dev/null +++ b/ros/src/node.hpp @@ -0,0 +1,81 @@ +// MIT License +// +// Copyright (c) 2025 Easton Potokar, Taylor Pool, and Michael Kaess +// +// Adapted from KISS-ICP ROS 2 node +// (Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill +// Stachniss) +#pragma once + +// FORM +#include "form/form.hpp" +#include "utils.hpp" + +// ROS 2 +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace form_ros { + +class EstimatorNode : public rclcpp::Node { +public: + /// EstimatorNode constructor + EstimatorNode() = delete; + explicit EstimatorNode(const rclcpp::NodeOptions &options); + +private: + /// Register new frame + void register_frame(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); + + /// Stream the estimated pose to ROS + void publish_odometry(const gtsam::Pose3 &pose, + const std_msgs::msg::Header &header); + + /// Stream the keypoints for visualization + template + void publish_clouds( + const std::vector &points, + rclcpp::Publisher::SharedPtr publisher, + const std_msgs::msg::Header &header) { + publisher->publish(std::move(utils::FeatsToPointCloud2(points, header))); + } + +private: + /// Tools for broadcasting TFs. + std::unique_ptr tf_broadcaster_; + std::unique_ptr tf2_buffer_; + std::unique_ptr tf2_listener_; + bool invert_odom_tf_; + bool publish_odom_tf_; + bool publish_debug_clouds_; + + /// Data subscribers. + rclcpp::Subscription::SharedPtr pointcloud_sub_; + + /// Data publishers. + rclcpp::Publisher::SharedPtr odom_publisher_; + rclcpp::Publisher::SharedPtr planar_publisher_; + rclcpp::Publisher::SharedPtr point_publisher_; + rclcpp::Publisher::SharedPtr map_planar_publisher_; + rclcpp::Publisher::SharedPtr map_point_publisher_; + + /// FORM estimator + form::Estimator estimator_; + + /// Global/map coordinate frame. + std::string lidar_odom_frame_{"odom_lidar"}; + std::string base_frame_{}; + + /// Covariance diagonal + double position_covariance_; + double orientation_covariance_; +}; + +} // namespace form_ros diff --git a/ros/src/ros_pc2.h b/ros/src/ros_pc2.h new file mode 100644 index 0000000..fc9eb0a --- /dev/null +++ b/ros/src/ros_pc2.h @@ -0,0 +1,240 @@ +// Adapted from evalio's pc2_conversions.h +// https://github.com/contagon/evalio/blob/main/cpp/bindings/ros_pc2.h +// +// Converts ROS PointCloud2 messages into organized form::PointXYZf vectors +// (row-major, num_rows * num_columns) suitable for FORM's feature extraction. +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include
+#include + +namespace form_ros { + +// ----------------------------- Data getters ----------------------------- // +// Build a lambda that reads a field of type T from raw PointCloud2 byte data +// at the given offset, handling the various PointField datatypes. +template +std::function data_getter(uint8_t datatype, + uint32_t offset) { + using sensor_msgs::msg::PointField; + switch (datatype) { + case PointField::UINT8: + return [offset](T &value, const uint8_t *data) noexcept { + value = static_cast(data[offset]); + }; + case PointField::INT8: + return [offset](T &value, const uint8_t *data) noexcept { + value = static_cast(*reinterpret_cast(data + offset)); + }; + case PointField::UINT16: + return [offset](T &value, const uint8_t *data) noexcept { + uint16_t v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + case PointField::INT16: + return [offset](T &value, const uint8_t *data) noexcept { + int16_t v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + case PointField::UINT32: + return [offset](T &value, const uint8_t *data) noexcept { + uint32_t v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + case PointField::INT32: + return [offset](T &value, const uint8_t *data) noexcept { + int32_t v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + case PointField::FLOAT32: + return [offset](T &value, const uint8_t *data) noexcept { + float v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + case PointField::FLOAT64: + return [offset](T &value, const uint8_t *data) noexcept { + double v; + std::memcpy(&v, data + offset, sizeof(v)); + value = static_cast(v); + }; + default: + throw std::runtime_error("Unsupported PointField datatype: " + + std::to_string(datatype)); + } +} + +template std::function blank() { + return [](T &, const uint8_t *) noexcept {}; +} + +// ------------------------- Reordering Helpers ------------------------- // +// Holds parsed per-point data before reordering into the organized grid. +struct RawPoint { + float x = 0.0f; + float y = 0.0f; + float z = 0.0f; + uint8_t row = 0; + uint16_t col = 0; +}; + +// Iterates through points to fill in columns +inline void +_fill_col(std::vector &mm, + std::function + func_col) { + // fill out the first one to kickstart + uint16_t prev_col = 0; + uint8_t prev_row = mm[0].row; + for (auto p = mm.begin() + 1; p != mm.end(); ++p) { + func_col(p->col, prev_col, prev_row, p->row); + prev_col = p->col; + prev_row = p->row; + } +} + +// Fills in column index for row major order +inline void fill_col_row_major(std::vector &mm) { + auto func_col = [](uint16_t &col, const uint16_t &prev_col, + const uint8_t &prev_row, const uint8_t &curr_row) { + if (prev_row != curr_row) { + col = 0; + } else { + col = prev_col + 1; + } + }; + + _fill_col(mm, func_col); +} + +// Fills in column index for column major order +inline void fill_col_col_major(std::vector &mm) { + auto func_col = [](uint16_t &col, const uint16_t &prev_col, + const uint8_t &prev_row, const uint8_t &curr_row) { + if (curr_row < prev_row) { + col = prev_col + 1; + } else { + col = prev_col; + } + }; + + _fill_col(mm, func_col); +} + +inline std::vector +reorder_points(std::vector &mm, size_t num_rows, size_t num_cols) { + std::vector output(num_rows * num_cols, + form::PointXYZf(0.0f, 0.0f, 0.0f)); + + for (auto p : mm) { + if (p.row >= num_rows || p.col >= num_cols) { + std::cerr << "Warning: Point with row " << static_cast(p.row) + << " and col " << p.col + << " is out of bounds for num_rows=" << num_rows + << " and num_cols=" << num_cols << ". Skipping this point." + << std::endl; + continue; + } + output[p.row * num_cols + p.col] = form::PointXYZf(p.x, p.y, p.z); + } + return output; +} + +// ------------------------- Main Conversion ------------------------- // +inline std::vector +PointCloud2ToForm(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, + int num_rows, int num_columns) { + if (msg->is_bigendian) { + throw std::runtime_error("Big-endian PointCloud2 is not supported"); + } + + const int n_points = static_cast(msg->width) * static_cast(msg->height); + + // Build field accessors + std::function func_x = blank(); + std::function func_y = blank(); + std::function func_z = blank(); + std::function func_row = blank(); + + bool has_x = false; + bool has_y = false; + bool has_z = false; + bool has_row = false; + + for (const auto &field : msg->fields) { + if (field.name == "x") { + func_x = data_getter(field.datatype, field.offset); + has_x = true; + } else if (field.name == "y") { + func_y = data_getter(field.datatype, field.offset); + has_y = true; + } else if (field.name == "z") { + func_z = data_getter(field.datatype, field.offset); + has_z = true; + } else if (field.name == "ring" || field.name == "row" || field.name == "channel") { + func_row = data_getter(field.datatype, field.offset); + has_row = true; + } + } + + // Validate that all required fields were found + if (!has_x || !has_y || !has_z) { + throw std::runtime_error( + "PointCloud2ToForm: Missing required point fields; expected fields 'x', 'y', and 'z'."); + } + if (!has_row) { + throw std::runtime_error( + "PointCloud2ToForm: Missing required row indicator field; expected one of 'ring', 'row', or 'channel'."); + } + + // Parse all points + std::vector raw(n_points); + const uint8_t *data = msg->data.data(); + for (size_t i = 0; i < n_points; ++i) { + const uint8_t *pt = data + i * msg->point_step; + func_x(raw[i].x, pt); + func_y(raw[i].y, pt); + func_z(raw[i].z, pt); + func_row(raw[i].row, pt); + } + + // Catch some potential edge cases with bad values + if (n_points > num_columns * num_rows) { + std::cerr << "Warning: PointCloud2 has more points than expected from num_rows " + "and num_columns. Please check your parameters." + << std::endl; + } + + // Infer properties of the cloud + bool all_points_present = (n_points == num_rows * num_columns); + bool row_major = true; + if (n_points >= 2) { + row_major = (raw[0].row == raw[1].row); + } + + // Fill out column indices based on inferred ordering + if (row_major) { + fill_col_row_major(raw); + } else { + fill_col_col_major(raw); + } + + return reorder_points(raw, num_rows, num_columns); +} + +} // namespace form_ros diff --git a/ros/src/utils.hpp b/ros/src/utils.hpp new file mode 100644 index 0000000..351d382 --- /dev/null +++ b/ros/src/utils.hpp @@ -0,0 +1,118 @@ +// MIT License +// +// Copyright (c) 2025 Easton Potokar, Taylor Pool, and Michael Kaess +// +// Adapted from KISS-ICP ROS 2 utility code +// (Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill +// Stachniss) +#pragma once + +#include +#include +#include +#include +#include +#include + +#include + +// ROS 2 +#include +#include +#include +#include +#include +#include +#include +#include + +namespace tf2 { + +inline geometry_msgs::msg::Transform gtsamToTransform(const gtsam::Pose3 &T) { + geometry_msgs::msg::Transform t; + t.translation.x = T.translation().x(); + t.translation.y = T.translation().y(); + t.translation.z = T.translation().z(); + + auto q = T.rotation().toQuaternion(); + t.rotation.x = q.x(); + t.rotation.y = q.y(); + t.rotation.z = q.z(); + t.rotation.w = q.w(); + + return t; +} + +inline geometry_msgs::msg::Pose gtsamToPose(const gtsam::Pose3 &T) { + geometry_msgs::msg::Pose t; + t.position.x = T.translation().x(); + t.position.y = T.translation().y(); + t.position.z = T.translation().z(); + + auto q = T.rotation().toQuaternion(); + t.orientation.x = q.x(); + t.orientation.y = q.y(); + t.orientation.z = q.z(); + t.orientation.w = q.w(); + + return t; +} + +inline gtsam::Pose3 +transformToGtsam(const geometry_msgs::msg::TransformStamped &transform) { + const auto &t = transform.transform; + return gtsam::Pose3( + gtsam::Rot3::Quaternion(t.rotation.w, t.rotation.x, t.rotation.y, + t.rotation.z), + gtsam::Point3(t.translation.x, t.translation.y, t.translation.z)); +} +} // namespace tf2 + +namespace form_ros::utils { + +using PointCloud2 = sensor_msgs::msg::PointCloud2; +using PointField = sensor_msgs::msg::PointField; +using Header = std_msgs::msg::Header; + +inline std::string FixFrameId(const std::string &frame_id) { + return std::regex_replace(frame_id, std::regex("^/"), ""); +} + +template +inline std::unique_ptr +FeatsToPointCloud2(const std::vector &points, const Header &header) { + // ------------------------- Setup PC2 Message ------------------------- // + auto msg = std::make_unique(); + msg->header = header; + msg->header.frame_id = FixFrameId(msg->header.frame_id); + msg->fields.clear(); + + int offset = 0; + offset = addPointField(*msg, "x", 1, PointField::FLOAT32, offset); + offset = addPointField(*msg, "y", 1, PointField::FLOAT32, offset); + offset = addPointField(*msg, "z", 1, PointField::FLOAT32, offset); + offset += sizeOfPointField(PointField::FLOAT32); + + // Resize the point cloud accordingly + msg->width = points.size(); + msg->height = 1; + msg->point_step = offset; + + msg->row_step = msg->width * msg->point_step; + msg->data.resize(msg->height * msg->row_step); + + // ------------------------- Fill Point Cloud ------------------------- // + sensor_msgs::PointCloud2Iterator msg_x(*msg, "x"); + sensor_msgs::PointCloud2Iterator msg_y(*msg, "y"); + sensor_msgs::PointCloud2Iterator msg_z(*msg, "z"); + for (size_t i = 0; i < points.size(); i++, ++msg_x, ++msg_y, ++msg_z) { + const auto &point = points[i]; + *msg_x = static_cast(point.x); + *msg_y = static_cast(point.y); + *msg_z = static_cast(point.z); + } + + return msg; +} + +} // namespace form_ros::utils