From e62ea2bfe4b31d70fe338bdd805b7fb75dd5436c Mon Sep 17 00:00:00 2001 From: Wolf Vollprecht Date: Thu, 20 Jun 2024 21:42:47 +0200 Subject: [PATCH] only linux --- .github/workflows/main.yml | 2 +- README.md | 30 +-- env/robostackenv.yaml | 7 +- vinca_linux_64.yaml | 479 +------------------------------------ vinca_linux_aarch64.yaml | 391 ------------------------------ vinca_osx.yaml | 104 -------- vinca_osx_arm64.yaml | 95 -------- vinca_win.yaml | 79 ------ 8 files changed, 20 insertions(+), 1167 deletions(-) delete mode 100644 vinca_linux_aarch64.yaml delete mode 100644 vinca_osx.yaml delete mode 100644 vinca_osx_arm64.yaml delete mode 100644 vinca_win.yaml diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index e2e21ca7..8d12311c 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -18,7 +18,7 @@ jobs: python-version: '3.11' # Version range or exact version of a Python version to use, using SemVer's version range syntax - name: Install vinca run: | - pip install git+https://github.com/RoboStack/vinca.git + pip install git+https://github.com/RoboStack/vinca.git@rattler-build - name: Generate recipes for linux-64 run: | diff --git a/README.md b/README.md index 4572a27c..bd8c57db 100644 --- a/README.md +++ b/README.md @@ -1,26 +1,26 @@ -# RoboStack (for ROS humble) +# RoboStack (for ROS jazzy) -[![Conda](https://img.shields.io/conda/dn/robostack-humble/ros-humble-desktop?style=flat-square)](https://anaconda.org/robostack/) +[![Conda](https://img.shields.io/conda/dn/robostack-jazzy/ros-jazzy-desktop?style=flat-square)](https://anaconda.org/robostack/) [![Gitter](https://img.shields.io/gitter/room/RoboStack/Lobby?style=flat-square)](https://gitter.im/RoboStack/Lobby) -[![GitHub Repo stars](https://img.shields.io/github/stars/robostack/ros-humble?style=flat-square)](https://github.com/RoboStack/ros-humble/) +[![GitHub Repo stars](https://img.shields.io/github/stars/robostack/ros-jazzy?style=flat-square)](https://github.com/RoboStack/ros-jazzy/) [![QUT Centre for Robotics](https://img.shields.io/badge/collection-QUT%20Robotics-%23043d71?style=flat-square)](https://qcr.github.io/) -[![Platforms](https://img.shields.io/badge/platforms-linux%20%7C%20win%20%7C%20macos%20%7C%20macos_arm64%20%7C%20linux_aarch64-green.svg?style=flat-square)](https://github.com/RoboStack/ros-humble) -[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-humble/linux.yml?branch=buildbranch_linux&label=build%20linux&style=flat-square)](https://github.com/RoboStack/ros-humble/actions/workflows/linux.yml) -[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-humble/win.yml?branch=buildbranch_win&label=build%20win&style=flat-square)](https://github.com/RoboStack/ros-humble/actions/workflows/win.yml) -[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-humble/osx.yml?branch=buildbranch_osx&label=build%20osx&style=flat-square)](https://github.com/RoboStack/ros-humble/actions/workflows/osx.yml) -[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-humble/osx_arm64.yml?branch=buildbranch_osx_arm64&label=build%20osx-arm64&style=flat-square)](https://github.com/RoboStack/ros-humble/actions/workflows/osx_arm64.yml) -[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-humble/build_linux_aarch64.yml?branch=buildbranch_linux_aarch64&label=build%20aarch64&style=flat-square)](https://github.com/RoboStack/ros-humble/actions/workflows/build_linux_aarch64.yml) +[![Platforms](https://img.shields.io/badge/platforms-linux%20%7C%20win%20%7C%20macos%20%7C%20macos_arm64%20%7C%20linux_aarch64-green.svg?style=flat-square)](https://github.com/RoboStack/ros-jazzy) +[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-jazzy/linux.yml?branch=buildbranch_linux&label=build%20linux&style=flat-square)](https://github.com/RoboStack/ros-jazzy/actions/workflows/linux.yml) +[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-jazzy/win.yml?branch=buildbranch_win&label=build%20win&style=flat-square)](https://github.com/RoboStack/ros-jazzy/actions/workflows/win.yml) +[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-jazzy/osx.yml?branch=buildbranch_osx&label=build%20osx&style=flat-square)](https://github.com/RoboStack/ros-jazzy/actions/workflows/osx.yml) +[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-jazzy/osx_arm64.yml?branch=buildbranch_osx_arm64&label=build%20osx-arm64&style=flat-square)](https://github.com/RoboStack/ros-jazzy/actions/workflows/osx_arm64.yml) +[![Azure DevOps builds (branch)](https://img.shields.io/github/actions/workflow/status/robostack/ros-jazzy/build_linux_aarch64.yml?branch=buildbranch_linux_aarch64&label=build%20aarch64&style=flat-square)](https://github.com/RoboStack/ros-jazzy/actions/workflows/build_linux_aarch64.yml) -[![GitHub issues](https://img.shields.io/github/issues-raw/robostack/ros-humble?style=flat-square)](https://github.com/RoboStack/ros-humble/issues) -[![GitHub closed issues](https://img.shields.io/github/issues-closed-raw/robostack/ros-humble?style=flat-square)](https://github.com/RoboStack/ros-humble/issues?q=is%3Aissue+is%3Aclosed) -[![GitHub pull requests](https://img.shields.io/github/issues-pr-raw/robostack/ros-humble?style=flat-square)](https://github.com/RoboStack/ros-humble/pulls) -[![GitHub closed pull requests](https://img.shields.io/github/issues-pr-closed-raw/robostack/ros-humble?style=flat-square)](https://github.com/RoboStack/ros-humble/pulls?q=is%3Apr+is%3Aclosed) +[![GitHub issues](https://img.shields.io/github/issues-raw/robostack/ros-jazzy?style=flat-square)](https://github.com/RoboStack/ros-jazzy/issues) +[![GitHub closed issues](https://img.shields.io/github/issues-closed-raw/robostack/ros-jazzy?style=flat-square)](https://github.com/RoboStack/ros-jazzy/issues?q=is%3Aissue+is%3Aclosed) +[![GitHub pull requests](https://img.shields.io/github/issues-pr-raw/robostack/ros-jazzy?style=flat-square)](https://github.com/RoboStack/ros-jazzy/pulls) +[![GitHub closed pull requests](https://img.shields.io/github/issues-pr-closed-raw/robostack/ros-jazzy?style=flat-square)](https://github.com/RoboStack/ros-jazzy/pulls?q=is%3Apr+is%3Aclosed) -[__Table with all available packages & architectures__](https://robostack.github.io/humble.html) +[__Table with all available packages & architectures__](https://robostack.github.io/jazzy.html) ## Why ROS and Conda? -Welcome to RoboStack, which tightly couples ROS with Conda, a cross-platform, language-agnostic package manager. We provide ROS binaries for Linux, macOS, Windows and ARM (Linux). Installing other recent packages via conda-forge side-by-side works easily, e.g. you can install TensorFlow/PyTorch in the same environment as ROS humble without any issues. As no system libraries are used, you can also easily install ROS humble on any recent Linux Distribution - including older versions of Ubuntu. As the packages are pre-built, it saves you from compiling from source, which is especially helpful on macOS and Windows. No root access is required, all packages live in your home directory. We have recently written up a [paper](https://arxiv.org/abs/2104.12910) and [blog post](https://medium.com/robostack/cross-platform-conda-packages-for-ros-fa1974fd1de3) with more information. +Welcome to RoboStack, which tightly couples ROS with Conda, a cross-platform, language-agnostic package manager. We provide ROS binaries for Linux, macOS, Windows and ARM (Linux). Installing other recent packages via conda-forge side-by-side works easily, e.g. you can install TensorFlow/PyTorch in the same environment as ROS jazzy without any issues. As no system libraries are used, you can also easily install ROS jazzy on any recent Linux Distribution - including older versions of Ubuntu. As the packages are pre-built, it saves you from compiling from source, which is especially helpful on macOS and Windows. No root access is required, all packages live in your home directory. We have recently written up a [paper](https://arxiv.org/abs/2104.12910) and [blog post](https://medium.com/robostack/cross-platform-conda-packages-for-ros-fa1974fd1de3) with more information. ## Attribution If you use RoboStack in your academic work, please refer to the following paper: diff --git a/env/robostackenv.yaml b/env/robostackenv.yaml index 95af1c9d..16b1bbb5 100644 --- a/env/robostackenv.yaml +++ b/env/robostackenv.yaml @@ -4,17 +4,14 @@ channels: - conda-forge dependencies: - python=3.11 -- conda-build - anaconda-client -- mamba -- conda - catkin_pkg - ruamel.yaml - rosdistro - empy - networkx - requests -- boa +- rattler-build - pip - pip: - - git+https://github.com/RoboStack/vinca.git@master + - git+https://github.com/RoboStack/vinca.git@rattler-build diff --git a/vinca_linux_64.yaml b/vinca_linux_64.yaml index 831167d3..d3c09fe5 100644 --- a/vinca_linux_64.yaml +++ b/vinca_linux_64.yaml @@ -5,7 +5,7 @@ conda_index: - robostack.yaml - packages-ignore.yaml -build_number: 6 +build_number: 0 mutex_package: ros2-distro-mutex 0.5 jazzy @@ -16,9 +16,6 @@ skip_all_deps: false full_rebuild: true packages_skip_by_deps: - # - nav2-rotation-shim-controller - # - rviz - # - diagnostic_updater - cartographer - octomap @@ -26,487 +23,15 @@ packages_remove_from_deps: - cartographer - octomap - warehouse_ros_mongo - # - stage-ros - # - python_qt_binding - # - joint_state_publisher_gui - # - stage skip_existing: - - https://conda.anaconda.org/robostack-staging/ + - https://conda.anaconda.org/robostack-jazzy/ packages_select_by_deps: - # only subset of packages to reduce maintainer load - - qt-qui-cpp # needs to be compiled locally - - - generator-dds-idl - ros_workspace - ros_environment - - ament_cmake - ros_base - - desktop - - navigation2 - - graph_msgs - - nav2_bringup - - turtlebot3 - - desktop_full - - apriltag - - turtlebot3_fake_node - - ur - - ublox - - robot_localization - - topic_tools - - stubborn_buddies - - teleop_tools - - udp_driver - - urdf_tutorial - - test_bond - - apex_test_tools - - ublox_dgnss - - velodyne_description - - velodyne - - visp - - apex_containers - - apex_test_tools - - bno055 - - aws_robomaker_small_warehouse_world - - avt_vimba_camera - - ros_ign - - spacenav - - system_modes - - tf_transformations - - turtle_tf2_cpp - - turtle_tf2_py - - ros2controlcli - - robot_controllers - - ros2_control - - ros2_controllers - - control-toolbox - - joint-trajectory-controller - - gazebo-dev - - gazebo-plugins - - gazebo-ros - - gazebo-ros-pkgs - - turtlebot3_gazebo - - turtlebot3_simulations - - rqt - - rqt_image_overlay - - rqt-robot-dashboard - - rqt-robot-monitor - - rqt-robot-steering - - joint-state-broadcaster - - joint-state-publisher - - xacro - - image-pipeline - - image-view - - bond-core - - camera-calibration - - camera-calibration-parsers - - camera-info-manager - - slam-toolbox - - foxglove_bridge - - ament-cmake-nose - - geographic_info - - geodesy - - rosbridge_suite - - ament_cmake_catch2 - - apriltag - - apriltag_ros - - marker-msgs - # - moveit - # - moveit-ros-perception - # - moveit-runtime - # - moveit-servo - # - moveit_visual_tools - # - moveit_servo - # - rqt-moveit - - - librealsense2 - - realsense2-camera - - realsense2-camera-msgs - - realsense2-description - - webots_ros2 - - rosidl-generator-dds-idl - - # ros2_control - - gazebo-ros2-control - - # Modern gz-sim integration - - ros-gz - - libg2o - - # Needs fixing - # - moveit-resources - - # ----- end of package support ----- - - # - rtabmap - # - control-box-rst - - # - plotjuggler - # - plotjuggler_ros - - # - zmqpp_vendor - - # - fogros2 - # - foxglove_msgs - # - four_wheel_steering_msgs - # - geometry_tutorials - # - gps_tools - # - gps_umd - # - gpsd_client - - # - gscam - - # - v4l2_camera - # - usb_cam - - # - zbar_ros - # - vitis_common - # - urg_node - # - ur_bringup - # - ublox_dgnss_node - # - ublox_ubx_interfaces - # - twist_mux - - # - ros2acceleration - # - ros2launch_security - # - ros2launch_security_examples - # - ros2nodl - # - ros2trace - - # - rosapi - # - rosbag2_storage_mcap - # - rosbag2_performance_benchmarking - - # - rosbridge_suite - - # - can_msgs - # - cartographer_rviz - # - cascade_lifecycle_msgs - # - chomp_motion_planner - # - color_names - # - cudnn_cmake_module - - # - rmf_demos - # - rmf_traffic_msgs - # - rmf_demos_maps - # - rmf_demos_tasks - - # - adaptive_component - # - async_web_server_cpp - # - boost_geometry_util - - # - ros2_ouster - # - ros2_socketcan - # - ros2trace_analysis - # - rplidar_ros - # - rot_conv - # - rt_manipulators - # - rt_manipulators_examples - - # - acado_vendor - # - automotive_autonomy_msgs - # - automotive_navigation_msgs - # - automotive_platform_msgs - # - autoware_auto_msgs - - # - dolly - - # - rviz_imu_plugin - # - sdformat_test_files - # - sdformat_urdf - # - self_test - # - serial_driver - # - simple_launch - # - slider_publisher - # - soccer_interfaces - # - topic_statistics_demo - - # needs babeltools and lttng-python on conda-forge - # - smacc2 - - # Not yet working - # - tvm_vendor - # - zenoh_bridge_dds - # - velodyne_simulator - # - wiimote - # - depthai - # - turtlebot3 - - # - behaviortree_cpp_v3 - # - ros_workspace - # - ros1_bridge - - # Used to work, now needs fixes - # - webots-ros2 - # - webots-ros2-abb - # - webots-ros2-core - # - webots-ros2-demos - # - webots-ros2-epuck - # - webots-ros2-examples - # - webots-ros2-importer - # - webots-ros2-msgs - # - webots-ros2-tesla - # - webots-ros2-tiago - # - webots-ros2-turtlebot - # - webots-ros2-tutorials - # - webots-ros2-universal-robot - # - webots-ros2-ur-e-description - # - webots_ros2 - - # needs a rebuild of ros-noetic first - # - ros1-rosbag-storage-vendor - - # build locally but not on CI; for now uploaded from local - # - popf - # - ros-ign-bridge - # - ros-ign-image - - # working - # - sbg_driver - # - ruckig - # - rosbridge-msgs - # - rosbridge-library - # - ros2launch-security - # - picknik-ament-copyright - # - nodl-to-policy - # - geometry-tutorials - # - sdformat-urdf - # - cartographer-ros - # - plansys2-bt-actions - # - plansys2-terminal - # - nav2-system-tests - # - lanelet2 - # - plansys2-bringup - # - octovis - # - gps-umd - # - usb-cam - # - tvm-vendor - # - ros2-socketcan - # - mrpt2 - # - ublox-dgnss - # - fmi-adapter-examples - # - spacenav - # - ros-ign - # - menge-vendor - # - openvslam - # - ackermann-msgs - # - four-wheel-steering-msgs - # - ign-rviz - # - ign-rviz-common - # - ign-rviz-plugins - # - libphidget22 - # - nao-lola - # - phidgets-accelerometer - # - phidgets-analog-inputs - # - phidgets-api - # - phidgets-digital-inputs - # - phidgets-digital-outputs - # - phidgets-drivers - # - phidgets-gyroscope - # - phidgets-high-speed-encoder - # - phidgets-ik - # - phidgets-magnetometer - # - phidgets-motors - # - phidgets-spatial - # - phidgets-temperature - # - ros-ign-bridge - # - ros-ign-gazebo - # - ros-ign-image - # - ros-ign-interfaces - # - soccer-marker-generation - # - vision-msgs - # - acado-vendor - # - ament-clang-format - # - ament_clang_tidy - # - ament-cmake-catch2 - # - ament_cmake_clang_tidy - # - ament-cmake-clang-format - # - ament_cmake_mypy - # - ament_cmake_nose - # - ament_cmake_pclint - # - ament_cmake_pycodestyle - # - ament_cmake_pyflakes - # - ament_download - # - ament_pclint - # - ament_pyflakes - # - ament-nodl - # - ament-pclint - # - ament-pycodestyle - # - ament-pyflakes - # - apex-containers - # - apex-test-tools - # - apriltag - # - async-web-server-cpp - # - autoware-auto-msgs - # - backward-ros - # - bno055 - # - can-msgs - # - cartographer-ros-msgs - # - cascade-lifecycle-msgs - # - color-names - # - compressed-depth-image-transport - # - compressed-image-transport - # - depth-image-proc - # - diagnostic-aggregator - # - diagnostic-updater - # - domain-bridge - # - dynamic-edt-3d - # - dynamixel-sdk - # - dynamixel-sdk-custom-interfaces - # - dynamixel-sdk-examples - # - examples-rclcpp-cbg-executor - # - examples-rclpy-guard-conditions - # - examples-rclpy-pointcloud-publisher - # - examples-tf2-py - # - filters - # - geographic-info - # - geographic-msgs - # - gps-msgs - # - gps-tools - # - grbl-msgs - # - grbl-ros - # - gurumdds-cmake-module - # - hls-lfcd-lds-driver - # - ifm3d-core - # - image-common - # - image-proc - # - image-publisher - # - image-rotate - # - joy-linux - # - joy-teleop - # - key-teleop - # - laser-proc - # - launch-system-modes - # - lgsvl-msgs - # - libmavconn - # - marti-can-msgs - # - marti-common-msgs - # - marti-dbw-msgs - # - marti-nav-msgs - # - marti-perception-msgs - # - marti-sensor-msgs - # - marti-status-msgs - # - marti-visualization-msgs - # - mavlink - # - mavros - # - mavros-msgs - # - mouse-teleop - # - nao-button-sim - # - nao-command-msgs - # - nao-sensor-msgs - # - nav2-bringup - # - nav2-gazebo-spawner - # - nmea-msgs - # - nodl-python - # - ntpd-driver - # - osqp-vendor - # - ouster-msgs - # - pcl-ros - # - perception-pcl - # - phidgets-msgs - # - plansys2-core - # - plansys2-lifecycle-manager - # - plansys2-msgs - # - plansys2-pddl-parser - # - plotjuggler-msgs - # - point-cloud-msg-wrapper - # - qpoases-vendor - # - qt-gui-app - # - qt-gui-core - # - quaternion-operation - # - radar-msgs - # - rc-common-msgs - # - rcdiscover - # - rc-genicam-api - # - rclc - # - rclc-examples - # - rclc-lifecycle - # - rclc-parameter - # - rclcpp-cascade-lifecycle - # - rcl-logging-log4cxx - # - rcl-logging-noop - # - rc-reason-clients - # - rc-reason-msgs - # - rcss3d-agent - # - realtime-tools - # - rmf-battery - # - rmf-building-map-msgs - # - rmf-building-map-tools - # - rmf-charger-msgs - # - rmf-cmake-uncrustify - # - rmf-dispenser-msgs - # - rmf-door-msgs - # - rmf-fleet-msgs - # - rmf-ingestor-msgs - # - rmf-lift-msgs - # - rmf-task-msgs - # - rmf-traffic - # - rmf-traffic-editor - # - rmf-traffic-editor-assets - # - rmf-traffic-editor-test-maps - # - rmf-traffic-msgs - # - rmf-utils - # - rmf-visualization-msgs - # - rmf-workcell-msgs - # - rmw-gurumdds-cpp - # - rmw-gurumdds-shared-cpp - # - ros2nodl - # - ros2-ouster - # - ros2trace - # - ros2trace-analysis - # - rosbag2-performance-benchmarking - # - rosidl-generator-dds-idl - # - rplidar-ros - # - run-move-group - # # - run-moveit-cpp - # - sdformat-test-files - # - self-test - # - sensor-msgs-py - # - serial-driver - # - soccer-vision-msgs - # - stereo-image-proc - # - stubborn-buddies - # - stubborn-buddies-msgs - # - system-modes - # - system-modes-examples - # - system-modes-msgs - # - teleop-tools - # - teleop-tools-msgs - # - test-apex-test-tools - # - test-bond - # - test-launch-system-modes - # - tf-transformations - # - topic-statistics-demo - # - tracetools-analysis - # - tracetools-launch - # - tracetools-read - # - tracetools-test - # - tracetools-trace - # - ublox - # - ublox-gps - # - ublox-msgs - # - ublox-serialization - # - ublox-ubx-interfaces - # - ublox-ubx-msgs - # - udp-driver - # - udp-msgs - # - urg-c - # - urg-node - # - urg-node-msgs - # - v4l2-camera - # - vision-opencv - # - wiimote-msgs - - # Don't work yet - # - run_moveit_cpp - # - wiimote - # - rc-dynamics-api - # - rosbag2-bag-v2-plugins - # this needs libdwarf and libiberty - # I think we need to build libdwarf first ... - # - osrf_testing_tools_cpp patch_dir: patch diff --git a/vinca_linux_aarch64.yaml b/vinca_linux_aarch64.yaml deleted file mode 100644 index 7a97fabb..00000000 --- a/vinca_linux_aarch64.yaml +++ /dev/null @@ -1,391 +0,0 @@ -ros_distro: humble - -# mapping for package keys -conda_index: - - robostack.yaml - - packages-ignore.yaml - -build_number: 4 - -mutex_package: ros2-distro-mutex 0.5 humble - -skip_all_deps: false - -# If full rebuild, the build number of the existing package has -# to match the selected build number for skipping -full_rebuild: true - -packages_skip_by_deps: - # - nav2-rotation-shim-controller - # - rviz - # - diagnostic_updater - - cartographer - - octomap - -packages_remove_from_deps: - - cartographer - - warehouse_ros_mongo - - octomap - # - stage-ros - # - python_qt_binding - # - joint_state_publisher_gui - # - stage - -skip_existing: - - https://conda.anaconda.org/robostack-staging/ - # - /home/ubuntu/micromamba/envs/devenv/conda-bld/ - -packages_select_by_deps: - # only subset of packages to reduce maintainer load - - ros2-controllers - - diff-drive-controller - - libcamera - - ros_workspace - - ros_environment - - ament_cmake - - ros_base - - desktop - - desktop_full - - rosbag2_storage_mcap - - cartographer-ros - - foxglove_bridge - - - gazebo_msgs - - gazebo_dev - - gazebo_ros - - gazebo_plugins - - gazebo_ros2_control - - gazebo_ros_pkgs - - - ackermann-msgs - - velodyne - - geodesy - - geographic_info - - tf-transformations - - robot_localization - - - rosbridge_suite - - vision-msgs - - slam-toolbox - - - ros2_control - - vision-msgs-rviz-plugins - - - navigation2 - - rviz2 - - behaviortree_cpp_v3 - - ament_cmake_catch2 - - - apriltag - - apriltag_ros - - # - moveit - # - moveit_servo - - # - control_toolbox - # - ros1_bridge - - # ros2_control - - gazebo-ros2-control - - # Modern gz-sim integration - - ros-gz - - # Used to work, now needs fixes - # - rtabmap - # - webots-ros2 - # - webots-ros2-abb - # - webots-ros2-core - # - webots-ros2-demos - # - webots-ros2-epuck - # - webots-ros2-examples - # - webots-ros2-importer - # - webots-ros2-msgs - # - webots-ros2-tesla - # - webots-ros2-tiago - # - webots-ros2-turtlebot - # - webots-ros2-tutorials - # - webots-ros2-universal-robot - # - webots-ros2-ur-e-description - # - webots_ros2 - - # needs a rebuild of ros-noetic first - # - ros1-rosbag-storage-vendor - - # build locally but not on CI; for now uploaded from local - # - popf - # - ros-ign-bridge - # - ros-ign-image - - # working - # - sbg_driver - # - ruckig - # - rosbridge-msgs - # - rosbridge-library - # - joint-state-broadcaster - # - joint-state-publisher - # - joint-trajectory-controller - # - xacro - # - ros2launch-security - # - picknik-ament-copyright - # - nodl-to-policy - # - geometry-tutorials - # - sdformat-urdf - # - cartographer-ros - # - plansys2-bt-actions - # - plansys2-terminal - # - nav2-system-tests - # - lanelet2 - # - plansys2-bringup - # - octovis - # - gps-umd - # - usb-cam - # - tvm-vendor - # - ros2-socketcan - # - mrpt2 - # - ublox-dgnss - # - fmi-adapter-examples - # - spacenav - # - ros-ign - # - menge-vendor - # - openvslam - # - four-wheel-steering-msgs - # - ign-rviz - # - ign-rviz-common - # - ign-rviz-plugins - # - image-pipeline - # - image-view - # - libphidget22 - # - nao-lola - # - phidgets-accelerometer - # - phidgets-analog-inputs - # - phidgets-api - # - phidgets-digital-inputs - # - phidgets-digital-outputs - # - phidgets-drivers - # - phidgets-gyroscope - # - phidgets-high-speed-encoder - # - phidgets-ik - # - phidgets-magnetometer - # - phidgets-motors - # - phidgets-spatial - # - phidgets-temperature - # - robot-localization - # - ros-ign-bridge - # - ros-ign-gazebo - # - ros-ign-image - # - ros-ign-interfaces - # - soccer-marker-generation - # - plotjuggler-ros - # - plotjuggler - # - acado-vendor - # - ament-clang-format - # - ament-clang-tidy - # - ament-cmake-catch2 - # - ament-cmake-clang-format - # - ament-cmake-clang-tidy - # - ament-cmake-mypy - # - ament-cmake-nose - # - ament-cmake-pclint - # - ament-cmake-pycodestyle - # - ament-cmake-pyflakes - # - ament-nodl - # - ament-pclint - # - ament-pycodestyle - # - ament-pyflakes - # - apex-containers - # - apex-test-tools - # - apriltag - # - async-web-server-cpp - # - autoware-auto-msgs - # - backward-ros - # - bno055 - # - bond-core - # - camera-calibration - # - camera-calibration-parsers - # - camera-info-manager - # - can-msgs - # - cartographer-ros-msgs - # - cascade-lifecycle-msgs - # - color-names - # - compressed-depth-image-transport - # - compressed-image-transport - # - control-box-rst - # - control-toolbox - # - depth-image-proc - # - diagnostic-aggregator - # - diagnostic-updater - # - domain-bridge - # - dynamic-edt-3d - # - dynamixel-sdk - # - dynamixel-sdk-custom-interfaces - # - dynamixel-sdk-examples - # - examples-rclcpp-cbg-executor - # - examples-rclpy-guard-conditions - # - examples-rclpy-pointcloud-publisher - # - examples-tf2-py - # - filters - # - geographic-info - # - gps-msgs - # - gps-tools - # - grbl-msgs - # - grbl-ros - # - gurumdds-cmake-module - # - hls-lfcd-lds-driver - # - ifm3d-core - # - image-common - # - image-proc - # - image-publisher - # - image-rotate - # - joy-linux - # - joy-teleop - # - key-teleop - # - laser-proc - # - launch-system-modes - # - lgsvl-msgs - # - libmavconn - # - librealsense2 - # - marti-can-msgs - # - marti-common-msgs - # - marti-dbw-msgs - # - marti-nav-msgs - # - marti-perception-msgs - # - marti-sensor-msgs - # - marti-status-msgs - # - marti-visualization-msgs - # - mavlink - # - mavros - # - mavros-msgs - # - mouse-teleop - # - moveit-resources - # - moveit-ros-perception - # - moveit-runtime - # - moveit-servo - # - nao-button-sim - # - nao-command-msgs - # - nao-sensor-msgs - # - nav2-bringup - # - nav2-gazebo-spawner - # - nmea-msgs - # - nodl-python - # - ntpd-driver - # - osqp-vendor - # - ouster-msgs - # - pcl-ros - # - perception-pcl - # - phidgets-msgs - # - plansys2-core - # - plansys2-lifecycle-manager - # - plansys2-msgs - # - plansys2-pddl-parser - # - plotjuggler-msgs - # - point-cloud-msg-wrapper - # - qpoases-vendor - # - qt-gui-app - # - qt-gui-core - # - quaternion-operation - # - radar-msgs - # - rc-common-msgs - # - rcdiscover - # - rc-genicam-api - # - rclc - # - rclc-examples - # - rclc-lifecycle - # - rclc-parameter - # - rclcpp-cascade-lifecycle - # - rcl-logging-log4cxx - # - rcl-logging-noop - # - rc-reason-clients - # - rc-reason-msgs - # - rcss3d-agent - # - realsense2-camera - # - realsense2-camera-msgs - # - realsense2-description - # - realtime-tools - # - rmf-battery - # - rmf-building-map-msgs - # - rmf-building-map-tools - # - rmf-charger-msgs - # - rmf-cmake-uncrustify - # - rmf-dispenser-msgs - # - rmf-door-msgs - # - rmf-fleet-msgs - # - rmf-ingestor-msgs - # - rmf-lift-msgs - # - rmf-task-msgs - # - rmf-traffic - # - rmf-traffic-editor - # - rmf-traffic-editor-assets - # - rmf-traffic-editor-test-maps - # - rmf-traffic-msgs - # - rmf-utils - # - rmf-visualization-msgs - # - rmf-workcell-msgs - # - rmw-gurumdds-cpp - # - rmw-gurumdds-shared-cpp - # - ros2nodl - # - ros2-ouster - # - ros2trace - # - ros2trace-analysis - # - rosbag2-performance-benchmarking - # - rosidl-generator-dds-idl - # - rplidar-ros - # - rqt - # - rqt-moveit - # - rqt-robot-dashboard - # - rqt-robot-monitor - # - rqt-robot-steering - # - run-move-group - # # - run-moveit-cpp - # - sdformat-test-files - # - self-test - # - sensor-msgs-py - # - serial-driver - # - soccer-vision-msgs - # - stereo-image-proc - # - stubborn-buddies - # - stubborn-buddies-msgs - # - system-modes - # - system-modes-examples - # - system-modes-msgs - # - teleop-tools - # - teleop-tools-msgs - # - test-apex-test-tools - # - test-bond - # - test-launch-system-modes - # - topic-statistics-demo - # - tracetools-analysis - # - tracetools-launch - # - tracetools-read - # - tracetools-test - # - tracetools-trace - # - turtlebot3-fake-node - # - turtlebot3-gazebo - # - turtlebot3-msgs - # - turtlebot3-simulations - # - ublox - # - ublox-gps - # - ublox-msgs - # - ublox-serialization - # - ublox-ubx-interfaces - # - ublox-ubx-msgs - # - udp-driver - # - udp-msgs - # - urg-c - # - urg-node - # - urg-node-msgs - # - v4l2-camera - # - vision-opencv - # - wiimote-msgs - - # Don't work yet - # - run_moveit_cpp - # - wiimote - # - rc-dynamics-api - # - rosbag2-bag-v2-plugins - - # this needs libdwarf and libiberty - # I think we need to build libdwarf first ... - # - osrf_testing_tools_cpp - -patch_dir: patch diff --git a/vinca_osx.yaml b/vinca_osx.yaml deleted file mode 100644 index 00ad585c..00000000 --- a/vinca_osx.yaml +++ /dev/null @@ -1,104 +0,0 @@ -ros_distro: humble - -# mapping for package keys -conda_index: - - robostack.yaml - - packages-ignore.yaml - -build_number: 6 - -mutex_package: ros2-distro-mutex 0.5 humble - -skip_all_deps: false - -# If full rebuild, the build number of the existing package has -# to match the selected build number for skipping -full_rebuild: true - -# build_in_own_azure_stage: -# - ros-galactic-rviz-rendering - -packages_skip_by_deps: - # - rttest - - cartographer - - octomap - -packages_remove_from_deps: - - cartographer - - octomap - - tlsf - - tlsf_cpp - - pendulum_control - - rttest - # Not available for macOS and Windows! - - gripper_controllers - -skip_existing: - # - https://conda.anaconda.org/robostack-humble/ - - https://conda.anaconda.org/robostack-staging/ - -packages_select_by_deps: - - ros_workspace - - ros_environment - - ros_base - - desktop - - desktop_full - - navigation2 - - rosbridge_suite - - vision_msgs - - rosbag2_storage_mcap - - foxglove_bridge - - turtlebot3 - - - control_msgs - - steering-controllers-library - - ackermann-steering-controller - - admittance-controller - - forward-command-controller - - bicycle_steering_controller - - diff_drive_controller - - effort_controllers - - force_torque_sensor_broadcaster - - imu_sensor_broadcaster - - position_controllers - - - ros2_control - - ros2_controllers - - - joint-state-broadcaster - - joint-state-publisher - - joint-trajectory-controller - - joint-limits - - xacro - - robot-localization - - velodyne - - sbg_driver - - vision-opencv - - ackermann-msgs - - ament_cmake_catch2 - - - gazebo_msgs - - gazebo_dev - - gazebo_ros - - gazebo_plugins - - gazebo_ros_pkgs - - - turtlebot3_gazebo - - plotjuggler-ros - - plotjuggler - - - apriltag - - apriltag_ros - - # ros2_control - - gazebo_ros2_control - - ros2_control - - ros2_controllers - - # Modern gz-sim integration - - ros-gz - - # - moveit - # - moveit_servo - -patch_dir: patch diff --git a/vinca_osx_arm64.yaml b/vinca_osx_arm64.yaml deleted file mode 100644 index 478fbcaa..00000000 --- a/vinca_osx_arm64.yaml +++ /dev/null @@ -1,95 +0,0 @@ -ros_distro: jazzy - -# mapping for package keys -conda_index: - - robostack.yaml - - packages-ignore.yaml - -build_number: 5 - -mutex_package: ros2-distro-mutex 0.5 jazzy - -skip_all_deps: false - -# If full rebuild, the build number of the existing package has -# to match the selected build number for skipping -full_rebuild: true - -# build_in_own_azure_stage: -# - ros-galactic-rviz-rendering - -packages_skip_by_deps: - # - rttest - - cartographer - - octomap - -packages_remove_from_deps: - - cartographer - - octomap - - tlsf - - tlsf_cpp - - pendulum_control - - rttest - # Not available for macOS and Windows! - - gripper_controllers - -skip_existing: - - https://conda.anaconda.org/robostack-staging/ - # - /Users/fischert/mambaforge/envs/devenv/conda-bld/ - -packages_select_by_deps: - - ros_workspace - - ros_environment - - ros_base - - demo_nodes_py - - demo_nodes_cpp - - desktop - - graph_msgs - - desktop_full - - navigation2 - - rosbridge_suite - - vision_msgs - - rosbag2_storage_mcap - - foxglove_bridge - - turtlebot3 - - - joint-state-broadcaster - - joint-state-publisher - - joint-state-publisher-gui - - joint-trajectory-controller - - xacro - - robot-localization - - vision-opencv - - - gazebo_msgs - - gazebo_dev - - gazebo_ros - - gazebo_plugins - - gazebo_ros2_control - - gazebo_ros_pkgs - - turtlebot3_gazebo - - - plotjuggler-ros - - plotjuggler - - - ament_cmake_catch2 - - - apriltag - - apriltag_ros - - - velodyne - - sbg_driver - - ackermann-msgs - - # ros2_control - - ros2_control - - ros2_controllers - - gazebo-ros2-control - - # Modern gz-sim integration - - ros-gz - - # - moveit - - -patch_dir: patch diff --git a/vinca_win.yaml b/vinca_win.yaml deleted file mode 100644 index 1b681a71..00000000 --- a/vinca_win.yaml +++ /dev/null @@ -1,79 +0,0 @@ -ros_distro: humble - -# mapping for package keys -conda_index: - - robostack.yaml - - packages-ignore.yaml - -build_number: 7 - -mutex_package: ros2-distro-mutex 0.5 humble - -skip_all_deps: false - -# If full rebuild, the build number of the existing package has -# to match the selected build number for skipping -full_rebuild: true - -packages_skip_by_deps: - - cartographer - - octomap - - rttest - -packages_remove_from_deps: - - cartographer - - octomap - - tlsf - - tlsf_cpp - - pendulum_control - - warehouse_ros_mongo - - pilz-industrial-motion-planner - -skip_existing: - - https://conda.anaconda.org/robostack-staging/ - -packages_select_by_deps: - - ament-cmake-core - #- ros2_control - #- ros2_controllers - - backward_ros - - ros_workspace - - vision_msgs - - ros_environment - - ros_base - - rmw_cyclonedds_cpp - - xacro - - gazebo-ros - # - navigation2 - # - desktop - # - cv_bridge - # - perception - # - gazebo_msgs - # - gazebo_dev - # - gazebo_ros - # - gazebo_plugins - # - gazebo_ros2_control - # - gazebo_ros_pkgs - # - turtlebot3_simulations - # - rosbridge_suite - # - ament_cmake_catch2 - # - nav2-mppi-controller - - # ros2_control - - gazebo-ros2-control - - ros2-controllers-test-nodes - - joint-state-publisher-gui - - # PREVIOUSLY SUPPORTED PACKAGES, CURRENTLY BROKEN - # Currently has upstream issues with git LFS - # - moveit - # Broken for now until we migrate to newer gazebo - # - desktop_full - - # REQUESTED PACKAGES - # Fails due to not finding csparse, could borrow patch from mrpt2 - # - slam-toolbox - # Needs slam-toolbox - # - nav2-bringup - -patch_dir: patch