diff --git a/.github/workflows/testpr.yml b/.github/workflows/testpr.yml index 0da260d9a..7a1498359 100644 --- a/.github/workflows/testpr.yml +++ b/.github/workflows/testpr.yml @@ -7,7 +7,7 @@ env: # Change to 'true' to enable the cache upload as artifacts SAVE_CACHE_AS_ARTIFACT: 'false' # Change to 'true' to ignore cache and force a full rebuild, but please restore to 'false' before merging - IGNORE_CACHE_AND_DO_FULL_REBUILD: 'true' + IGNORE_CACHE_AND_DO_FULL_REBUILD: 'false' jobs: build: strategy: diff --git a/patch/dependencies.yaml b/patch/dependencies.yaml index de8563759..c9ec24c10 100644 --- a/patch/dependencies.yaml +++ b/patch/dependencies.yaml @@ -31,7 +31,7 @@ libcurl_vendor: add_host: ["libcurl"] add_run: ["libcurl"] intra_process_demo: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] # Depends on opencv with gui support, see https://github.com/ros2/demos/blob/8f361a1ece2daae54016959f3ea9ab2e7692ddbb/intra_process_demo/include/image_pipeline/image_view_node.hpp#L58 add_run: ["libopencv * *qt6*"] rviz_ogre_vendor: @@ -39,9 +39,9 @@ rviz_ogre_vendor: add_build: ["vcstool"] add_run: ["assimp"] pcl_conversions: - add_host: ["REQUIRE_OPENGL", "libboost-devel"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "libboost-devel"] pcl_ros: - add_host: ["REQUIRE_OPENGL", "libboost-devel"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "libboost-devel"] rviz_rendering: add_host: ["glew"] behaviortree_cpp: @@ -50,23 +50,23 @@ behaviortree_cpp: plotjuggler: add_host: ["libxcb", "${{ 'elfutils' if linux }}", "ros-jazzy-ros-workspace", "git-lfs"] embree_vendor: - add_host: ["REQUIRE_OPENGL", "libpng", "libjpeg-turbo", "openimageio", "tbb", "tbb-devel", "embree"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "libpng", "libjpeg-turbo", "openimageio", "tbb", "tbb-devel", "embree"] ign_rviz_common: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] ign_rviz: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] ign_rviz_plugins: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] image_view: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] # Depends on opencv with gui support, see https://github.com/ros-perception/image_pipeline/blob/746268fcfd21b389bc39ae60bb6345a53c838558/image_view/src/stereo_view_node.cpp#L253 add_run: ["libopencv * *qt6*"] nao_lola: add_host: ["libboost-devel"] ros_ign_gazebo: - add_host: ["ros-jazzy-std-msgs", "ros-jazzy-rclcpp", "REQUIRE_OPENGL"] + add_host: ["ros-jazzy-std-msgs", "ros-jazzy-rclcpp", "${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] ros_ign_gazebo_demos: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] rosbag2_bag_v2_plugins: add_host: ["ros-noetic-roscpp"] tvm_vendor: @@ -87,7 +87,7 @@ ros1_rosbag_storage_vendor: popf: add_host: ["perl"] rtabmap: - add_host: ["REQUIRE_OPENGL", "ceres-solver", "libdc1394", "libusb", "vtk"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "ceres-solver", "libdc1394", "libusb", "vtk"] backward_ros: # binutils is added only on linux to avoid the -liberty library not found in macos # see https://github.com/RoboStack/ros-jazzy/pull/95#issuecomment-3113166166 @@ -111,62 +111,62 @@ python_qt_binding: add_run: ["pyqt-builder"] qt_gui_cpp: add_build: ["${{ 'pyqt' if (build_platform != target_platform) }}", "${{ 'qt-main' if (build_platform != target_platform) }}"] - add_host: ["REQUIRE_OPENGL", "pyqt-builder", "pep517", "pyside2"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "pyqt-builder", "pep517", "pyside2"] add_run: ["pyqt-builder", "pep517"] rqt_gui_cpp: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] ur_moveit_config: add_host: ["ros-jazzy-rclpy"] add_run: ["ros-jazzy-rclpy"] gscam: add_host: ["glib"] dolly_ignition: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] google_benchmark_vendor: add_host: ["benchmark"] add_run: ["benchmark"] rqt_image_view: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] rqt_image_overlay_layer: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] rviz_visual_testing_framework: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] rviz2: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] plotjuggler_ros: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_framework: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_core_plugins: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_controllers: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_app_plugins: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_srdf_plugins: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_setup_assistant: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] moveit_visual_tools: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] force_torque_sensor_broadcaster: add_host: ["typeguard", "jinja2"] ros_gz_sim: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] geometric_shapes: add_host: ["octomap"] ros_image_to_qimage: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] rqt_image_overlay: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] slam_toolbox: add_build: ["${{ 'qt-main' if (build_platform != target_platform) }}"] - add_host: ["REQUIRE_OPENGL", "blas-devel"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}", "blas-devel"] vision_msgs_rviz_plugins: add_build: ["${{ 'qt-main' if (build_platform != target_platform) }}"] - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] velodyne_pointcloud: add_host: ["libboost-devel"] # TODO unvendor?! @@ -235,9 +235,9 @@ gz_ogre_next_vendor: rosx_introspection: add_host: ["rapidjson"] gz_ros2_control: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] gz_ros2_control_demos: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] octomap_ros: add_host: ["octomap"] octomap_rviz_plugins: @@ -247,7 +247,7 @@ zenoh_cpp_vendor: rmw_zenoh_cpp: add_host: ["libzenohc", "libzenohcxx"] autoware_utils_pcl: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] autoware_utils_debug: add_host: ["fmt"] image_tools: @@ -259,4 +259,4 @@ camera_calibration: livox_ros_driver2: add_host: ["livox-sdk2"] moveit2_tutorials: - add_host: ["REQUIRE_OPENGL"] + add_host: ["${{ 'libgl-devel' if linux }}", "${{ 'libopengl-devel' if linux }}"] diff --git a/patch/ros-jazzy-draco-point-cloud-transport.patch b/patch/ros-jazzy-draco-point-cloud-transport.patch deleted file mode 100644 index d1e15123d..000000000 --- a/patch/ros-jazzy-draco-point-cloud-transport.patch +++ /dev/null @@ -1,33 +0,0 @@ -diff --git a/CMakeLists.txt b/CMakeLists.txt -index f6c0bec..b9c47e3 100644 ---- a/CMakeLists.txt -+++ b/CMakeLists.txt -@@ -36,10 +36,27 @@ add_library(${PROJECT_NAME} - src/manifest.cpp - ) - --target_link_libraries(${PROJECT_NAME} ${DRACO_LIBRARIES}) - - ament_target_dependencies(${PROJECT_NAME} ${dependencies}) - -+# draco 1.5.3 dropped the DRACO_LIBRARIES variable in favor of -+# draco::draco imported target, but debian introduced DRACO_LIBRARIES -+# back, but that is not present in other distributions. For maximum -+# compatibility, we link DRACO_LIBRARIES if defined, otherwise draco::draco -+# See: -+# * https://github.com/google/draco/commit/7109fbee87c6d932cdc0ac7394bc5d485db26d44 -+# * https://sources.debian.org/patches/draco/1.5.6+dfsg-3/0004-Set-DRACO_LIBRARIES-for-backwards-compatibility.patch/ -+if(DEFINED DRACO_LIBRARIES) -+ target_link_libraries(${PROJECT_NAME} ${DRACO_LIBRARIES}) -+else() -+ target_link_libraries(${PROJECT_NAME} draco::draco) -+endif() -+ -+target_include_directories(${PROJECT_NAME} PUBLIC -+ $ -+ $ -+) -+ - install(TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib diff --git a/patch/ros-jazzy-foxglove-bridge.osx.patch b/patch/ros-jazzy-foxglove-bridge.osx.patch new file mode 100644 index 000000000..0e07fcada --- /dev/null +++ b/patch/ros-jazzy-foxglove-bridge.osx.patch @@ -0,0 +1,108 @@ +diff --git a/src/ros2_foxglove_bridge.cpp b/src/ros2_foxglove_bridge.cpp +index 978c732..4883047 100644 +--- a/src/ros2_foxglove_bridge.cpp ++++ b/src/ros2_foxglove_bridge.cpp +@@ -282,7 +282,7 @@ void FoxgloveBridge::updateAdvertisedTopics( + std::string topic(channel.topic()); + const TopicAndDatatype topicAndSchemaName = {topic, schemaName}; + if (latestTopics.find(topicAndSchemaName) == latestTopics.end()) { +- RCLCPP_INFO(this->get_logger(), "Removing channel %lu for topic \"%s\" (%s)", channel.id(), ++ RCLCPP_INFO(this->get_logger(), "Removing channel %llu for topic \"%s\" (%s)", channel.id(), + topic.c_str(), schemaName.c_str()); + channel.close(); + channelIt = _channels.erase(channelIt); +@@ -349,7 +349,7 @@ void FoxgloveBridge::updateAdvertisedTopics( + } + + const ChannelId channelId = channelResult.value().id(); +- RCLCPP_INFO(this->get_logger(), "Advertising new channel %lu for topic \"%s\"", channelId, ++ RCLCPP_INFO(this->get_logger(), "Advertising new channel %llu for topic \"%s\"", channelId, + topic.c_str()); + _channels.insert({channelId, std::move(channelResult.value())}); + } +@@ -570,14 +570,14 @@ void FoxgloveBridge::subscribeConnectionGraph(bool subscribe) { + void FoxgloveBridge::subscribe(ChannelId channelId, const foxglove::ClientMetadata& client) { + if (!client.sink_id.has_value()) { + RCLCPP_ERROR(this->get_logger(), +- "received subscribe request from client %u for channel %lu but client " ++ "received subscribe request from client %u for channel %llu but client " + "has no sink ID", + client.id, channelId); + return; + } + + RCLCPP_INFO(this->get_logger(), +- "received subscribe request for channel %lu from client %u (sink %lu)", channelId, ++ "received subscribe request for channel %llu from client %u (sink %llu)", channelId, + client.id, client.sink_id.value()); + std::lock_guard lock(_subscriptionsMutex); + +@@ -585,7 +585,7 @@ void FoxgloveBridge::subscribe(ChannelId channelId, const foxglove::ClientMetada + // calling this callback? + auto it = _channels.find(channelId); + if (it == _channels.end()) { +- RCLCPP_ERROR(this->get_logger(), "received subscribe request for unknown channel: %lu", ++ RCLCPP_ERROR(this->get_logger(), "received subscribe request for unknown channel: %llu", + channelId); + return; + } +@@ -615,7 +615,7 @@ void FoxgloveBridge::subscribe(ChannelId channelId, const foxglove::ClientMetada + + if (!client.sink_id.has_value()) { + RCLCPP_ERROR(this->get_logger(), +- "received subscribe request for channel %lu but client " ++ "received subscribe request for channel %llu but client " + "has no sink ID", + channelId); + return; +@@ -623,19 +623,19 @@ void FoxgloveBridge::subscribe(ChannelId channelId, const foxglove::ClientMetada + + _subscriptions.insert({{channelId, client.id}, subscription}); + RCLCPP_INFO(this->get_logger(), +- "created ROS subscription on %s (%s) successfully for channel %lu (client " +- "%u, sink %lu)", ++ "created ROS subscription on %s (%s) successfully for channel %llu (client " ++ "%u, sink %llu)", + topic.c_str(), datatype.c_str(), channelId, client.id, client.sink_id.value()); + } + + void FoxgloveBridge::unsubscribe(ChannelId channelId, const foxglove::ClientMetadata& client) { + std::lock_guard lock(_subscriptionsMutex); + +- RCLCPP_INFO(this->get_logger(), "received unsubscribe request for channel %lu", channelId); ++ RCLCPP_INFO(this->get_logger(), "received unsubscribe request for channel %llu", channelId); + + auto it = _channels.find(channelId); + if (it == _channels.end()) { +- RCLCPP_ERROR(this->get_logger(), "received unsubscribe request for unknown channel %lu", ++ RCLCPP_ERROR(this->get_logger(), "received unsubscribe request for unknown channel %llu", + channelId); + return; + } +@@ -643,7 +643,7 @@ void FoxgloveBridge::unsubscribe(ChannelId channelId, const foxglove::ClientMeta + auto subscriptionIt = _subscriptions.find({channelId, client.id}); + if (subscriptionIt == _subscriptions.end()) { + RCLCPP_ERROR(this->get_logger(), +- "Client %u tried unsubscribing from channel %lu but a corresponding ROS " ++ "Client %u tried unsubscribing from channel %llu but a corresponding ROS " + "subscription doesn't exist", + client.id, channelId); + return; +@@ -651,7 +651,7 @@ void FoxgloveBridge::unsubscribe(ChannelId channelId, const foxglove::ClientMeta + + const std::string& topic = subscriptionIt->second->get_topic_name(); + RCLCPP_INFO(this->get_logger(), +- "Cleaned up subscription to topic %s for client %u on channel %lu", topic.c_str(), ++ "Cleaned up subscription to topic %s for client %u on channel %llu", topic.c_str(), + client.id, channelId); + _subscriptions.erase(subscriptionIt); + } +@@ -755,7 +755,7 @@ void FoxgloveBridge::clientUnadvertise(ClientId clientId, ChannelId clientChanne + + const auto& publisher = it->second.publisher; + RCLCPP_INFO(this->get_logger(), +- "Client ID %u is no longer advertising %s (%zu subscribers) on channel %lu", clientId, ++ "Client ID %u is no longer advertising %s (%zu subscribers) on channel %llu", clientId, + publisher->get_topic_name(), publisher->get_subscription_count(), clientChannelId); + + _clientAdvertisedTopics.erase(it); diff --git a/patch/ros-jazzy-foxglove-bridge.patch b/patch/ros-jazzy-foxglove-bridge.patch new file mode 100644 index 000000000..c851aaa75 --- /dev/null +++ b/patch/ros-jazzy-foxglove-bridge.patch @@ -0,0 +1,23 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index a72a85b..9550019 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -70,6 +70,18 @@ else() + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(FOXGLOVE_SDK_PLATFORM "x86_64-unknown-linux-gnu") + set(FOXGLOVE_SDK_SHA "574c3ce006d6131d6519b416f25ef37c5b2a0721ef49c894286c79a5a5e0b4fc") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "arm64") ++ set(FOXGLOVE_SDK_PLATFORM "aarch64-apple-darwin") ++ set(FOXGLOVE_SDK_SHA "015d660ede95ad4d37f84e83e8ebbe81545f1d3c9fea4a24667baf692267f151") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") ++ set(FOXGLOVE_SDK_PLATFORM "x86_64-apple-darwin") ++ set(FOXGLOVE_SDK_SHA "07a1903013639ae872be9fcee8ccf72224a20cc142e642063a226ba2c2b54196") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Windows" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "ARM64") ++ set(FOXGLOVE_SDK_PLATFORM "aarch64-pc-windows-msvc") ++ set(FOXGLOVE_SDK_SHA "caa797bad483ee2f1013c39a8997a409a45515f15e62ead9011351f12596f57d") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Windows" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "AMD64") ++ set(FOXGLOVE_SDK_PLATFORM "x86_64-pc-windows-msvc") ++ set(FOXGLOVE_SDK_SHA "906a5658a207dfe929a6b75f39e0064efdb6182d923e695617fcfa10d311f349") + else() + message(FATAL_ERROR "Unsupported platform/architecture combination: ${CMAKE_SYSTEM_PROCESSOR}-${CMAKE_SYSTEM_NAME}") + endif() diff --git a/patch/ros-jazzy-foxglove-bridge.win.patch b/patch/ros-jazzy-foxglove-bridge.win.patch index b8c4d62ec..cc5b1603a 100644 --- a/patch/ros-jazzy-foxglove-bridge.win.patch +++ b/patch/ros-jazzy-foxglove-bridge.win.patch @@ -1,133 +1,85 @@ diff --git a/CMakeLists.txt b/CMakeLists.txt -index 715ce29..f8b43d5 100644 +index a72a85b..8b69dda 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt -@@ -14,6 +14,11 @@ project(foxglove_bridge LANGUAGES CXX VERSION 0.8.3) - set(CMAKE_CXX_STANDARD 17) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - -+if(MSVC) -+ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE) -+ set(BUILD_SHARED_LIBS TRUE) -+endif() -+ - macro(enable_strict_compiler_warnings target) - if (MSVC) - target_compile_options(${target} PRIVATE /WX /W4) -@@ -77,8 +82,9 @@ add_library(foxglove_bridge_base SHARED - ${CMAKE_CURRENT_BINARY_DIR}/foxglove_bridge_base/src/version.cpp - ) - target_include_directories(foxglove_bridge_base -- PUBLIC -+ SYSTEM PUBLIC - $ -+ $ - $ - ) - target_link_libraries(foxglove_bridge_base -@@ -92,7 +98,12 @@ if(nlohmann_json_FOUND) - else() - message(STATUS "nlohmann_json not found, will search at compile time") +@@ -70,6 +70,18 @@ else() + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(FOXGLOVE_SDK_PLATFORM "x86_64-unknown-linux-gnu") + set(FOXGLOVE_SDK_SHA "574c3ce006d6131d6519b416f25ef37c5b2a0721ef49c894286c79a5a5e0b4fc") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "arm64") ++ set(FOXGLOVE_SDK_PLATFORM "aarch64-apple-darwin") ++ set(FOXGLOVE_SDK_SHA "015d660ede95ad4d37f84e83e8ebbe81545f1d3c9fea4a24667baf692267f151") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") ++ set(FOXGLOVE_SDK_PLATFORM "x86_64-apple-darwin") ++ set(FOXGLOVE_SDK_SHA "07a1903013639ae872be9fcee8ccf72224a20cc142e642063a226ba2c2b54196") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Windows" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "ARM64") ++ set(FOXGLOVE_SDK_PLATFORM "aarch64-pc-windows-msvc") ++ set(FOXGLOVE_SDK_SHA "caa797bad483ee2f1013c39a8997a409a45515f15e62ead9011351f12596f57d") ++ elseif(CMAKE_SYSTEM_NAME STREQUAL "Windows" AND CMAKE_SYSTEM_PROCESSOR STREQUAL "AMD64") ++ set(FOXGLOVE_SDK_PLATFORM "x86_64-pc-windows-msvc") ++ set(FOXGLOVE_SDK_SHA "906a5658a207dfe929a6b75f39e0064efdb6182d923e695617fcfa10d311f349") + else() + message(FATAL_ERROR "Unsupported platform/architecture combination: ${CMAKE_SYSTEM_PROCESSOR}-${CMAKE_SYSTEM_NAME}") + endif() +@@ -91,7 +103,16 @@ else() + file(GLOB_RECURSE FOXGLOVE_SDK_SOURCES CONFIGURE_DEPENDS "${foxglove_sdk_SOURCE_DIR}/src/*.cpp") + target_sources(foxglove_cpp_static PRIVATE ${FOXGLOVE_SDK_SOURCES}) + set_target_properties(foxglove_cpp_static PROPERTIES POSITION_INDEPENDENT_CODE ON) +- target_link_libraries(foxglove_cpp_static PRIVATE ${foxglove_sdk_SOURCE_DIR}/lib/libfoxglove.a) ++ if(MSVC) ++ target_link_libraries(foxglove_cpp_static PRIVATE ++ ${foxglove_sdk_SOURCE_DIR}/lib/foxglove.lib ++ Ws2_32.lib ++ Userenv.lib ++ Ntdll.lib ++ ) ++ else() ++ target_link_libraries(foxglove_cpp_static PRIVATE ${foxglove_sdk_SOURCE_DIR}/lib/libfoxglove.a) ++ endif() endif() --enable_strict_compiler_warnings(foxglove_bridge_base) -+# enable_strict_compiler_warnings(foxglove_bridge_base) -+if(MSVC) -+ target_compile_definitions(foxglove_bridge_base PUBLIC _WEBSOCKETPP_CPP11_STL_) -+ include(GenerateExportHeader) -+ generate_export_header(foxglove_bridge_base) -+endif() - - message(STATUS "ROS_VERSION: " $ENV{ROS_VERSION}) - message(STATUS "ROS_DISTRO: " $ENV{ROS_DISTRO}) -@@ -280,6 +291,9 @@ elseif(ROS_BUILD_TYPE STREQUAL "ament_cmake") - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin - ) -+ if(MSVC) -+ install(FILES ${CMAKE_CURRENT_BINARY_DIR}/foxglove_bridge_base_export.h DESTINATION include) -+ endif() - install(DIRECTORY ros2_foxglove_bridge/launch - DESTINATION share/${PROJECT_NAME}/ - ) -diff --git a/foxglove_bridge_base/include/foxglove_bridge/foxglove_bridge.hpp b/foxglove_bridge_base/include/foxglove_bridge/foxglove_bridge.hpp -index 4b85891..6a946ee 100644 ---- a/foxglove_bridge_base/include/foxglove_bridge/foxglove_bridge.hpp -+++ b/foxglove_bridge_base/include/foxglove_bridge/foxglove_bridge.hpp -@@ -1,11 +1,13 @@ - #pragma once - -+#include -+ - namespace foxglove { - - const char* WebSocketUserAgent(); --extern const char FOXGLOVE_BRIDGE_VERSION[]; -+extern FOXGLOVE_BRIDGE_BASE_EXPORT const char FOXGLOVE_BRIDGE_VERSION[]; + find_program(GIT_SCM git DOC "Git version control") +diff --git a/src/message_definition_cache.cpp b/src/message_definition_cache.cpp +index f338db9..d766894 100644 +--- a/src/message_definition_cache.cpp ++++ b/src/message_definition_cache.cpp +@@ -225,16 +225,16 @@ const MessageSpec& MessageDefinitionCache::load_message_spec( --extern const char FOXGLOVE_BRIDGE_GIT_HASH[]; -+extern FOXGLOVE_BRIDGE_BASE_EXPORT const char FOXGLOVE_BRIDGE_GIT_HASH[]; - - } // namespace foxglove -diff --git a/ros2_foxglove_bridge/src/message_definition_cache.cpp b/ros2_foxglove_bridge/src/message_definition_cache.cpp -index 262c482..2d72a3a 100644 ---- a/ros2_foxglove_bridge/src/message_definition_cache.cpp -+++ b/ros2_foxglove_bridge/src/message_definition_cache.cpp -@@ -234,7 +234,7 @@ const MessageSpec& MessageDefinitionCache::load_message_spec( + // Find the first line that ends with the filename we're looking for + const auto lines = split_string(index_contents); +- const auto it = std::find_if(lines.begin(), lines.end(), [&filename](const std::string& line) { ++ const auto line_it = std::find_if(lines.begin(), lines.end(), [&filename](const std::string& line) { + std::filesystem::path filePath(line); + return filePath.filename() == filename; + }); +- if (it == lines.end()) { ++ if (line_it == lines.end()) { + throw DefinitionNotFoundError(definition_identifier.package_resource_name); } // Read the file - const std::string full_path = share_dir + std::filesystem::path::preferred_separator + *it; -+ const std::string full_path = share_dir + std::string(1, std::filesystem::path::preferred_separator) + *it; ++ const std::filesystem::path full_path = std::filesystem::path(share_dir) / *line_it; std::ifstream file{full_path}; if (!file.good()) { throw DefinitionNotFoundError(definition_identifier.package_resource_name); -@@ -283,11 +283,11 @@ const MessageSpec& MessageDefinitionCache::load_message_spec( - } - - // Find the the subtype that was originally requested and return it. -- const auto it = msg_specs_by_definition_identifier_.find(definition_identifier); -- if (it == msg_specs_by_definition_identifier_.end()) { -+ const auto it_action = msg_specs_by_definition_identifier_.find(definition_identifier); -+ if (it_action == msg_specs_by_definition_identifier_.end()) { - throw DefinitionNotFoundError(definition_identifier.package_resource_name); - } -- return it->second; -+ return it_action->second; - } else if (subfolder == "srv") { - if (definition_identifier.format == MessageDefinitionFormat::IDL) { - RCUTILS_LOG_ERROR_NAMED("foxglove_bridge", -@@ -319,11 +319,11 @@ const MessageSpec& MessageDefinitionCache::load_message_spec( - } +@@ -376,8 +376,8 @@ std::pair MessageDefinitionCache::g + result = delimiter(root_definition_identifier) + append_recursive(root_definition_identifier); + } - // Find the the subtype that was originally requested and return it. -- const auto it = msg_specs_by_definition_identifier_.find(definition_identifier); -- if (it == msg_specs_by_definition_identifier_.end()) { -+ const auto it_srv = msg_specs_by_definition_identifier_.find(definition_identifier); -+ if (it_srv == msg_specs_by_definition_identifier_.end()) { - throw DefinitionNotFoundError(definition_identifier.package_resource_name); - } -- return it->second; -+ return it_srv->second; - } else { - // Normal message type. - const MessageSpec& spec = -diff --git a/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp b/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp -index 0143674..d6876e3 100644 ---- a/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp -+++ b/ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp -@@ -20,7 +20,14 @@ using foxglove::isWhitelisted; +- auto [it, _] = full_text_cache_.emplace(root_package_resource_name, result); +- return {format, it->second}; ++ auto [cache_it, _] = full_text_cache_.emplace(root_package_resource_name, result); ++ return {format, cache_it->second}; + } - FoxgloveBridge::FoxgloveBridge(const rclcpp::NodeOptions& options) - : Node("foxglove_bridge", options) { -+#if defined(_MSC_VER) -+ char* rosDistro; -+ std::size_t size; -+ _dupenv_s(&rosDistro, &size, "ROS_DISTRO"); -+ std::unique_ptr release(rosDistro, &free); -+#else - const char* rosDistro = std::getenv("ROS_DISTRO"); -+#endif - RCLCPP_INFO(this->get_logger(), "Starting foxglove_bridge (%s, %s@%s) with %s", rosDistro, - foxglove::FOXGLOVE_BRIDGE_VERSION, foxglove::FOXGLOVE_BRIDGE_GIT_HASH, - foxglove::WebSocketUserAgent()); + } // namespace foxglove_bridge +diff --git a/src/ros2_foxglove_bridge.cpp b/src/ros2_foxglove_bridge.cpp +index 978c732..83dce52 100644 +--- a/src/ros2_foxglove_bridge.cpp ++++ b/src/ros2_foxglove_bridge.cpp +@@ -1,3 +1,4 @@ ++#define _CRT_SECURE_NO_WARNINGS + #include + #include + #include diff --git a/patch/ros-jazzy-ros2-control-cmake.patch b/patch/ros-jazzy-ros2-control-cmake.patch index f958b1a59..cbf35c6aa 100644 --- a/patch/ros-jazzy-ros2-control-cmake.patch +++ b/patch/ros-jazzy-ros2-control-cmake.patch @@ -1,24 +1,44 @@ -diff --git a/ros2_control_cmake/cmake/ros2_control.cmake b/ros2_control_cmake/cmake/ros2_control.cmake -index 9d74527..c267128 100644 ---- a/ros2_control_cmake/cmake/ros2_control.cmake -+++ b/ros2_control_cmake/cmake/ros2_control.cmake -@@ -34,10 +34,10 @@ endmacro() +diff --git a/cmake/ros2_control.cmake b/cmake/ros2_control.cmake +index 4f9f757..6269a9b 100644 +--- a/cmake/ros2_control.cmake ++++ b/cmake/ros2_control.cmake +@@ -34,20 +34,20 @@ endmacro() # set compiler options depending on detected compiler macro(set_compiler_options) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") -- add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable -- -Werror=return-type -Werror=shadow -Werror=format -- -Werror=missing-braces) +- add_compile_options( +- -Wall -Wextra -Wpedantic +- -Wshadow -Wconversion -Wold-style-cast +- -Werror=conversion +- -Werror=format +- -Werror=missing-braces +- -Werror=overflow +- -Werror=return-type +- -Werror=shadow +- -Werror=sign-compare +- -Werror=unused-but-set-variable +- -Werror=unused-variable +- ) - message(STATUS "Compiler warnings enabled for ${CMAKE_CXX_COMPILER_ID}") -+ # add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable -+ # -Werror=return-type -Werror=shadow -Werror=format -+ # -Werror=missing-braces) ++ # add_compile_options( ++ # -Wall -Wextra -Wpedantic ++ # -Wshadow -Wconversion -Wold-style-cast ++ # -Werror=conversion ++ # -Werror=format ++ # -Werror=missing-braces ++ # -Werror=overflow ++ # -Werror=return-type ++ # -Werror=shadow ++ # -Werror=sign-compare ++ # -Werror=unused-but-set-variable ++ # -Werror=unused-variable ++ # ) + # message(STATUS "Compiler warnings enabled for ${CMAKE_CXX_COMPILER_ID}") # https://docs.ros.org/en/rolling/How-To-Guides/Ament-CMake-Documentation.html#compiler-and-linker-options if(NOT CMAKE_C_STANDARD) -@@ -48,13 +48,13 @@ macro(set_compiler_options) - endif() +@@ -60,13 +60,13 @@ macro(set_compiler_options) + set(CMAKE_CXX_STANDARD_REQUIRED ON) # Extract major version if g++ is used - if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") @@ -35,6 +55,6 @@ index 9d74527..c267128 100644 + # add_compile_options(-Werror=range-loop-construct) + # endif() + # endif() - endif() - endmacro() + if(CMAKE_CXX_COMPILER_ID MATCHES "(Clang)") + add_compile_options( diff --git a/patch/ros-jazzy-sbg-driver.patch b/patch/ros-jazzy-sbg-driver.patch new file mode 100644 index 000000000..0d8710025 --- /dev/null +++ b/patch/ros-jazzy-sbg-driver.patch @@ -0,0 +1,35 @@ +diff --git a/include/sbg_driver/sbg_vector3.h b/include/sbg_driver/sbg_vector3.h +index 0bc5b80..0b1b02c 100644 +--- a/include/sbg_driver/sbg_vector3.h ++++ b/include/sbg_driver/sbg_vector3.h +@@ -115,7 +115,7 @@ public: + * \param[in] p_raw_data Pointer to data array. + * \param[in] array_size Array size (Should be defined as 3). + */ +- SbgVector3(const T* p_raw_data, size_t array_size) ++ SbgVector3(const T* p_raw_data, [[maybe_unused]] size_t array_size) + { + assert(array_size == 3); + +diff --git a/src/sbg_device.cpp b/src/sbg_device.cpp +index 820322e..b802365 100644 +--- a/src/sbg_device.cpp ++++ b/src/sbg_device.cpp +@@ -5,6 +5,8 @@ + #include + #include + #include ++#include ++#include + + // SbgECom headers + #include +@@ -118,7 +120,7 @@ void SbgDevice::onLogReceived(SbgEComClass msg_class, SbgEComMsgId msg, const Sb + log_replay_last_timestamp_ = timestamp; + } + +- usleep(time_to_sleep); ++ std::this_thread::sleep_for(std::chrono::microseconds(time_to_sleep)); + } + + // diff --git a/pixi.lock b/pixi.lock index 66b764ca0..669ecfddc 100644 --- a/pixi.lock +++ b/pixi.lock @@ -117,11 +117,13 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-64/yaml-0.2.5-h280c20c_3.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/zstandard-0.25.0-py312h5253ce2_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-64/zstd-1.5.7-hb8e6e7a_2.conda + - pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/66/dd/f95350e853a4468ec37478414fc04ae2d61dad7a947b3015c3dcc51a09b9/docutils-0.22.2-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3b/95/88ed47cb7da88569a78b7d6fb9420298df7e99997810c844a924d96d3c08/empy-3.3.4.tar.gz - pypi: https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3c/2e/8d0c2ab90a8c1d9a24f0399058ab8519a3279d1bd4289511d74e909f060e/markupsafe-3.0.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl - pypi: https://files.pythonhosted.org/packages/eb/8d/776adee7bbf76365fdd7f2552710282c79a4ead5d2a46408c9043a2b70ba/networkx-3.5-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl @@ -130,7 +132,7 @@ environments: - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/df/99/65080c863eb06d4498de3d6c86f3e90595e02e159fd8529f1565f56cfe2c/ruamel.yaml.clib-0.2.14-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl - - pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 + - pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 linux-aarch64: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-cli-base-0.5.3-pyhd8ed1ab_0.conda @@ -241,11 +243,13 @@ environments: - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/yaml-0.2.5-h80f16a2_3.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/zstandard-0.25.0-py312hd41f8a7_0.conda - conda: https://repo.prefix.dev/conda-forge/linux-aarch64/zstd-1.5.7-hbcf94c1_2.conda + - pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/66/dd/f95350e853a4468ec37478414fc04ae2d61dad7a947b3015c3dcc51a09b9/docutils-0.22.2-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3b/95/88ed47cb7da88569a78b7d6fb9420298df7e99997810c844a924d96d3c08/empy-3.3.4.tar.gz - pypi: https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/1e/2c/799f4742efc39633a1b54a92eec4082e4f815314869865d876824c257c1e/markupsafe-3.0.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl - pypi: https://files.pythonhosted.org/packages/eb/8d/776adee7bbf76365fdd7f2552710282c79a4ead5d2a46408c9043a2b70ba/networkx-3.5-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl @@ -254,7 +258,7 @@ environments: - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/2b/c5/346c7094344a60419764b4b1334d9e0285031c961176ff88ffb652405b0c/ruamel.yaml.clib-0.2.14-cp312-cp312-manylinux2014_aarch64.whl - - pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 + - pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 osx-64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-cli-base-0.5.3-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.13.0-pyh29332c3_1.conda @@ -354,11 +358,13 @@ environments: - conda: https://repo.prefix.dev/conda-forge/osx-64/yaml-0.2.5-h4132b18_3.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/zstandard-0.25.0-py312h01f6755_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-64/zstd-1.5.7-h8210216_2.conda + - pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/66/dd/f95350e853a4468ec37478414fc04ae2d61dad7a947b3015c3dcc51a09b9/docutils-0.22.2-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3b/95/88ed47cb7da88569a78b7d6fb9420298df7e99997810c844a924d96d3c08/empy-3.3.4.tar.gz - pypi: https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/5a/72/147da192e38635ada20e0a2e1a51cf8823d2119ce8883f7053879c2199b5/markupsafe-3.0.3-cp312-cp312-macosx_10_13_x86_64.whl - pypi: https://files.pythonhosted.org/packages/eb/8d/776adee7bbf76365fdd7f2552710282c79a4ead5d2a46408c9043a2b70ba/networkx-3.5-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl @@ -367,7 +373,7 @@ environments: - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/b4/42/ccfb34a25289afbbc42017e4d3d4288e61d35b2e00cfc6b92974a6a1f94b/ruamel.yaml.clib-0.2.14-cp312-cp312-macosx_10_13_universal2.whl - - pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 + - pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 osx-arm64: - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-cli-base-0.5.3-pyhd8ed1ab_0.conda - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-client-1.13.0-pyh29332c3_1.conda @@ -468,11 +474,13 @@ environments: - conda: https://repo.prefix.dev/conda-forge/osx-arm64/yaml-0.2.5-h925e9cb_3.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/zstandard-0.25.0-py312h37e1c23_0.conda - conda: https://repo.prefix.dev/conda-forge/osx-arm64/zstd-1.5.7-h6491c7d_2.conda + - pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/66/dd/f95350e853a4468ec37478414fc04ae2d61dad7a947b3015c3dcc51a09b9/docutils-0.22.2-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3b/95/88ed47cb7da88569a78b7d6fb9420298df7e99997810c844a924d96d3c08/empy-3.3.4.tar.gz - pypi: https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/9a/81/7e4e08678a1f98521201c3079f77db69fb552acd56067661f8c2f534a718/markupsafe-3.0.3-cp312-cp312-macosx_11_0_arm64.whl - pypi: https://files.pythonhosted.org/packages/eb/8d/776adee7bbf76365fdd7f2552710282c79a4ead5d2a46408c9043a2b70ba/networkx-3.5-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl @@ -481,7 +489,7 @@ environments: - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/b4/42/ccfb34a25289afbbc42017e4d3d4288e61d35b2e00cfc6b92974a6a1f94b/ruamel.yaml.clib-0.2.14-cp312-cp312-macosx_10_13_universal2.whl - - pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 + - pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 win-64: - conda: https://repo.prefix.dev/conda-forge/win-64/_openmp_mutex-4.5-2_gnu.conda - conda: https://repo.prefix.dev/conda-forge/noarch/anaconda-cli-base-0.5.3-pyhd8ed1ab_0.conda @@ -588,11 +596,13 @@ environments: - conda: https://repo.prefix.dev/conda-forge/win-64/yaml-0.2.5-h6a83c73_3.conda - conda: https://repo.prefix.dev/conda-forge/win-64/zstandard-0.25.0-py312he5662c2_0.conda - conda: https://repo.prefix.dev/conda-forge/win-64/zstd-1.5.7-hbeecb71_2.conda + - pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/66/dd/f95350e853a4468ec37478414fc04ae2d61dad7a947b3015c3dcc51a09b9/docutils-0.22.2-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/3b/95/88ed47cb7da88569a78b7d6fb9420298df7e99997810c844a924d96d3c08/empy-3.3.4.tar.gz - pypi: https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl + - pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/aa/5b/bec5aa9bbbb2c946ca2733ef9c4ca91c91b6a24580193e891b5f7dbe8e1e/markupsafe-3.0.3-cp312-cp312-win_amd64.whl - pypi: https://files.pythonhosted.org/packages/eb/8d/776adee7bbf76365fdd7f2552710282c79a4ead5d2a46408c9043a2b70ba/networkx-3.5-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl @@ -601,7 +611,7 @@ environments: - pypi: https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/35/79/5e2cffa1c77432f11cd93a5351f30732c997a239d3a3090856a72d6d8ba7/ruamel.yaml-0.17.40-py3-none-any.whl - pypi: https://files.pythonhosted.org/packages/76/ab/5121f7f3b651db93de546f8c982c241397aad0a4765d793aca1dac5eadee/ruamel.yaml.clib-0.2.14-cp312-cp312-win_amd64.whl - - pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 + - pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 packages: - conda: https://repo.prefix.dev/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 sha256: fe51de6107f9edc7aa4f786a70f4a883943bc9d39b3bb7307c04c41410990726 @@ -722,6 +732,22 @@ packages: - pkg:pypi/attrs?source=hash-mapping size: 57181 timestamp: 1741918625732 +- pypi: https://files.pythonhosted.org/packages/e5/ca/78d423b324b8d77900030fa59c4aa9054261ef0925631cd2501dd015b7b7/boolean_py-5.0-py3-none-any.whl + name: boolean-py + version: '5.0' + sha256: ef28a70bd43115208441b53a045d1549e2f0ec6e3d08a9d142cbc41c1938e8d9 + requires_dist: + - pytest>=6,!=7.0.0 ; extra == 'testing' + - pytest-xdist>=2 ; extra == 'testing' + - twine ; extra == 'dev' + - build ; extra == 'dev' + - black ; extra == 'linting' + - isort ; extra == 'linting' + - pycodestyle ; extra == 'linting' + - sphinx>=3.3.1 ; extra == 'docs' + - sphinx-rtd-theme>=0.5.0 ; extra == 'docs' + - doc8>=0.8.1 ; extra == 'docs' + - sphinxcontrib-apidoc>=0.3.0 ; extra == 'docs' - conda: https://repo.prefix.dev/conda-forge/linux-64/brotli-python-1.1.0-py312h1289d80_4.conda sha256: 52a9ac412512b418ecdb364ba21c0f3dc96f0abbdb356b3cfbb980020b663d9b md5: fd0e7746ed0676f008daacb706ce69e4 @@ -2955,6 +2981,25 @@ packages: purls: [] size: 55476 timestamp: 1727963768015 +- pypi: https://files.pythonhosted.org/packages/af/40/791891d4c0c4dab4c5e187c17261cedc26285fd41541577f900470a45a4d/license_expression-30.4.4-py3-none-any.whl + name: license-expression + version: 30.4.4 + sha256: 421788fdcadb41f049d2dc934ce666626265aeccefddd25e162a26f23bcbf8a4 + requires_dist: + - boolean-py>=4.0 + - pytest>=7.0.1 ; extra == 'dev' + - pytest-xdist>=2 ; extra == 'dev' + - twine ; extra == 'dev' + - ruff ; extra == 'dev' + - sphinx>=5.0.2 ; extra == 'dev' + - sphinx-rtd-theme>=1.0.0 ; extra == 'dev' + - sphinxcontrib-apidoc>=0.4.0 ; extra == 'dev' + - sphinx-reredirects>=0.1.2 ; extra == 'dev' + - doc8>=0.11.2 ; extra == 'dev' + - sphinx-autobuild ; extra == 'dev' + - sphinx-rtd-dark-mode>=1.3.0 ; extra == 'dev' + - sphinx-copybutton ; extra == 'dev' + requires_python: '>=3.9' - conda: https://repo.prefix.dev/conda-forge/win-64/m2-conda-epoch-20250515-0_x86_64.conda build_number: 0 sha256: 51e9214548f177db9c3fe70424e3774c95bf19cd69e0e56e83abe2e393228ba1 @@ -4531,19 +4576,20 @@ packages: purls: [] size: 113963 timestamp: 1753739198723 -- pypi: git+https://github.com/RoboStack/vinca.git?rev=84494ae511217e1c8267b4d0d458969a53d588f6#84494ae511217e1c8267b4d0d458969a53d588f6 +- pypi: git+https://github.com/RoboStack/vinca.git?rev=38e639a0bb390d99f58cde09a0d772d1d855fb29#38e639a0bb390d99f58cde09a0d772d1d855fb29 name: vinca - version: 0.1.0 + version: 0.2.0 requires_dist: - catkin-pkg>=0.4.16 - - ruamel-yaml>=0.16.6,<0.18.0 - - rosdistro>=0.8.0 - empy>=3.3.4,<4.0.0 - - requests>=2.24.0 + - jinja2>=3.0.0 + - license-expression>=30.0.0 - networkx>=2.5 + - requests>=2.24.0 - rich>=10 - - jinja2>=3.0.0 - requires_python: '>=3.6' + - rosdistro>=0.8.0 + - ruamel-yaml>=0.16.6,<0.18.0 + requires_python: '>=3.9' - conda: https://repo.prefix.dev/conda-forge/noarch/win_inet_pton-1.1.0-pyh7428d3b_8.conda sha256: 93807369ab91f230cf9e6e2a237eaa812492fe00face5b38068735858fba954f md5: 46e441ba871f524e2b067929da3051c2 diff --git a/pixi.toml b/pixi.toml index bd8e48a0f..98bb65fcf 100644 --- a/pixi.toml +++ b/pixi.toml @@ -1,4 +1,4 @@ -[project] +[workspace] name = "ros-jazzy" description = "RoboStack repo to package ros-jazzy packages as conda packages" authors = ["Tobias Fischer ", "Wolf Vollprecht ", "Silvio Traversaro "] @@ -23,7 +23,7 @@ git = "*" [pypi-dependencies] # This is tipically the latest commit on main branch -vinca = { git = "https://github.com/RoboStack/vinca.git", rev = "84494ae511217e1c8267b4d0d458969a53d588f6" } +vinca = { git = "https://github.com/RoboStack/vinca.git", rev = "38e639a0bb390d99f58cde09a0d772d1d855fb29" } # Uncomment this line to work with a local vinca for faster iteration, but remember to comment it back # (and regenerate the pixi.lock) once you push the modified commit to the repo # vinca = { path = "../vinca", editable = true } diff --git a/pkg_additional_info.yaml b/pkg_additional_info.yaml index c17299148..c6960932b 100644 --- a/pkg_additional_info.yaml +++ b/pkg_additional_info.yaml @@ -145,6 +145,10 @@ rviz_ogre_vendor: # Remove once https://github.com/PickNikRobotics/data_tamer/pull/58 is merged and released data_tamer_cpp: additional_cmake_args: "-DCMAKE_WINDOWS_EXPORT_ALL_SYMBOLS=ON" +foxglove_bridge: + additional_cmake_args: "-DCMAKE_WINDOWS_EXPORT_ALL_SYMBOLS=ON" +lanelet2_projection: + additional_cmake_args: "-DCMAKE_CXX_STANDARD=17 -DCMAKE_CXX_STANDARD_REQUIRED=ON -DCMAKE_CXX_EXTENSIONS=OFF" +lanelet2_python: + additional_cmake_args: "-DCMAKE_CXX_STANDARD=17 -DCMAKE_CXX_STANDARD_REQUIRED=ON -DCMAKE_CXX_EXTENSIONS=OFF" # Everything after this comment needs to be removed on next full rebuild -point_cloud_transport: - build_number: 11 diff --git a/rosdistro_snapshot.yaml b/rosdistro_snapshot.yaml index 288aa0706..68491202b 100644 --- a/rosdistro_snapshot.yaml +++ b/rosdistro_snapshot.yaml @@ -1,4 +1,4 @@ -# Snapshot generated by vinca-snapshot on 2025-09-27T03:14:56Z UTC for distro jazzy +# Snapshot generated by vinca-snapshot on 2025-10-28T14:38:47Z UTC for distro jazzy acado_vendor: tag: release/jazzy/acado_vendor/1.0.0-7 url: https://github.com/ros2-gbp/acado_vendor-release.git @@ -16,9 +16,9 @@ ackermann_nlmpc_msgs: url: https://github.com/ros2-gbp/ackmerann_nlmpc-release.git version: 1.0.3 ackermann_steering_controller: - tag: release/jazzy/ackermann_steering_controller/4.32.0-1 + tag: release/jazzy/ackermann_steering_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 action_msgs: tag: release/jazzy/action_msgs/2.0.3-1 url: https://github.com/ros2-gbp/rcl_interfaces-release.git @@ -48,9 +48,9 @@ adaptive_component: url: https://github.com/ros2-gbp/adaptive_component-release.git version: 0.2.1 admittance_controller: - tag: release/jazzy/admittance_controller/4.32.0-1 + tag: release/jazzy/admittance_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 ads_vendor: tag: release/jazzy/ads_vendor/1.0.2-1 url: https://github.com/b-robotized/ads_vendor-release.git @@ -599,6 +599,14 @@ battery_state_rviz_overlay: tag: release/jazzy/battery_state_rviz_overlay/1.0.2-1 url: https://github.com/ros2-gbp/ros_battery_monitoring-release.git version: 1.0.2 +beckhoff_ads_bringup: + tag: release/jazzy/beckhoff_ads_bringup/1.0.0-1 + url: https://github.com/b-robotized/beckhoff_ads_driver-release.git + version: 1.0.0 +beckhoff_ads_hardware_interface: + tag: release/jazzy/beckhoff_ads_hardware_interface/1.0.0-1 + url: https://github.com/b-robotized/beckhoff_ads_driver-release.git + version: 1.0.0 behaviortree_cpp: tag: release/jazzy/behaviortree_cpp/4.7.1-1 url: https://github.com/ros2-gbp/behaviortree_cpp_v4-release.git @@ -620,9 +628,9 @@ beluga_ros: url: https://github.com/ros2-gbp/beluga-release.git version: 2.0.2 bicycle_steering_controller: - tag: release/jazzy/bicycle_steering_controller/4.32.0-1 + tag: release/jazzy/bicycle_steering_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 bno055: tag: release/jazzy/bno055/0.5.0-3 url: https://github.com/ros2-gbp/bno055-release.git @@ -684,9 +692,9 @@ camera_info_manager_py: url: https://github.com/ros2-gbp/image_common-release.git version: 5.1.7 camera_ros: - tag: release/jazzy/camera_ros/0.5.0-1 + tag: release/jazzy/camera_ros/0.5.1-1 url: https://github.com/ros2-gbp/camera_ros-release.git - version: 0.5.0 + version: 0.5.1 can_msgs: tag: release/jazzy/can_msgs/2.0.0-6 url: https://github.com/ros2-gbp/ros_canopen-release.git @@ -776,9 +784,9 @@ catch_ros2: url: https://github.com/ros2-gbp/catch_ros2-release.git version: 0.2.2 chained_filter_controller: - tag: release/jazzy/chained_filter_controller/4.32.0-1 + tag: release/jazzy/chained_filter_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 chomp_motion_planner: tag: release/jazzy/chomp_motion_planner/2.12.3-1 url: https://github.com/ros2-gbp/moveit2-release.git @@ -792,45 +800,45 @@ classic_bags: url: https://github.com/ros2-gbp/classic_bags-release.git version: 0.4.0 clearpath_bt_joy: - tag: release/jazzy/clearpath_bt_joy/2.7.4-1 + tag: release/jazzy/clearpath_bt_joy/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_common: - tag: release/jazzy/clearpath_common/2.7.4-1 + tag: release/jazzy/clearpath_common/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_config: - tag: release/jazzy/clearpath_config/2.7.3-1 + tag: release/jazzy/clearpath_config/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_config-release.git - version: 2.7.3 + version: 2.8.0 clearpath_config_live: tag: release/jazzy/clearpath_config_live/2.7.0-2 url: https://github.com/clearpath-gbp/clearpath_desktop-release.git version: 2.7.0 clearpath_control: - tag: release/jazzy/clearpath_control/2.7.4-1 + tag: release/jazzy/clearpath_control/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_customization: - tag: release/jazzy/clearpath_customization/2.7.4-1 + tag: release/jazzy/clearpath_customization/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_description: - tag: release/jazzy/clearpath_description/2.7.4-1 + tag: release/jazzy/clearpath_description/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_desktop: tag: release/jazzy/clearpath_desktop/2.7.0-2 url: https://github.com/clearpath-gbp/clearpath_desktop-release.git version: 2.7.0 clearpath_diagnostics: - tag: release/jazzy/clearpath_diagnostics/2.7.4-1 + tag: release/jazzy/clearpath_diagnostics/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_generator_common: - tag: release/jazzy/clearpath_generator_common/2.7.4-1 + tag: release/jazzy/clearpath_generator_common/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_generator_gz: tag: release/jazzy/clearpath_generator_gz/2.7.0-1 url: https://github.com/clearpath-gbp/clearpath_simulator-release.git @@ -840,21 +848,21 @@ clearpath_gz: url: https://github.com/clearpath-gbp/clearpath_simulator-release.git version: 2.7.0 clearpath_manipulators: - tag: release/jazzy/clearpath_manipulators/2.7.4-1 + tag: release/jazzy/clearpath_manipulators/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_manipulators_description: - tag: release/jazzy/clearpath_manipulators_description/2.7.4-1 + tag: release/jazzy/clearpath_manipulators_description/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_motor_msgs: tag: release/jazzy/clearpath_motor_msgs/2.7.0-1 url: https://github.com/clearpath-gbp/clearpath_msgs-release.git version: 2.7.0 clearpath_mounts_description: - tag: release/jazzy/clearpath_mounts_description/2.7.4-1 + tag: release/jazzy/clearpath_mounts_description/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_msgs: tag: release/jazzy/clearpath_msgs/2.7.0-1 url: https://github.com/clearpath-gbp/clearpath_msgs-release.git @@ -868,9 +876,9 @@ clearpath_offboard_sensors: url: https://github.com/clearpath-gbp/clearpath_desktop-release.git version: 2.7.0 clearpath_platform_description: - tag: release/jazzy/clearpath_platform_description/2.7.4-1 + tag: release/jazzy/clearpath_platform_description/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_platform_msgs: tag: release/jazzy/clearpath_platform_msgs/2.7.0-1 url: https://github.com/clearpath-gbp/clearpath_msgs-release.git @@ -880,9 +888,9 @@ clearpath_ros2_socketcan_interface: url: https://github.com/clearpath-gbp/clearpath_ros2_socketcan_interface-release.git version: 2.1.4 clearpath_sensors_description: - tag: release/jazzy/clearpath_sensors_description/2.7.4-1 + tag: release/jazzy/clearpath_sensors_description/2.8.0-1 url: https://github.com/clearpath-gbp/clearpath_common-release.git - version: 2.7.4 + version: 2.8.0 clearpath_simulator: tag: release/jazzy/clearpath_simulator/2.7.0-1 url: https://github.com/clearpath-gbp/clearpath_simulator-release.git @@ -912,9 +920,9 @@ cmake_generate_parameter_module_example: url: https://github.com/ros2-gbp/generate_parameter_library-release.git version: 0.5.0 coal: - tag: release/jazzy/coal/3.0.1-1 + tag: release/jazzy/coal/3.0.2-1 url: https://github.com/ros2-gbp/coal-release.git - version: 3.0.1 + version: 3.0.2 cob_actions: tag: release/jazzy/cob_actions/2.8.12-1 url: https://github.com/ros2-gbp/cob_common-release.git @@ -972,25 +980,25 @@ control_msgs: url: https://github.com/ros2-gbp/control_msgs-release.git version: 5.5.0 control_toolbox: - tag: release/jazzy/control_toolbox/4.7.1-1 + tag: release/jazzy/control_toolbox/4.9.0-1 url: https://github.com/ros2-gbp/control_toolbox-release.git - version: 4.7.1 + version: 4.9.0 controller_interface: - tag: release/jazzy/controller_interface/4.37.0-1 + tag: release/jazzy/controller_interface/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 controller_manager: - tag: release/jazzy/controller_manager/4.37.0-1 + tag: release/jazzy/controller_manager/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 controller_manager_msgs: - tag: release/jazzy/controller_manager_msgs/4.37.0-1 + tag: release/jazzy/controller_manager_msgs/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 costmap_queue: - tag: release/jazzy/costmap_queue/1.3.9-1 + tag: release/jazzy/costmap_queue/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 crane_plus: tag: release/jazzy/crane_plus/3.0.0-1 url: https://github.com/ros2-gbp/crane_plus-release.git @@ -1143,6 +1151,10 @@ data_tamer_msgs: tag: release/jazzy/data_tamer_msgs/0.9.4-4 url: https://github.com/ros2-gbp/data_tamer-release.git version: 0.9.4 +data_tamer_tools: + tag: release/jazzy/data_tamer_tools/0.2.0-1 + url: https://github.com/jlack1987/data_tamer_tools-release.git + version: 0.2.0 dataspeed_can: tag: release/jazzy/dataspeed_can/2.0.6-1 url: https://github.com/DataspeedInc-release/dataspeed_can-release.git @@ -1272,9 +1284,9 @@ diagnostics: url: https://github.com/ros2-gbp/diagnostics-release.git version: 4.2.6 diff_drive_controller: - tag: release/jazzy/diff_drive_controller/4.32.0-1 + tag: release/jazzy/diff_drive_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 dolly: tag: release/jazzy/dolly/0.4.0-6 url: https://github.com/ros2-gbp/dolly-release.git @@ -1300,25 +1312,25 @@ domain_coordinator: url: https://github.com/ros2-gbp/ament_cmake_ros-release.git version: 0.12.0 draco_point_cloud_transport: - tag: release/jazzy/draco_point_cloud_transport/4.0.1-1 + tag: release/jazzy/draco_point_cloud_transport/4.0.2-1 url: https://github.com/ros2-gbp/point_cloud_transport_plugins-release.git - version: 4.0.1 + version: 4.0.2 ds_dbw: - tag: release/jazzy/ds_dbw/2.3.6-1 + tag: release/jazzy/ds_dbw/2.3.9-1 url: https://github.com/DataspeedInc-release/dbw_ros-release.git - version: 2.3.6 + version: 2.3.9 ds_dbw_can: - tag: release/jazzy/ds_dbw_can/2.3.6-1 + tag: release/jazzy/ds_dbw_can/2.3.9-1 url: https://github.com/DataspeedInc-release/dbw_ros-release.git - version: 2.3.6 + version: 2.3.9 ds_dbw_joystick_demo: - tag: release/jazzy/ds_dbw_joystick_demo/2.3.6-1 + tag: release/jazzy/ds_dbw_joystick_demo/2.3.9-1 url: https://github.com/DataspeedInc-release/dbw_ros-release.git - version: 2.3.6 + version: 2.3.9 ds_dbw_msgs: - tag: release/jazzy/ds_dbw_msgs/2.3.6-1 + tag: release/jazzy/ds_dbw_msgs/2.3.9-1 url: https://github.com/DataspeedInc-release/dbw_ros-release.git - version: 2.3.6 + version: 2.3.9 dual_arm_panda_moveit_config: tag: release/jazzy/dual_arm_panda_moveit_config/3.1.0-1 url: https://github.com/ros2-gbp/moveit_resources-release.git @@ -1340,21 +1352,21 @@ dummy_sensors: url: https://github.com/ros2-gbp/demos-release.git version: 0.33.7 dwb_core: - tag: release/jazzy/dwb_core/1.3.9-1 + tag: release/jazzy/dwb_core/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 dwb_critics: - tag: release/jazzy/dwb_critics/1.3.9-1 + tag: release/jazzy/dwb_critics/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 dwb_msgs: - tag: release/jazzy/dwb_msgs/1.3.9-1 + tag: release/jazzy/dwb_msgs/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 dwb_plugins: - tag: release/jazzy/dwb_plugins/1.3.9-1 + tag: release/jazzy/dwb_plugins/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 dynamic_edt_3d: tag: release/jazzy/dynamic_edt_3d/1.10.0-4 url: https://github.com/ros2-gbp/octomap-release.git @@ -1364,9 +1376,9 @@ dynamixel_hardware: url: https://github.com/ros2-gbp/dynamixel_hardware-release.git version: 0.5.0 dynamixel_hardware_interface: - tag: release/jazzy/dynamixel_hardware_interface/1.4.15-1 + tag: release/jazzy/dynamixel_hardware_interface/1.4.16-1 url: https://github.com/ros2-gbp/dynamixel_hardware_interface-release.git - version: 1.4.15 + version: 1.4.16 dynamixel_interfaces: tag: release/jazzy/dynamixel_interfaces/1.0.1-1 url: https://github.com/ros2-gbp/dynamixel_interfaces-release.git @@ -1540,9 +1552,9 @@ ecl_utilities: url: https://github.com/ros2-gbp/ecl_core-release.git version: 1.2.1 effort_controllers: - tag: release/jazzy/effort_controllers/4.32.0-1 + tag: release/jazzy/effort_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 eigen3_cmake_module: tag: release/jazzy/eigen3_cmake_module/0.3.0-3 url: https://github.com/ros2-gbp/eigen3_cmake_module-release.git @@ -1552,153 +1564,157 @@ eigen_stl_containers: url: https://github.com/ros2-gbp/eigen_stl_containers-release.git version: 1.1.0 eigenpy: - tag: release/jazzy/eigenpy/3.11.0-1 + tag: release/jazzy/eigenpy/3.12.0-1 url: https://github.com/ros2-gbp/eigenpy-release.git - version: 3.11.0 + version: 3.12.0 eiquadprog: - tag: release/jazzy/eiquadprog/1.2.9-1 + tag: release/jazzy/eiquadprog/1.3.0-1 url: https://github.com/ros2-gbp/eiquadprog-release.git - version: 1.2.9 + version: 1.3.0 ess_imu_driver2: tag: release/jazzy/ess_imu_driver2/2.0.3-1 url: https://github.com/ros2-gbp/ess_imu_driver2-release.git version: 2.0.3 etsi_its_cam_coding: - tag: release/jazzy/etsi_its_cam_coding/3.3.0-1 + tag: release/jazzy/etsi_its_cam_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cam_conversion: - tag: release/jazzy/etsi_its_cam_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_cam_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cam_msgs: - tag: release/jazzy/etsi_its_cam_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_cam_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cam_ts_coding: - tag: release/jazzy/etsi_its_cam_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_cam_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cam_ts_conversion: - tag: release/jazzy/etsi_its_cam_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_cam_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cam_ts_msgs: - tag: release/jazzy/etsi_its_cam_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_cam_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_coding: - tag: release/jazzy/etsi_its_coding/3.3.0-1 + tag: release/jazzy/etsi_its_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_conversion: - tag: release/jazzy/etsi_its_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 +etsi_its_conversion_srvs: + tag: release/jazzy/etsi_its_conversion_srvs/3.4.0-1 + url: https://github.com/ros2-gbp/etsi_its_messages-release.git + version: 3.4.0 etsi_its_cpm_ts_coding: - tag: release/jazzy/etsi_its_cpm_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_cpm_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cpm_ts_conversion: - tag: release/jazzy/etsi_its_cpm_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_cpm_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_cpm_ts_msgs: - tag: release/jazzy/etsi_its_cpm_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_cpm_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_coding: - tag: release/jazzy/etsi_its_denm_coding/3.3.0-1 + tag: release/jazzy/etsi_its_denm_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_conversion: - tag: release/jazzy/etsi_its_denm_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_denm_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_msgs: - tag: release/jazzy/etsi_its_denm_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_denm_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_ts_coding: - tag: release/jazzy/etsi_its_denm_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_denm_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_ts_conversion: - tag: release/jazzy/etsi_its_denm_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_denm_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_denm_ts_msgs: - tag: release/jazzy/etsi_its_denm_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_denm_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mapem_ts_coding: - tag: release/jazzy/etsi_its_mapem_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_mapem_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mapem_ts_conversion: - tag: release/jazzy/etsi_its_mapem_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_mapem_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mapem_ts_msgs: - tag: release/jazzy/etsi_its_mapem_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_mapem_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mcm_uulm_coding: - tag: release/jazzy/etsi_its_mcm_uulm_coding/3.3.0-1 + tag: release/jazzy/etsi_its_mcm_uulm_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mcm_uulm_conversion: - tag: release/jazzy/etsi_its_mcm_uulm_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_mcm_uulm_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_mcm_uulm_msgs: - tag: release/jazzy/etsi_its_mcm_uulm_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_mcm_uulm_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_messages: - tag: release/jazzy/etsi_its_messages/3.3.0-1 + tag: release/jazzy/etsi_its_messages/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_msgs: - tag: release/jazzy/etsi_its_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_msgs_utils: - tag: release/jazzy/etsi_its_msgs_utils/3.3.0-1 + tag: release/jazzy/etsi_its_msgs_utils/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_primitives_conversion: - tag: release/jazzy/etsi_its_primitives_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_primitives_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_rviz_plugins: - tag: release/jazzy/etsi_its_rviz_plugins/3.3.0-1 + tag: release/jazzy/etsi_its_rviz_plugins/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_spatem_ts_coding: - tag: release/jazzy/etsi_its_spatem_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_spatem_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_spatem_ts_conversion: - tag: release/jazzy/etsi_its_spatem_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_spatem_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_spatem_ts_msgs: - tag: release/jazzy/etsi_its_spatem_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_spatem_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_vam_ts_coding: - tag: release/jazzy/etsi_its_vam_ts_coding/3.3.0-1 + tag: release/jazzy/etsi_its_vam_ts_coding/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_vam_ts_conversion: - tag: release/jazzy/etsi_its_vam_ts_conversion/3.3.0-1 + tag: release/jazzy/etsi_its_vam_ts_conversion/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 etsi_its_vam_ts_msgs: - tag: release/jazzy/etsi_its_vam_ts_msgs/3.3.0-1 + tag: release/jazzy/etsi_its_vam_ts_msgs/3.4.0-1 url: https://github.com/ros2-gbp/etsi_its_messages-release.git - version: 3.3.0 + version: 3.4.0 event_camera_codecs: tag: release/jazzy/event_camera_codecs/2.0.0-1 url: https://github.com/ros2-gbp/event_camera_codecs-release.git @@ -1744,93 +1760,93 @@ example_interfaces: url: https://github.com/ros2-gbp/example_interfaces-release.git version: 0.12.0 examples_rclcpp_async_client: - tag: release/jazzy/examples_rclcpp_async_client/0.19.6-1 + tag: release/jazzy/examples_rclcpp_async_client/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_cbg_executor: - tag: release/jazzy/examples_rclcpp_cbg_executor/0.19.6-1 + tag: release/jazzy/examples_rclcpp_cbg_executor/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_action_client: - tag: release/jazzy/examples_rclcpp_minimal_action_client/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_action_client/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_action_server: - tag: release/jazzy/examples_rclcpp_minimal_action_server/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_action_server/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_client: - tag: release/jazzy/examples_rclcpp_minimal_client/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_client/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_composition: - tag: release/jazzy/examples_rclcpp_minimal_composition/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_composition/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_publisher: - tag: release/jazzy/examples_rclcpp_minimal_publisher/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_publisher/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_service: - tag: release/jazzy/examples_rclcpp_minimal_service/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_service/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_subscriber: - tag: release/jazzy/examples_rclcpp_minimal_subscriber/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_subscriber/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_minimal_timer: - tag: release/jazzy/examples_rclcpp_minimal_timer/0.19.6-1 + tag: release/jazzy/examples_rclcpp_minimal_timer/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_multithreaded_executor: - tag: release/jazzy/examples_rclcpp_multithreaded_executor/0.19.6-1 + tag: release/jazzy/examples_rclcpp_multithreaded_executor/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclcpp_wait_set: - tag: release/jazzy/examples_rclcpp_wait_set/0.19.6-1 + tag: release/jazzy/examples_rclcpp_wait_set/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_executors: - tag: release/jazzy/examples_rclpy_executors/0.19.6-1 + tag: release/jazzy/examples_rclpy_executors/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_guard_conditions: - tag: release/jazzy/examples_rclpy_guard_conditions/0.19.6-1 + tag: release/jazzy/examples_rclpy_guard_conditions/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_action_client: - tag: release/jazzy/examples_rclpy_minimal_action_client/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_action_client/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_action_server: - tag: release/jazzy/examples_rclpy_minimal_action_server/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_action_server/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_client: - tag: release/jazzy/examples_rclpy_minimal_client/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_client/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_publisher: - tag: release/jazzy/examples_rclpy_minimal_publisher/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_publisher/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_service: - tag: release/jazzy/examples_rclpy_minimal_service/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_service/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_minimal_subscriber: - tag: release/jazzy/examples_rclpy_minimal_subscriber/0.19.6-1 + tag: release/jazzy/examples_rclpy_minimal_subscriber/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_rclpy_pointcloud_publisher: - tag: release/jazzy/examples_rclpy_pointcloud_publisher/0.19.6-1 + tag: release/jazzy/examples_rclpy_pointcloud_publisher/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 examples_tf2_py: - tag: release/jazzy/examples_tf2_py/0.36.14-1 + tag: release/jazzy/examples_tf2_py/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 executive_smach: tag: release/jazzy/executive_smach/3.0.3-3 url: https://github.com/ros2-gbp/executive_smach-release.git @@ -1868,45 +1884,45 @@ ffmpeg_image_transport_tools: url: https://github.com/ros2-gbp/ffmpeg_image_transport_tools-release.git version: 3.0.1 ffw: - tag: release/jazzy/ffw/1.1.12-1 + tag: release/jazzy/ffw/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_bringup: - tag: release/jazzy/ffw_bringup/1.1.12-1 + tag: release/jazzy/ffw_bringup/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_description: - tag: release/jazzy/ffw_description/1.1.12-1 + tag: release/jazzy/ffw_description/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_joint_trajectory_command_broadcaster: - tag: release/jazzy/ffw_joint_trajectory_command_broadcaster/1.1.12-1 + tag: release/jazzy/ffw_joint_trajectory_command_broadcaster/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_joystick_controller: - tag: release/jazzy/ffw_joystick_controller/1.1.12-1 + tag: release/jazzy/ffw_joystick_controller/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_moveit_config: - tag: release/jazzy/ffw_moveit_config/1.1.12-1 + tag: release/jazzy/ffw_moveit_config/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_robot_manager: - tag: release/jazzy/ffw_robot_manager/1.1.12-1 + tag: release/jazzy/ffw_robot_manager/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_spring_actuator_controller: - tag: release/jazzy/ffw_spring_actuator_controller/1.1.12-1 + tag: release/jazzy/ffw_spring_actuator_controller/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_swerve_drive_controller: - tag: release/jazzy/ffw_swerve_drive_controller/1.1.12-1 + tag: release/jazzy/ffw_swerve_drive_controller/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 ffw_teleop: - tag: release/jazzy/ffw_teleop/1.1.12-1 + tag: release/jazzy/ffw_teleop/1.1.14-1 url: https://github.com/ros2-gbp/ai_worker-release.git - version: 1.1.12 + version: 1.1.14 fields2cover: tag: release/jazzy/fields2cover/2.0.0-10 url: https://github.com/ros2-gbp/fields2cover-release.git @@ -1992,29 +2008,33 @@ foonathan_memory_vendor: url: https://github.com/ros2-gbp/foonathan_memory_vendor-release.git version: 1.3.1 force_torque_sensor_broadcaster: - tag: release/jazzy/force_torque_sensor_broadcaster/4.32.0-1 + tag: release/jazzy/force_torque_sensor_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 forward_command_controller: - tag: release/jazzy/forward_command_controller/4.32.0-1 + tag: release/jazzy/forward_command_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 four_wheel_steering_msgs: tag: release/jazzy/four_wheel_steering_msgs/2.0.1-6 url: https://github.com/ros2-gbp/four_wheel_steering_msgs-release.git version: 2.0.1 foxglove_bridge: - tag: release/jazzy/foxglove_bridge/0.8.5-1 + tag: release/jazzy/foxglove_bridge/3.2.1-1 url: https://github.com/ros2-gbp/foxglove_bridge-release.git - version: 0.8.5 + version: 3.2.1 foxglove_compressed_video_transport: tag: release/jazzy/foxglove_compressed_video_transport/3.0.1-1 url: https://github.com/ros2-gbp/foxglove_compressed_video_transport-release.git version: 3.0.1 foxglove_msgs: - tag: release/jazzy/foxglove_msgs/3.1.0-1 - url: https://github.com/ros2-gbp/ros_foxglove_msgs-release.git - version: 3.1.0 + tag: release/jazzy/foxglove_msgs/3.2.1-1 + url: https://github.com/ros2-gbp/foxglove_bridge-release.git + version: 3.2.1 +frame_editor: + tag: release/jazzy/frame_editor/2.0.2-5 + url: https://github.com/ros2-gbp/rqt_frame_editor_plugin-release.git + version: 2.0.2 franka_inria_inverse_dynamics_solver: tag: release/jazzy/franka_inria_inverse_dynamics_solver/2.0.0-1 url: https://github.com/ros2-gbp/inverse_dynamics_solver-release.git @@ -2132,9 +2152,9 @@ geometric_shapes: url: https://github.com/ros2-gbp/geometric_shapes-release.git version: 2.3.2 geometry2: - tag: release/jazzy/geometry2/0.36.14-1 + tag: release/jazzy/geometry2/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 geometry_msgs: tag: release/jazzy/geometry_msgs/5.3.6-1 url: https://github.com/ros2-gbp/common_interfaces-release.git @@ -2152,17 +2172,17 @@ google_benchmark_vendor: url: https://github.com/ros2-gbp/google_benchmark_vendor-release.git version: 0.5.0 gpio_controllers: - tag: release/jazzy/gpio_controllers/4.32.0-1 + tag: release/jazzy/gpio_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 gps_msgs: tag: release/jazzy/gps_msgs/2.1.1-1 url: https://github.com/ros2-gbp/gps_umd-release.git version: 2.1.1 gps_sensor_broadcaster: - tag: release/jazzy/gps_sensor_broadcaster/4.32.0-1 + tag: release/jazzy/gps_sensor_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 gps_tools: tag: release/jazzy/gps_tools/2.1.1-1 url: https://github.com/ros2-gbp/gps_umd-release.git @@ -2192,69 +2212,69 @@ grbl_ros: url: https://github.com/ros2-gbp/grbl_ros-release.git version: 0.0.16 grid_map: - tag: release/jazzy/grid_map/2.2.1-1 + tag: release/jazzy/grid_map/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_cmake_helpers: - tag: release/jazzy/grid_map_cmake_helpers/2.2.1-1 + tag: release/jazzy/grid_map_cmake_helpers/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_core: - tag: release/jazzy/grid_map_core/2.2.1-1 + tag: release/jazzy/grid_map_core/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_costmap_2d: - tag: release/jazzy/grid_map_costmap_2d/2.2.1-1 + tag: release/jazzy/grid_map_costmap_2d/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_cv: - tag: release/jazzy/grid_map_cv/2.2.1-1 + tag: release/jazzy/grid_map_cv/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_demos: - tag: release/jazzy/grid_map_demos/2.2.1-1 + tag: release/jazzy/grid_map_demos/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_filters: - tag: release/jazzy/grid_map_filters/2.2.1-1 + tag: release/jazzy/grid_map_filters/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_loader: - tag: release/jazzy/grid_map_loader/2.2.1-1 + tag: release/jazzy/grid_map_loader/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_msgs: - tag: release/jazzy/grid_map_msgs/2.2.1-1 + tag: release/jazzy/grid_map_msgs/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_octomap: - tag: release/jazzy/grid_map_octomap/2.2.1-1 + tag: release/jazzy/grid_map_octomap/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_pcl: - tag: release/jazzy/grid_map_pcl/2.2.1-1 + tag: release/jazzy/grid_map_pcl/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_ros: - tag: release/jazzy/grid_map_ros/2.2.1-1 + tag: release/jazzy/grid_map_ros/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_rviz_plugin: - tag: release/jazzy/grid_map_rviz_plugin/2.2.1-1 + tag: release/jazzy/grid_map_rviz_plugin/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_sdf: - tag: release/jazzy/grid_map_sdf/2.2.1-1 + tag: release/jazzy/grid_map_sdf/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 grid_map_visualization: - tag: release/jazzy/grid_map_visualization/2.2.1-1 + tag: release/jazzy/grid_map_visualization/2.2.2-2 url: https://github.com/ros2-gbp/grid_map-release.git - version: 2.2.1 + version: 2.2.2 gripper_controllers: - tag: release/jazzy/gripper_controllers/4.32.0-1 + tag: release/jazzy/gripper_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 gscam: tag: release/jazzy/gscam/2.0.2-5 url: https://github.com/ros2-gbp/gscam-release.git @@ -2308,9 +2328,9 @@ gz_ogre_next_vendor: url: https://github.com/ros2-gbp/gz_ogre_next_vendor-release.git version: 0.0.5 gz_physics_vendor: - tag: release/jazzy/gz_physics_vendor/0.0.6-1 + tag: release/jazzy/gz_physics_vendor/0.0.7-1 url: https://github.com/ros2-gbp/gz_physics_vendor-release.git - version: 0.0.6 + version: 0.0.7 gz_plugin_vendor: tag: release/jazzy/gz_plugin_vendor/0.0.5-1 url: https://github.com/ros2-gbp/gz_plugin_vendor-release.git @@ -2320,41 +2340,41 @@ gz_rendering_vendor: url: https://github.com/ros2-gbp/gz_rendering_vendor-release.git version: 0.0.6 gz_ros2_control: - tag: release/jazzy/gz_ros2_control/1.2.15-1 + tag: release/jazzy/gz_ros2_control/1.2.16-1 url: https://github.com/ros2-gbp/ign_ros2_control-release.git - version: 1.2.15 + version: 1.2.16 gz_ros2_control_demos: - tag: release/jazzy/gz_ros2_control_demos/1.2.15-1 + tag: release/jazzy/gz_ros2_control_demos/1.2.16-1 url: https://github.com/ros2-gbp/ign_ros2_control-release.git - version: 1.2.15 + version: 1.2.16 gz_sensors_vendor: tag: release/jazzy/gz_sensors_vendor/0.0.6-1 url: https://github.com/ros2-gbp/gz_sensors_vendor-release.git version: 0.0.6 gz_sim_vendor: - tag: release/jazzy/gz_sim_vendor/0.0.8-1 + tag: release/jazzy/gz_sim_vendor/0.0.9-1 url: https://github.com/ros2-gbp/gz_sim_vendor-release.git - version: 0.0.8 + version: 0.0.9 gz_tools_vendor: tag: release/jazzy/gz_tools_vendor/0.0.7-1 url: https://github.com/ros2-gbp/gz_tools_vendor-release.git version: 0.0.7 gz_transport_vendor: - tag: release/jazzy/gz_transport_vendor/0.0.6-1 + tag: release/jazzy/gz_transport_vendor/0.0.7-1 url: https://github.com/ros2-gbp/gz_transport_vendor-release.git - version: 0.0.6 + version: 0.0.7 gz_utils_vendor: tag: release/jazzy/gz_utils_vendor/0.0.5-1 url: https://github.com/ros2-gbp/gz_utils_vendor-release.git version: 0.0.5 hardware_interface: - tag: release/jazzy/hardware_interface/4.37.0-1 + tag: release/jazzy/hardware_interface/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 hardware_interface_testing: - tag: release/jazzy/hardware_interface_testing/4.37.0-1 + tag: release/jazzy/hardware_interface_testing/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 hash_library_vendor: tag: release/jazzy/hash_library_vendor/0.1.1-7 url: https://github.com/ros2-gbp/hash_library_vendor-release.git @@ -2368,9 +2388,9 @@ heaphook: url: https://github.com/ros2-gbp/heaphook-release.git version: 0.1.1 hebi_cpp_api: - tag: release/jazzy/hebi_cpp_api/3.13.0-3 + tag: release/jazzy/hebi_cpp_api/3.15.0-1 url: https://github.com/ros2-gbp/hebi_cpp_api-release.git - version: 3.13.0 + version: 3.15.0 hls_lfcd_lds_driver: tag: release/jazzy/hls_lfcd_lds_driver/2.1.1-1 url: https://github.com/ros2-gbp/hls_lfcd_lds_driver-release.git @@ -2472,9 +2492,9 @@ imu_processors: url: https://github.com/ros2-gbp/imu_pipeline-release.git version: 0.5.2 imu_sensor_broadcaster: - tag: release/jazzy/imu_sensor_broadcaster/4.32.0-1 + tag: release/jazzy/imu_sensor_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 imu_tools: tag: release/jazzy/imu_tools/2.1.5-1 url: https://github.com/ros2-gbp/imu_tools-release.git @@ -2484,17 +2504,17 @@ imu_transformer: url: https://github.com/ros2-gbp/imu_pipeline-release.git version: 0.5.2 insight_gui: - tag: release/jazzy/insight_gui/0.1.2-1 + tag: release/jazzy/insight_gui/0.1.3-1 url: https://github.com/ros2-gbp/insight_gui-release.git - version: 0.1.2 + version: 0.1.3 interactive_marker_twist_server: tag: release/jazzy/interactive_marker_twist_server/2.1.1-1 url: https://github.com/ros2-gbp/interactive_marker_twist_server-release.git version: 2.1.1 interactive_markers: - tag: release/jazzy/interactive_markers/2.5.4-2 + tag: release/jazzy/interactive_markers/2.5.5-1 url: https://github.com/ros2-gbp/interactive_markers-release.git - version: 2.5.4 + version: 2.5.5 intra_process_demo: tag: release/jazzy/intra_process_demo/0.33.7-1 url: https://github.com/ros2-gbp/demos-release.git @@ -2552,13 +2572,13 @@ jacro: url: https://github.com/ros2-gbp/jacro-release.git version: 0.2.0 joint_limits: - tag: release/jazzy/joint_limits/4.37.0-1 + tag: release/jazzy/joint_limits/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 joint_state_broadcaster: - tag: release/jazzy/joint_state_broadcaster/4.32.0-1 + tag: release/jazzy/joint_state_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 joint_state_publisher: tag: release/jazzy/joint_state_publisher/2.4.0-3 url: https://github.com/ros2-gbp/joint_state_publisher-release.git @@ -2568,13 +2588,13 @@ joint_state_publisher_gui: url: https://github.com/ros2-gbp/joint_state_publisher-release.git version: 2.4.0 joint_state_topic_hardware_interface: - tag: release/jazzy/joint_state_topic_hardware_interface/0.2.0-1 + tag: release/jazzy/joint_state_topic_hardware_interface/0.2.1-1 url: https://github.com/ros2-gbp/topic_based_hardware-release.git - version: 0.2.0 + version: 0.2.1 joint_trajectory_controller: - tag: release/jazzy/joint_trajectory_controller/4.32.0-1 + tag: release/jazzy/joint_trajectory_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 joy: tag: release/jazzy/joy/3.3.0-3 url: https://github.com/ros2-gbp/joystick_drivers-release.git @@ -2591,6 +2611,10 @@ joy_tester: tag: release/jazzy/joy_tester/0.0.2-4 url: https://github.com/ros2-gbp/joy_tester-release.git version: 0.0.2 +jrl_cmakemodules: + tag: release/jazzy/jrl_cmakemodules/1.1.0-2 + url: https://github.com/ros2-gbp/jrl_cmakemodules-release.git + version: 1.1.0 kartech_linear_actuator_msgs: tag: release/jazzy/kartech_linear_actuator_msgs/4.0.0-4 url: https://github.com/ros2-gbp/astuff_sensor_msgs-release.git @@ -2612,21 +2636,21 @@ keyboard_handler: url: https://github.com/ros2-gbp/keyboard_handler-release.git version: 0.3.1 kinematics_interface: - tag: release/jazzy/kinematics_interface/1.5.0-1 + tag: release/jazzy/kinematics_interface/1.6.0-1 url: https://github.com/ros2-gbp/kinematics_interface-release.git - version: 1.5.0 + version: 1.6.0 kinematics_interface_kdl: - tag: release/jazzy/kinematics_interface_kdl/1.5.0-1 + tag: release/jazzy/kinematics_interface_kdl/1.6.0-1 url: https://github.com/ros2-gbp/kinematics_interface-release.git - version: 1.5.0 + version: 1.6.0 kinematics_interface_pinocchio: tag: release/jazzy/kinematics_interface_pinocchio/0.0.1-1 url: https://github.com/justagist/kinematics_interface_pinocchio-release.git version: 0.0.1 kitti_metrics_eval: - tag: release/jazzy/kitti_metrics_eval/1.9.0-1 + tag: release/jazzy/kitti_metrics_eval/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 kobuki_core: tag: release/jazzy/kobuki_core/1.4.0-4 url: https://github.com/ros2-gbp/kobuki_core-release.git @@ -2640,13 +2664,13 @@ kobuki_velocity_smoother: url: https://github.com/ros2-gbp/kobuki_velocity_smoother-release.git version: 0.15.0 kompass: - tag: release/jazzy/kompass/0.3.1-1 + tag: release/jazzy/kompass/0.3.2-1 url: https://github.com/ros2-gbp/kompass-release.git - version: 0.3.1 + version: 0.3.2 kompass_interfaces: - tag: release/jazzy/kompass_interfaces/0.3.1-1 + tag: release/jazzy/kompass_interfaces/0.3.2-1 url: https://github.com/ros2-gbp/kompass-release.git - version: 0.3.1 + version: 0.3.2 lanelet2: tag: release/jazzy/lanelet2/1.2.1-1 url: https://github.com/ros2-gbp/lanelet2-release.git @@ -2696,9 +2720,9 @@ laser_filters: url: https://github.com/ros2-gbp/laser_filters-release.git version: 2.0.9 laser_geometry: - tag: release/jazzy/laser_geometry/2.7.1-1 + tag: release/jazzy/laser_geometry/2.7.2-1 url: https://github.com/ros2-gbp/laser_geometry-release.git - version: 2.7.1 + version: 2.7.2 laser_proc: tag: release/jazzy/laser_proc/1.0.2-7 url: https://github.com/ros2-gbp/laser_proc-release.git @@ -2708,17 +2732,21 @@ laser_segmentation: url: https://github.com/ros2-gbp/laser_segmentation-release.git version: 3.0.4 launch: - tag: release/jazzy/launch/3.4.6-1 + tag: release/jazzy/launch/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 +launch_frontend_py: + tag: release/jazzy/launch_frontend_py/0.1.0-1 + url: https://github.com/ros2-gbp/launch_frontend_py-release.git + version: 0.1.0 launch_param_builder: tag: release/jazzy/launch_param_builder/0.1.1-4 url: https://github.com/ros2-gbp/launch_param_builder-release.git version: 0.1.1 launch_pytest: - tag: release/jazzy/launch_pytest/3.4.6-1 + tag: release/jazzy/launch_pytest/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 launch_ros: tag: release/jazzy/launch_ros/0.26.9-1 url: https://github.com/ros2-gbp/launch_ros-release.git @@ -2728,29 +2756,29 @@ launch_system_modes: url: https://github.com/ros2-gbp/system_modes-release.git version: 0.9.0 launch_testing: - tag: release/jazzy/launch_testing/3.4.6-1 + tag: release/jazzy/launch_testing/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 launch_testing_ament_cmake: - tag: release/jazzy/launch_testing_ament_cmake/3.4.6-1 + tag: release/jazzy/launch_testing_ament_cmake/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 launch_testing_examples: - tag: release/jazzy/launch_testing_examples/0.19.6-1 + tag: release/jazzy/launch_testing_examples/0.19.7-1 url: https://github.com/ros2-gbp/examples-release.git - version: 0.19.6 + version: 0.19.7 launch_testing_ros: tag: release/jazzy/launch_testing_ros/0.26.9-1 url: https://github.com/ros2-gbp/launch_ros-release.git version: 0.26.9 launch_xml: - tag: release/jazzy/launch_xml/3.4.6-1 + tag: release/jazzy/launch_xml/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 launch_yaml: - tag: release/jazzy/launch_yaml/3.4.6-1 + tag: release/jazzy/launch_yaml/3.4.8-1 url: https://github.com/ros2-gbp/launch-release.git - version: 3.4.6 + version: 3.4.8 ld08_driver: tag: release/jazzy/ld08_driver/1.1.4-1 url: https://github.com/ros2-gbp/ld08_driver-release.git @@ -2888,9 +2916,9 @@ linux_isolate_process: url: https://github.com/ros2-gbp/linux_isolate_process-release.git version: 0.0.2 live555_vendor: - tag: release/jazzy/live555_vendor/0.20250719.0-1 + tag: release/jazzy/live555_vendor/0.20250917.0-1 url: https://github.com/ros2-gbp/live555_vendor-release.git - version: 0.20250719.0 + version: 0.20250917.0 lms1xx: tag: release/jazzy/lms1xx/1.0.1-1 url: https://github.com/clearpath-gbp/LMS1xx-release.git @@ -3000,17 +3028,17 @@ mcap_vendor: url: https://github.com/ros2-gbp/rosbag2-release.git version: 0.26.9 mecanum_drive_controller: - tag: release/jazzy/mecanum_drive_controller/4.32.0-1 + tag: release/jazzy/mecanum_drive_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 menge_vendor: tag: release/jazzy/menge_vendor/1.2.1-1 url: https://github.com/ros2-gbp/menge_vendor-release.git version: 1.2.1 message_filters: - tag: release/jazzy/message_filters/4.11.7-1 + tag: release/jazzy/message_filters/4.11.9-1 url: https://github.com/ros2-gbp/ros2_message_filters-release.git - version: 4.11.7 + version: 4.11.9 message_tf_frame_transformer: tag: release/jazzy/message_tf_frame_transformer/1.1.3-1 url: https://github.com/ros2-gbp/message_tf_frame_transformer-release.git @@ -3032,25 +3060,25 @@ micro_ros_msgs: url: https://github.com/ros2-gbp/micro_ros_msgs-release.git version: 1.0.0 microstrain_inertial_description: - tag: release/jazzy/microstrain_inertial_description/4.7.0-1 + tag: release/jazzy/microstrain_inertial_description/4.8.0-1 url: https://github.com/ros2-gbp/microstrain_inertial-release.git - version: 4.7.0 + version: 4.8.0 microstrain_inertial_driver: - tag: release/jazzy/microstrain_inertial_driver/4.7.0-1 + tag: release/jazzy/microstrain_inertial_driver/4.8.0-1 url: https://github.com/ros2-gbp/microstrain_inertial-release.git - version: 4.7.0 + version: 4.8.0 microstrain_inertial_examples: - tag: release/jazzy/microstrain_inertial_examples/4.7.0-1 + tag: release/jazzy/microstrain_inertial_examples/4.8.0-1 url: https://github.com/ros2-gbp/microstrain_inertial-release.git - version: 4.7.0 + version: 4.8.0 microstrain_inertial_msgs: - tag: release/jazzy/microstrain_inertial_msgs/4.7.0-1 + tag: release/jazzy/microstrain_inertial_msgs/4.8.0-1 url: https://github.com/ros2-gbp/microstrain_inertial-release.git - version: 4.7.0 + version: 4.8.0 microstrain_inertial_rqt: - tag: release/jazzy/microstrain_inertial_rqt/4.7.0-1 + tag: release/jazzy/microstrain_inertial_rqt/4.8.0-1 url: https://github.com/ros2-gbp/microstrain_inertial-release.git - version: 4.7.0 + version: 4.8.0 mimick_vendor: tag: release/jazzy/mimick_vendor/0.6.2-1 url: https://github.com/ros2-gbp/mimick_vendor-release.git @@ -3064,113 +3092,121 @@ mocap_optitrack: url: https://github.com/ros2-gbp/mocap_optitrack-release.git version: 1.0.1 mola: - tag: release/jazzy/mola/1.9.0-1 + tag: release/jazzy/mola/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_bridge_ros2: - tag: release/jazzy/mola_bridge_ros2/1.9.0-1 + tag: release/jazzy/mola_bridge_ros2/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_common: - tag: release/jazzy/mola_common/0.5.1-1 + tag: release/jazzy/mola_common/0.5.2-1 url: https://github.com/ros2-gbp/mola_common-release.git - version: 0.5.1 + version: 0.5.2 mola_demos: - tag: release/jazzy/mola_demos/1.9.0-1 + tag: release/jazzy/mola_demos/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_gnss_to_markers: tag: release/jazzy/mola_gnss_to_markers/0.1.0-1 url: https://github.com/ros2-gbp/mola_gnss_to_markers-release.git version: 0.1.0 +mola_imu_preintegration: + tag: release/jazzy/mola_imu_preintegration/1.13.2-1 + url: https://github.com/ros2-gbp/mola_imu_preintegration-release.git + version: 1.13.2 mola_input_euroc_dataset: - tag: release/jazzy/mola_input_euroc_dataset/1.9.0-1 + tag: release/jazzy/mola_input_euroc_dataset/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_kitti360_dataset: - tag: release/jazzy/mola_input_kitti360_dataset/1.9.0-1 + tag: release/jazzy/mola_input_kitti360_dataset/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_kitti_dataset: - tag: release/jazzy/mola_input_kitti_dataset/1.9.0-1 + tag: release/jazzy/mola_input_kitti_dataset/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 +mola_input_lidar_bin_dataset: + tag: release/jazzy/mola_input_lidar_bin_dataset/2.1.0-1 + url: https://github.com/ros2-gbp/mola-release.git + version: 2.1.0 mola_input_mulran_dataset: - tag: release/jazzy/mola_input_mulran_dataset/1.9.0-1 + tag: release/jazzy/mola_input_mulran_dataset/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_paris_luco_dataset: - tag: release/jazzy/mola_input_paris_luco_dataset/1.9.0-1 + tag: release/jazzy/mola_input_paris_luco_dataset/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_rawlog: - tag: release/jazzy/mola_input_rawlog/1.9.0-1 + tag: release/jazzy/mola_input_rawlog/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_rosbag2: - tag: release/jazzy/mola_input_rosbag2/1.9.0-1 + tag: release/jazzy/mola_input_rosbag2/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_input_video: - tag: release/jazzy/mola_input_video/1.9.0-1 + tag: release/jazzy/mola_input_video/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_kernel: - tag: release/jazzy/mola_kernel/1.9.0-1 + tag: release/jazzy/mola_kernel/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_launcher: - tag: release/jazzy/mola_launcher/1.9.0-1 + tag: release/jazzy/mola_launcher/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_lidar_odometry: - tag: release/jazzy/mola_lidar_odometry/0.9.0-1 + tag: release/jazzy/mola_lidar_odometry/1.2.0-1 url: https://github.com/ros2-gbp/mola_lidar_odometry-release.git - version: 0.9.0 + version: 1.2.0 mola_metric_maps: - tag: release/jazzy/mola_metric_maps/1.9.0-1 + tag: release/jazzy/mola_metric_maps/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_msgs: - tag: release/jazzy/mola_msgs/1.9.0-1 + tag: release/jazzy/mola_msgs/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_pose_list: - tag: release/jazzy/mola_pose_list/1.9.0-1 + tag: release/jazzy/mola_pose_list/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_relocalization: - tag: release/jazzy/mola_relocalization/1.9.0-1 + tag: release/jazzy/mola_relocalization/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_state_estimation: - tag: release/jazzy/mola_state_estimation/1.10.0-1 + tag: release/jazzy/mola_state_estimation/1.11.1-1 url: https://github.com/ros2-gbp/mola_state_estimation-release.git - version: 1.10.0 + version: 1.11.1 mola_state_estimation_simple: - tag: release/jazzy/mola_state_estimation_simple/1.10.0-1 + tag: release/jazzy/mola_state_estimation_simple/1.11.1-1 url: https://github.com/ros2-gbp/mola_state_estimation-release.git - version: 1.10.0 + version: 1.11.1 mola_state_estimation_smoother: - tag: release/jazzy/mola_state_estimation_smoother/1.10.0-1 + tag: release/jazzy/mola_state_estimation_smoother/1.11.1-1 url: https://github.com/ros2-gbp/mola_state_estimation-release.git - version: 1.10.0 + version: 1.11.1 mola_test_datasets: tag: release/jazzy/mola_test_datasets/0.4.2-1 url: https://github.com/ros2-gbp/mola_test_datasets-release.git version: 0.4.2 mola_traj_tools: - tag: release/jazzy/mola_traj_tools/1.9.0-1 + tag: release/jazzy/mola_traj_tools/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_viz: - tag: release/jazzy/mola_viz/1.9.0-1 + tag: release/jazzy/mola_viz/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 mola_yaml: - tag: release/jazzy/mola_yaml/1.9.0-1 + tag: release/jazzy/mola_yaml/2.1.0-1 url: https://github.com/ros2-gbp/mola-release.git - version: 1.9.0 + version: 2.1.0 motion_capture_tracking: tag: release/jazzy/motion_capture_tracking/1.0.6-1 url: https://github.com/ros2-gbp/motion_capture_tracking-release.git @@ -3363,14 +3399,34 @@ moveit_simple_controller_manager: tag: release/jazzy/moveit_simple_controller_manager/2.12.3-1 url: https://github.com/ros2-gbp/moveit2-release.git version: 2.12.3 +moveit_task_constructor_capabilities: + tag: release/jazzy/moveit_task_constructor_capabilities/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 +moveit_task_constructor_core: + tag: release/jazzy/moveit_task_constructor_core/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 +moveit_task_constructor_demo: + tag: release/jazzy/moveit_task_constructor_demo/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 +moveit_task_constructor_msgs: + tag: release/jazzy/moveit_task_constructor_msgs/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 +moveit_task_constructor_visualization: + tag: release/jazzy/moveit_task_constructor_visualization/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 moveit_visual_tools: tag: release/jazzy/moveit_visual_tools/4.1.2-1 url: https://github.com/ros2-gbp/moveit_visual_tools-release.git version: 4.1.2 mp2p_icp: - tag: release/jazzy/mp2p_icp/1.8.0-1 + tag: release/jazzy/mp2p_icp/2.0.0-1 url: https://github.com/ros2-gbp/mp2p_icp-release.git - version: 1.8.0 + version: 2.0.0 mqtt_client: tag: release/jazzy/mqtt_client/2.4.1-2 url: https://github.com/ros2-gbp/mqtt_client-release.git @@ -3380,73 +3436,73 @@ mqtt_client_interfaces: url: https://github.com/ros2-gbp/mqtt_client-release.git version: 2.4.1 mrpt_apps: - tag: release/jazzy/mrpt_apps/2.14.12-1 + tag: release/jazzy/mrpt_apps/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_generic_sensor: tag: release/jazzy/mrpt_generic_sensor/0.2.3-1 url: https://github.com/ros2-gbp/mrpt_sensors-release.git version: 0.2.3 mrpt_libapps: - tag: release/jazzy/mrpt_libapps/2.14.12-1 + tag: release/jazzy/mrpt_libapps/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libbase: - tag: release/jazzy/mrpt_libbase/2.14.12-1 + tag: release/jazzy/mrpt_libbase/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libgui: - tag: release/jazzy/mrpt_libgui/2.14.12-1 + tag: release/jazzy/mrpt_libgui/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libhwdrivers: - tag: release/jazzy/mrpt_libhwdrivers/2.14.12-1 + tag: release/jazzy/mrpt_libhwdrivers/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libmaps: - tag: release/jazzy/mrpt_libmaps/2.14.12-1 + tag: release/jazzy/mrpt_libmaps/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libmath: - tag: release/jazzy/mrpt_libmath/2.14.12-1 + tag: release/jazzy/mrpt_libmath/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libnav: - tag: release/jazzy/mrpt_libnav/2.14.12-1 + tag: release/jazzy/mrpt_libnav/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libobs: - tag: release/jazzy/mrpt_libobs/2.14.12-1 + tag: release/jazzy/mrpt_libobs/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libopengl: - tag: release/jazzy/mrpt_libopengl/2.14.12-1 + tag: release/jazzy/mrpt_libopengl/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libposes: - tag: release/jazzy/mrpt_libposes/2.14.12-1 + tag: release/jazzy/mrpt_libposes/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libros_bridge: - tag: release/jazzy/mrpt_libros_bridge/2.14.12-1 + tag: release/jazzy/mrpt_libros_bridge/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libslam: - tag: release/jazzy/mrpt_libslam/2.14.12-1 + tag: release/jazzy/mrpt_libslam/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_libtclap: - tag: release/jazzy/mrpt_libtclap/2.14.12-1 + tag: release/jazzy/mrpt_libtclap/2.14.16-1 url: https://github.com/ros2-gbp/mrpt_ros-release.git - version: 2.14.12 + version: 2.14.16 mrpt_map_server: tag: release/jazzy/mrpt_map_server/2.2.3-1 url: https://github.com/ros2-gbp/mrpt_navigation-release.git version: 2.2.3 mrpt_msgs: - tag: release/jazzy/mrpt_msgs/0.5.0-1 + tag: release/jazzy/mrpt_msgs/0.6.0-1 url: https://github.com/ros2-gbp/mrpt_msgs-release.git - version: 0.5.0 + version: 0.6.0 mrpt_msgs_bridge: tag: release/jazzy/mrpt_msgs_bridge/2.2.3-1 url: https://github.com/ros2-gbp/mrpt_navigation-release.git @@ -3520,21 +3576,21 @@ multires_image: url: https://github.com/ros2-gbp/mapviz-release.git version: 2.5.10 multisensor_calibration: - tag: release/jazzy/multisensor_calibration/2.0.3-1 + tag: release/jazzy/multisensor_calibration/2.0.4-1 url: https://github.com/ros2-gbp/multisensor_calibration-release.git - version: 2.0.3 + version: 2.0.4 multisensor_calibration_interface: - tag: release/jazzy/multisensor_calibration_interface/2.0.3-1 + tag: release/jazzy/multisensor_calibration_interface/2.0.4-1 url: https://github.com/ros2-gbp/multisensor_calibration-release.git - version: 2.0.3 + version: 2.0.4 mvsim: tag: release/jazzy/mvsim/0.14.0-1 url: https://github.com/ros2-gbp/mvsim-release.git version: 0.14.0 nanoeigenpy: - tag: release/jazzy/nanoeigenpy/0.3.0-1 + tag: release/jazzy/nanoeigenpy/0.4.0-1 url: https://github.com/ros2-gbp/nanoeigenpy-release.git - version: 0.3.0 + version: 0.4.0 nao_button_sim: tag: release/jazzy/nao_button_sim/1.0.1-1 url: https://github.com/ros2-gbp/nao_button_sim-release.git @@ -3568,69 +3624,69 @@ naoqi_libqi: url: https://github.com/ros-naoqi/libqi-release.git version: 3.0.3 nav2_amcl: - tag: release/jazzy/nav2_amcl/1.3.9-1 + tag: release/jazzy/nav2_amcl/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_behavior_tree: - tag: release/jazzy/nav2_behavior_tree/1.3.9-1 + tag: release/jazzy/nav2_behavior_tree/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_behaviors: - tag: release/jazzy/nav2_behaviors/1.3.9-1 + tag: release/jazzy/nav2_behaviors/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_bringup: - tag: release/jazzy/nav2_bringup/1.3.9-1 + tag: release/jazzy/nav2_bringup/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_bt_navigator: - tag: release/jazzy/nav2_bt_navigator/1.3.9-1 + tag: release/jazzy/nav2_bt_navigator/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_collision_monitor: - tag: release/jazzy/nav2_collision_monitor/1.3.9-1 + tag: release/jazzy/nav2_collision_monitor/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_common: - tag: release/jazzy/nav2_common/1.3.9-1 + tag: release/jazzy/nav2_common/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_constrained_smoother: - tag: release/jazzy/nav2_constrained_smoother/1.3.9-1 + tag: release/jazzy/nav2_constrained_smoother/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_controller: - tag: release/jazzy/nav2_controller/1.3.9-1 + tag: release/jazzy/nav2_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_core: - tag: release/jazzy/nav2_core/1.3.9-1 + tag: release/jazzy/nav2_core/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_costmap_2d: - tag: release/jazzy/nav2_costmap_2d/1.3.9-1 + tag: release/jazzy/nav2_costmap_2d/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_dwb_controller: - tag: release/jazzy/nav2_dwb_controller/1.3.9-1 + tag: release/jazzy/nav2_dwb_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_graceful_controller: - tag: release/jazzy/nav2_graceful_controller/1.3.9-1 + tag: release/jazzy/nav2_graceful_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_lifecycle_manager: - tag: release/jazzy/nav2_lifecycle_manager/1.3.9-1 + tag: release/jazzy/nav2_lifecycle_manager/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_loopback_sim: - tag: release/jazzy/nav2_loopback_sim/1.3.9-1 + tag: release/jazzy/nav2_loopback_sim/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_map_server: - tag: release/jazzy/nav2_map_server/1.3.9-1 + tag: release/jazzy/nav2_map_server/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_minimal_tb3_sim: tag: release/jazzy/nav2_minimal_tb3_sim/1.0.1-1 url: https://github.com/ros2-gbp/nav2_minimal_turtlebot_simulation-release.git @@ -3644,89 +3700,109 @@ nav2_minimal_tb4_sim: url: https://github.com/ros2-gbp/nav2_minimal_turtlebot_simulation-release.git version: 1.0.1 nav2_mppi_controller: - tag: release/jazzy/nav2_mppi_controller/1.3.9-1 + tag: release/jazzy/nav2_mppi_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_msgs: - tag: release/jazzy/nav2_msgs/1.3.9-1 + tag: release/jazzy/nav2_msgs/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_navfn_planner: - tag: release/jazzy/nav2_navfn_planner/1.3.9-1 + tag: release/jazzy/nav2_navfn_planner/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_planner: - tag: release/jazzy/nav2_planner/1.3.9-1 + tag: release/jazzy/nav2_planner/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_regulated_pure_pursuit_controller: - tag: release/jazzy/nav2_regulated_pure_pursuit_controller/1.3.9-1 + tag: release/jazzy/nav2_regulated_pure_pursuit_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_rotation_shim_controller: - tag: release/jazzy/nav2_rotation_shim_controller/1.3.9-1 + tag: release/jazzy/nav2_rotation_shim_controller/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_route: - tag: release/jazzy/nav2_route/1.3.9-1 + tag: release/jazzy/nav2_route/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_rviz_plugins: - tag: release/jazzy/nav2_rviz_plugins/1.3.9-1 + tag: release/jazzy/nav2_rviz_plugins/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_simple_commander: - tag: release/jazzy/nav2_simple_commander/1.3.9-1 + tag: release/jazzy/nav2_simple_commander/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_smac_planner: - tag: release/jazzy/nav2_smac_planner/1.3.9-1 + tag: release/jazzy/nav2_smac_planner/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_smoother: - tag: release/jazzy/nav2_smoother/1.3.9-1 + tag: release/jazzy/nav2_smoother/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_system_tests: - tag: release/jazzy/nav2_system_tests/1.3.9-1 + tag: release/jazzy/nav2_system_tests/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_theta_star_planner: - tag: release/jazzy/nav2_theta_star_planner/1.3.9-1 + tag: release/jazzy/nav2_theta_star_planner/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_util: - tag: release/jazzy/nav2_util/1.3.9-1 + tag: release/jazzy/nav2_util/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_velocity_smoother: - tag: release/jazzy/nav2_velocity_smoother/1.3.9-1 + tag: release/jazzy/nav2_velocity_smoother/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_voxel_grid: - tag: release/jazzy/nav2_voxel_grid/1.3.9-1 + tag: release/jazzy/nav2_voxel_grid/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav2_waypoint_follower: - tag: release/jazzy/nav2_waypoint_follower/1.3.9-1 + tag: release/jazzy/nav2_waypoint_follower/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav_2d_msgs: - tag: release/jazzy/nav_2d_msgs/1.3.9-1 + tag: release/jazzy/nav_2d_msgs/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav_2d_utils: - tag: release/jazzy/nav_2d_utils/1.3.9-1 + tag: release/jazzy/nav_2d_utils/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 nav_msgs: tag: release/jazzy/nav_msgs/5.3.6-1 url: https://github.com/ros2-gbp/common_interfaces-release.git version: 5.3.6 navigation2: - tag: release/jazzy/navigation2/1.3.9-1 + tag: release/jazzy/navigation2/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 +navmap_core: + tag: release/jazzy/navmap_core/0.2.5-1 + url: https://github.com/EasyNavigation/NavMap-release.git + version: 0.2.5 +navmap_examples: + tag: release/jazzy/navmap_examples/0.2.5-1 + url: https://github.com/EasyNavigation/NavMap-release.git + version: 0.2.5 +navmap_ros: + tag: release/jazzy/navmap_ros/0.2.5-1 + url: https://github.com/EasyNavigation/NavMap-release.git + version: 0.2.5 +navmap_ros_interfaces: + tag: release/jazzy/navmap_ros_interfaces/0.2.5-1 + url: https://github.com/EasyNavigation/NavMap-release.git + version: 0.2.5 +navmap_rviz_plugin: + tag: release/jazzy/navmap_rviz_plugin/0.2.5-1 + url: https://github.com/EasyNavigation/NavMap-release.git + version: 0.2.5 neo_nav2_bringup: tag: release/jazzy/neo_nav2_bringup/1.3.1-1 url: https://github.com/ros2-gbp/neo_nav2_bringup-release.git @@ -3904,9 +3980,9 @@ om_spring_actuator_controller: url: https://github.com/ros2-gbp/open_manipulator-release.git version: 4.0.8 omni_wheel_drive_controller: - tag: release/jazzy/omni_wheel_drive_controller/4.32.0-1 + tag: release/jazzy/omni_wheel_drive_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 ompl: tag: release/jazzy/ompl/1.7.0-2 url: https://github.com/ros2-gbp/ompl-release.git @@ -3960,17 +4036,17 @@ openeb_vendor: url: https://github.com/ros2-gbp/openeb_vendor-release.git version: 2.0.2 opennav_docking: - tag: release/jazzy/opennav_docking/1.3.9-1 + tag: release/jazzy/opennav_docking/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 opennav_docking_bt: - tag: release/jazzy/opennav_docking_bt/1.3.9-1 + tag: release/jazzy/opennav_docking_bt/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 opennav_docking_core: - tag: release/jazzy/opennav_docking_core/1.3.9-1 + tag: release/jazzy/opennav_docking_core/1.3.10-1 url: https://github.com/SteveMacenski/navigation2-release.git - version: 1.3.9 + version: 1.3.10 openni2_camera: tag: release/jazzy/openni2_camera/2.2.2-1 url: https://github.com/ros2-gbp/openni2_camera-release.git @@ -3979,6 +4055,18 @@ openvdb_vendor: tag: release/jazzy/openvdb_vendor/2.5.5-1 url: https://github.com/SteveMacenski/spatio_temporal_voxel_layer-release.git version: 2.5.5 +orbbec_camera: + tag: release/jazzy/orbbec_camera/1.5.14-1 + url: https://github.com/orbbec/orbbec_camera_v1-release.git + version: 1.5.14 +orbbec_camera_msgs: + tag: release/jazzy/orbbec_camera_msgs/1.5.14-1 + url: https://github.com/orbbec/orbbec_camera_v1-release.git + version: 1.5.14 +orbbec_description: + tag: release/jazzy/orbbec_description/1.5.14-1 + url: https://github.com/orbbec/orbbec_camera_v1-release.git + version: 1.5.14 orocos_kdl_vendor: tag: release/jazzy/orocos_kdl_vendor/0.5.1-2 url: https://github.com/ros2-gbp/orocos_kdl_vendor-release.git @@ -4024,13 +4112,13 @@ pal_statistics_msgs: url: https://github.com/ros2-gbp/pal_statistics-release.git version: 2.7.0 pangolin: - tag: release/jazzy/pangolin/0.9.3-1 + tag: release/jazzy/pangolin/0.9.4-1 url: https://github.com/ros2-gbp/Pangolin-release.git - version: 0.9.3 + version: 0.9.4 parallel_gripper_controller: - tag: release/jazzy/parallel_gripper_controller/4.32.0-1 + tag: release/jazzy/parallel_gripper_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 parameter_traits: tag: release/jazzy/parameter_traits/0.5.0-1 url: https://github.com/ros2-gbp/generate_parameter_library-release.git @@ -4152,9 +4240,9 @@ picknik_twist_controller: url: https://github.com/ros2-gbp/picknik_controllers-release.git version: 0.0.4 pid_controller: - tag: release/jazzy/pid_controller/4.32.0-1 + tag: release/jazzy/pid_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 pilz_industrial_motion_planner: tag: release/jazzy/pilz_industrial_motion_planner/2.12.3-1 url: https://github.com/ros2-gbp/moveit2-release.git @@ -4164,9 +4252,9 @@ pilz_industrial_motion_planner_testutils: url: https://github.com/ros2-gbp/moveit2-release.git version: 2.12.3 pinocchio: - tag: release/jazzy/pinocchio/3.6.0-1 + tag: release/jazzy/pinocchio/3.8.0-1 url: https://github.com/ros2-gbp/pinocchio-release.git - version: 3.6.0 + version: 3.8.0 plansys2_bringup: tag: release/jazzy/plansys2_bringup/2.0.18-1 url: https://github.com/ros2-gbp/ros2_planning_system-release.git @@ -4227,10 +4315,30 @@ plansys2_tools: tag: release/jazzy/plansys2_tools/2.0.18-1 url: https://github.com/ros2-gbp/ros2_planning_system-release.git version: 2.0.18 +play_motion2: + tag: release/jazzy/play_motion2/1.8.0-1 + url: https://github.com/pal-gbp/play_motion2-release.git + version: 1.8.0 +play_motion2_cli: + tag: release/jazzy/play_motion2_cli/1.8.0-1 + url: https://github.com/pal-gbp/play_motion2-release.git + version: 1.8.0 +play_motion2_msgs: + tag: release/jazzy/play_motion2_msgs/1.8.0-1 + url: https://github.com/pal-gbp/play_motion2-release.git + version: 1.8.0 +play_motion_builder: + tag: release/jazzy/play_motion_builder/1.4.0-1 + url: https://github.com/ros2-gbp/play_motion_builder-release.git + version: 1.4.0 +play_motion_builder_msgs: + tag: release/jazzy/play_motion_builder_msgs/1.4.0-1 + url: https://github.com/ros2-gbp/play_motion_builder-release.git + version: 1.4.0 plotjuggler: - tag: release/jazzy/plotjuggler/3.10.11-1 + tag: release/jazzy/plotjuggler/3.13.2-1 url: https://github.com/ros2-gbp/plotjuggler-release.git - version: 3.10.11 + version: 3.13.2 plotjuggler_msgs: tag: release/jazzy/plotjuggler_msgs/0.2.3-5 url: https://github.com/ros2-gbp/plotjuggler_msgs-release.git @@ -4240,29 +4348,29 @@ plotjuggler_ros: url: https://github.com/ros2-gbp/plotjuggler-ros-plugins-release.git version: 2.3.0 pluginlib: - tag: release/jazzy/pluginlib/5.4.2-2 + tag: release/jazzy/pluginlib/5.4.3-1 url: https://github.com/ros2-gbp/pluginlib-release.git - version: 5.4.2 + version: 5.4.3 point_cloud_interfaces: - tag: release/jazzy/point_cloud_interfaces/4.0.1-1 + tag: release/jazzy/point_cloud_interfaces/4.0.2-1 url: https://github.com/ros2-gbp/point_cloud_transport_plugins-release.git - version: 4.0.1 + version: 4.0.2 point_cloud_msg_wrapper: tag: release/jazzy/point_cloud_msg_wrapper/1.0.7-5 url: https://github.com/ros2-gbp/point_cloud_msg_wrapper-release.git version: 1.0.7 point_cloud_transport: - tag: release/jazzy/point_cloud_transport/4.0.4-1 + tag: release/jazzy/point_cloud_transport/4.0.5-1 url: https://github.com/ros2-gbp/point_cloud_transport-release.git - version: 4.0.4 + version: 4.0.5 point_cloud_transport_plugins: - tag: release/jazzy/point_cloud_transport_plugins/4.0.1-1 + tag: release/jazzy/point_cloud_transport_plugins/4.0.2-1 url: https://github.com/ros2-gbp/point_cloud_transport_plugins-release.git - version: 4.0.1 + version: 4.0.2 point_cloud_transport_py: - tag: release/jazzy/point_cloud_transport_py/4.0.4-1 + tag: release/jazzy/point_cloud_transport_py/4.0.5-1 url: https://github.com/ros2-gbp/point_cloud_transport-release.git - version: 4.0.4 + version: 4.0.5 point_cloud_transport_tutorial: tag: release/jazzy/point_cloud_transport_tutorial/0.0.2-2 url: https://github.com/ros2-gbp/point_cloud_transport_tutorial-release.git @@ -4292,17 +4400,17 @@ popf: url: https://github.com/ros2-gbp/popf-release.git version: 0.0.17 pose_broadcaster: - tag: release/jazzy/pose_broadcaster/4.32.0-1 + tag: release/jazzy/pose_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 pose_cov_ops: tag: release/jazzy/pose_cov_ops/0.4.0-1 url: https://github.com/ros2-gbp/pose_cov_ops-release.git version: 0.4.0 position_controllers: - tag: release/jazzy/position_controllers/4.32.0-1 + tag: release/jazzy/position_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 protobuf_comm: tag: release/jazzy/protobuf_comm/0.9.3-1 url: https://github.com/ros2-gbp/protobuf_comm-release.git @@ -4368,9 +4476,9 @@ python_orocos_kdl_vendor: url: https://github.com/ros2-gbp/orocos_kdl_vendor-release.git version: 0.5.1 python_qt_binding: - tag: release/jazzy/python_qt_binding/2.2.1-1 + tag: release/jazzy/python_qt_binding/2.2.2-1 url: https://github.com/ros2-gbp/python_qt_binding-release.git - version: 2.2.1 + version: 2.2.2 qml_ros2_plugin: tag: release/jazzy/qml_ros2_plugin/1.25.2-2 url: https://github.com/ros2-gbp/qml_ros2_plugin-release.git @@ -4432,9 +4540,9 @@ random_numbers: url: https://github.com/ros2-gbp/random_numbers-release.git version: 2.0.1 range_sensor_broadcaster: - tag: release/jazzy/range_sensor_broadcaster/4.32.0-1 + tag: release/jazzy/range_sensor_broadcaster/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 raspimouse: tag: release/jazzy/raspimouse/2.0.0-1 url: https://github.com/ros2-gbp/raspimouse2-release.git @@ -4520,21 +4628,21 @@ rcgcrd_spl_4_conversion: url: https://github.com/ros2-gbp/game_controller_spl-release.git version: 4.1.0 rcl: - tag: release/jazzy/rcl/9.2.7-1 + tag: release/jazzy/rcl/9.2.8-1 url: https://github.com/ros2-gbp/rcl-release.git - version: 9.2.7 + version: 9.2.8 rcl_action: - tag: release/jazzy/rcl_action/9.2.7-1 + tag: release/jazzy/rcl_action/9.2.8-1 url: https://github.com/ros2-gbp/rcl-release.git - version: 9.2.7 + version: 9.2.8 rcl_interfaces: tag: release/jazzy/rcl_interfaces/2.0.3-1 url: https://github.com/ros2-gbp/rcl_interfaces-release.git version: 2.0.3 rcl_lifecycle: - tag: release/jazzy/rcl_lifecycle/9.2.7-1 + tag: release/jazzy/rcl_lifecycle/9.2.8-1 url: https://github.com/ros2-gbp/rcl-release.git - version: 9.2.7 + version: 9.2.8 rcl_logging_interface: tag: release/jazzy/rcl_logging_interface/3.1.1-1 url: https://github.com/ros2-gbp/rcl_logging-release.git @@ -4548,9 +4656,9 @@ rcl_logging_spdlog: url: https://github.com/ros2-gbp/rcl_logging-release.git version: 3.1.1 rcl_yaml_param_parser: - tag: release/jazzy/rcl_yaml_param_parser/9.2.7-1 + tag: release/jazzy/rcl_yaml_param_parser/9.2.8-1 url: https://github.com/ros2-gbp/rcl-release.git - version: 9.2.7 + version: 9.2.8 rclc: tag: release/jazzy/rclc/6.1.0-3 url: https://github.com/ros2-gbp/rclc-release.git @@ -4568,29 +4676,29 @@ rclc_parameter: url: https://github.com/ros2-gbp/rclc-release.git version: 6.1.0 rclcpp: - tag: release/jazzy/rclcpp/28.1.12-1 + tag: release/jazzy/rclcpp/28.1.13-1 url: https://github.com/ros2-gbp/rclcpp-release.git - version: 28.1.12 + version: 28.1.13 rclcpp_action: - tag: release/jazzy/rclcpp_action/28.1.12-1 + tag: release/jazzy/rclcpp_action/28.1.13-1 url: https://github.com/ros2-gbp/rclcpp-release.git - version: 28.1.12 + version: 28.1.13 rclcpp_cascade_lifecycle: tag: release/jazzy/rclcpp_cascade_lifecycle/2.0.0-3 url: https://github.com/ros2-gbp/cascade_lifecycle-release.git version: 2.0.0 rclcpp_components: - tag: release/jazzy/rclcpp_components/28.1.12-1 + tag: release/jazzy/rclcpp_components/28.1.13-1 url: https://github.com/ros2-gbp/rclcpp-release.git - version: 28.1.12 + version: 28.1.13 rclcpp_lifecycle: - tag: release/jazzy/rclcpp_lifecycle/28.1.12-1 + tag: release/jazzy/rclcpp_lifecycle/28.1.13-1 url: https://github.com/ros2-gbp/rclcpp-release.git - version: 28.1.12 + version: 28.1.13 rclpy: - tag: release/jazzy/rclpy/7.1.5-1 + tag: release/jazzy/rclpy/7.1.6-1 url: https://github.com/ros2-gbp/rclpy-release.git - version: 7.1.5 + version: 7.1.6 rclpy_message_converter: tag: release/jazzy/rclpy_message_converter/2.0.1-4 url: https://github.com/ros2-gbp/rospy_message_converter-release.git @@ -4656,13 +4764,17 @@ realsense2_description: url: https://github.com/ros2-gbp/realsense-ros-release.git version: 4.56.4 realtime_tools: - tag: release/jazzy/realtime_tools/3.9.0-1 + tag: release/jazzy/realtime_tools/3.10.0-1 url: https://github.com/ros2-gbp/realtime_tools-release.git - version: 3.9.0 + version: 3.10.0 reductstore_agent: tag: release/jazzy/reductstore_agent/0.2.0-1 url: https://github.com/ros2-gbp/reductstore_agent-release.git version: 0.2.0 +replay_testing: + tag: release/jazzy/replay_testing/0.0.3-1 + url: https://github.com/ros2-gbp/replay_testing-release.git + version: 0.0.3 resource_retriever: tag: release/jazzy/resource_retriever/3.4.4-1 url: https://github.com/ros2-gbp/resource_retriever-release.git @@ -4671,6 +4783,10 @@ rig_reconfigure: tag: release/jazzy/rig_reconfigure/1.6.0-1 url: https://github.com/ros2-gbp/rig_reconfigure-release.git version: 1.6.0 +rko_lio: + tag: release/jazzy/rko_lio/0.1.6-1 + url: https://github.com/ros2-gbp/rko_lio-release.git + version: 0.1.6 rmf_api_msgs: tag: release/jazzy/rmf_api_msgs/0.3.1-1 url: https://github.com/ros2-gbp/rmf_api_msgs-release.git @@ -4864,13 +4980,13 @@ rmw: url: https://github.com/ros2-gbp/rmw-release.git version: 7.3.2 rmw_connextdds: - tag: release/jazzy/rmw_connextdds/0.22.1-1 + tag: release/jazzy/rmw_connextdds/0.22.2-1 url: https://github.com/ros2-gbp/rmw_connextdds-release.git - version: 0.22.1 + version: 0.22.2 rmw_connextdds_common: - tag: release/jazzy/rmw_connextdds_common/0.22.1-1 + tag: release/jazzy/rmw_connextdds_common/0.22.2-1 url: https://github.com/ros2-gbp/rmw_connextdds-release.git - version: 0.22.1 + version: 0.22.2 rmw_cyclonedds_cpp: tag: release/jazzy/rmw_cyclonedds_cpp/2.2.3-1 url: https://github.com/ros2-gbp/rmw_cyclonedds-release.git @@ -4908,13 +5024,13 @@ rmw_implementation_cmake: url: https://github.com/ros2-gbp/rmw-release.git version: 7.3.2 rmw_stats_shim: - tag: release/jazzy/rmw_stats_shim/0.1.1-1 + tag: release/jazzy/rmw_stats_shim/0.2.3-1 url: https://github.com/ros2-gbp/graph_monitor-release.git - version: 0.1.1 + version: 0.2.3 rmw_zenoh_cpp: - tag: release/jazzy/rmw_zenoh_cpp/0.2.7-1 + tag: release/jazzy/rmw_zenoh_cpp/0.2.8-1 url: https://github.com/ros2-gbp/rmw_zenoh-release.git - version: 0.2.7 + version: 0.2.8 robot_calibration: tag: release/jazzy/robot_calibration/0.10.0-1 url: https://github.com/ros2-gbp/robot_calibration-release.git @@ -4952,25 +5068,29 @@ robotraconteur_companion: url: https://github.com/ros2-gbp/robotraconteur_companion-release.git version: 0.4.2 ros2_control: - tag: release/jazzy/ros2_control/4.37.0-1 + tag: release/jazzy/ros2_control/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 ros2_control_cmake: - tag: release/jazzy/ros2_control_cmake/0.2.1-1 + tag: release/jazzy/ros2_control_cmake/0.3.0-1 url: https://github.com/ros2-gbp/ros2_control_cmake-release.git - version: 0.2.1 + version: 0.3.0 ros2_control_test_assets: - tag: release/jazzy/ros2_control_test_assets/4.37.0-1 + tag: release/jazzy/ros2_control_test_assets/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 ros2_controllers: - tag: release/jazzy/ros2_controllers/4.32.0-1 + tag: release/jazzy/ros2_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 ros2_controllers_test_nodes: - tag: release/jazzy/ros2_controllers_test_nodes/4.32.0-1 + tag: release/jazzy/ros2_controllers_test_nodes/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 +ros2_fmt_logger: + tag: release/jazzy/ros2_fmt_logger/1.0.0-1 + url: https://github.com/ros2-gbp/ros2_fmt_logger-release.git + version: 1.0.0 ros2_socketcan: tag: release/jazzy/ros2_socketcan/1.3.0-1 url: https://github.com/ros2-gbp/ros2_socketcan-release.git @@ -5008,9 +5128,9 @@ ros2component: url: https://github.com/ros2-gbp/ros2cli-release.git version: 0.32.6 ros2controlcli: - tag: release/jazzy/ros2controlcli/4.37.0-1 + tag: release/jazzy/ros2controlcli/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 ros2doctor: tag: release/jazzy/ros2doctor/0.32.6-1 url: https://github.com/ros2-gbp/ros2cli-release.git @@ -5059,6 +5179,10 @@ ros2pkg: tag: release/jazzy/ros2pkg/0.32.6-1 url: https://github.com/ros2-gbp/ros2cli-release.git version: 0.32.6 +ros2plugin: + tag: release/jazzy/ros2plugin/5.4.3-1 + url: https://github.com/ros2-gbp/pluginlib-release.git + version: 5.4.3 ros2run: tag: release/jazzy/ros2run/0.32.6-1 url: https://github.com/ros2-gbp/ros2cli-release.git @@ -5252,13 +5376,13 @@ rosbridge_test_msgs: url: https://github.com/ros2-gbp/rosbridge_suite-release.git version: 2.3.0 rosgraph_monitor: - tag: release/jazzy/rosgraph_monitor/0.1.1-1 + tag: release/jazzy/rosgraph_monitor/0.2.3-1 url: https://github.com/ros2-gbp/graph_monitor-release.git - version: 0.1.1 + version: 0.2.3 rosgraph_monitor_msgs: - tag: release/jazzy/rosgraph_monitor_msgs/0.1.1-1 + tag: release/jazzy/rosgraph_monitor_msgs/0.2.3-1 url: https://github.com/ros2-gbp/graph_monitor-release.git - version: 0.1.1 + version: 0.2.3 rosgraph_msgs: tag: release/jazzy/rosgraph_msgs/2.0.3-1 url: https://github.com/ros2-gbp/rcl_interfaces-release.git @@ -5312,9 +5436,9 @@ rosidl_generator_dds_idl: url: https://github.com/ros2-gbp/rosidl_dds-release.git version: 0.11.1 rosidl_generator_py: - tag: release/jazzy/rosidl_generator_py/0.22.1-1 + tag: release/jazzy/rosidl_generator_py/0.22.2-1 url: https://github.com/ros2-gbp/rosidl_python-release.git - version: 0.22.1 + version: 0.22.2 rosidl_generator_type_description: tag: release/jazzy/rosidl_generator_type_description/4.6.6-1 url: https://github.com/ros2-gbp/rosidl-release.git @@ -5436,9 +5560,9 @@ rpyutils: url: https://github.com/ros2-gbp/rpyutils-release.git version: 0.4.2 rqt: - tag: release/jazzy/rqt/1.6.0-2 + tag: release/jazzy/rqt/1.6.2-2 url: https://github.com/ros2-gbp/rqt-release.git - version: 1.6.0 + version: 1.6.2 rqt_action: tag: release/jazzy/rqt_action/2.2.0-3 url: https://github.com/ros2-gbp/rqt_action-release.git @@ -5460,9 +5584,9 @@ rqt_console: url: https://github.com/ros2-gbp/rqt_console-release.git version: 2.2.1 rqt_controller_manager: - tag: release/jazzy/rqt_controller_manager/4.37.0-1 + tag: release/jazzy/rqt_controller_manager/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 rqt_dotgraph: tag: release/jazzy/rqt_dotgraph/0.0.5-1 url: https://github.com/ros2-gbp/rqt_dotgraph-release.git @@ -5476,17 +5600,17 @@ rqt_graph: url: https://github.com/ros2-gbp/rqt_graph-release.git version: 1.5.5 rqt_gui: - tag: release/jazzy/rqt_gui/1.6.0-2 + tag: release/jazzy/rqt_gui/1.6.2-2 url: https://github.com/ros2-gbp/rqt-release.git - version: 1.6.0 + version: 1.6.2 rqt_gui_cpp: - tag: release/jazzy/rqt_gui_cpp/1.6.0-2 + tag: release/jazzy/rqt_gui_cpp/1.6.2-2 url: https://github.com/ros2-gbp/rqt-release.git - version: 1.6.0 + version: 1.6.2 rqt_gui_py: - tag: release/jazzy/rqt_gui_py/1.6.0-2 + tag: release/jazzy/rqt_gui_py/1.6.2-2 url: https://github.com/ros2-gbp/rqt-release.git - version: 1.6.0 + version: 1.6.2 rqt_image_overlay: tag: release/jazzy/rqt_image_overlay/0.4.0-1 url: https://github.com/ros2-gbp/rqt_image_overlay-release.git @@ -5500,9 +5624,9 @@ rqt_image_view: url: https://github.com/ros2-gbp/rqt_image_view-release.git version: 1.3.0 rqt_joint_trajectory_controller: - tag: release/jazzy/rqt_joint_trajectory_controller/4.32.0-1 + tag: release/jazzy/rqt_joint_trajectory_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 rqt_moveit: tag: release/jazzy/rqt_moveit/1.0.1-5 url: https://github.com/ros2-gbp/rqt_moveit-release.git @@ -5511,6 +5635,10 @@ rqt_msg: tag: release/jazzy/rqt_msg/1.5.1-3 url: https://github.com/ros2-gbp/rqt_msg-release.git version: 1.5.1 +rqt_play_motion_builder: + tag: release/jazzy/rqt_play_motion_builder/1.4.0-1 + url: https://github.com/ros2-gbp/play_motion_builder-release.git + version: 1.4.0 rqt_plot: tag: release/jazzy/rqt_plot/1.4.4-1 url: https://github.com/ros2-gbp/rqt_plot-release.git @@ -5520,13 +5648,13 @@ rqt_publisher: url: https://github.com/ros2-gbp/rqt_publisher-release.git version: 1.7.2 rqt_py_common: - tag: release/jazzy/rqt_py_common/1.6.0-2 + tag: release/jazzy/rqt_py_common/1.6.2-2 url: https://github.com/ros2-gbp/rqt-release.git - version: 1.6.0 + version: 1.6.2 rqt_py_console: - tag: release/jazzy/rqt_py_console/1.2.2-3 + tag: release/jazzy/rqt_py_console/1.2.3-1 url: https://github.com/ros2-gbp/rqt_py_console-release.git - version: 1.2.2 + version: 1.2.3 rqt_reconfigure: tag: release/jazzy/rqt_reconfigure/1.6.2-3 url: https://github.com/ros2-gbp/rqt_reconfigure-release.git @@ -5564,9 +5692,9 @@ rqt_tf_tree: url: https://github.com/ros2-gbp/rqt_tf_tree-release.git version: 1.0.5 rqt_topic: - tag: release/jazzy/rqt_topic/1.7.3-1 + tag: release/jazzy/rqt_topic/1.7.4-1 url: https://github.com/ros2-gbp/rqt_topic-release.git - version: 1.7.3 + version: 1.7.4 rsl: tag: release/jazzy/rsl/1.2.0-1 url: https://github.com/ros2-gbp/RSL-release.git @@ -5652,9 +5780,9 @@ rtcm_msgs: url: https://github.com/ros2-gbp/rtcm_msgs-release.git version: 1.1.6 rti_connext_dds_cmake_module: - tag: release/jazzy/rti_connext_dds_cmake_module/0.22.1-1 + tag: release/jazzy/rti_connext_dds_cmake_module/0.22.2-1 url: https://github.com/ros2-gbp/rmw_connextdds-release.git - version: 0.22.1 + version: 0.22.2 rtsp_image_transport: tag: release/jazzy/rtsp_image_transport/2.0.1-1 url: https://github.com/ros2-gbp/rtsp_image_transport-release.git @@ -5668,9 +5796,9 @@ ruckig: url: https://github.com/ros2-gbp/ruckig-release.git version: 0.9.2 rviz2: - tag: release/jazzy/rviz2/14.1.15-1 + tag: release/jazzy/rviz2/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_2d_overlay_msgs: tag: release/jazzy/rviz_2d_overlay_msgs/1.3.1-1 url: https://github.com/ros2-gbp/rviz_2d_overlay_plugins-release.git @@ -5680,49 +5808,53 @@ rviz_2d_overlay_plugins: url: https://github.com/ros2-gbp/rviz_2d_overlay_plugins-release.git version: 1.3.1 rviz_assimp_vendor: - tag: release/jazzy/rviz_assimp_vendor/14.1.15-1 + tag: release/jazzy/rviz_assimp_vendor/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_common: - tag: release/jazzy/rviz_common/14.1.15-1 + tag: release/jazzy/rviz_common/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_default_plugins: - tag: release/jazzy/rviz_default_plugins/14.1.15-1 + tag: release/jazzy/rviz_default_plugins/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_imu_plugin: tag: release/jazzy/rviz_imu_plugin/2.1.5-1 url: https://github.com/ros2-gbp/imu_tools-release.git version: 2.1.5 +rviz_marker_tools: + tag: release/jazzy/rviz_marker_tools/0.1.4-1 + url: https://github.com/ros2-gbp/moveit_task_constructor-release.git + version: 0.1.4 rviz_ogre_vendor: - tag: release/jazzy/rviz_ogre_vendor/14.1.15-1 + tag: release/jazzy/rviz_ogre_vendor/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_rendering: - tag: release/jazzy/rviz_rendering/14.1.15-1 + tag: release/jazzy/rviz_rendering/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_rendering_tests: - tag: release/jazzy/rviz_rendering_tests/14.1.15-1 + tag: release/jazzy/rviz_rendering_tests/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_satellite: tag: release/jazzy/rviz_satellite/4.2.0-1 url: https://github.com/nobleo/rviz_satellite-release.git version: 4.2.0 rviz_visual_testing_framework: - tag: release/jazzy/rviz_visual_testing_framework/14.1.15-1 + tag: release/jazzy/rviz_visual_testing_framework/14.1.16-1 url: https://github.com/ros2-gbp/rviz-release.git - version: 14.1.15 + version: 14.1.16 rviz_visual_tools: tag: release/jazzy/rviz_visual_tools/4.1.4-4 url: https://github.com/ros2-gbp/rviz_visual_tools-release.git version: 4.1.4 sbg_driver: - tag: release/jazzy/sbg_driver/3.2.0-1 + tag: release/jazzy/sbg_driver/3.3.0-1 url: https://github.com/SBG-Systems/sbg_ros2-release.git - version: 3.2.0 + version: 3.3.0 scenario_execution: tag: release/jazzy/scenario_execution/1.3.0-1 url: https://github.com/ros2-gbp/scenario_execution-release.git @@ -5840,9 +5972,9 @@ sick_safevisionary_tests: url: https://github.com/ros2-gbp/sick_safevisionary_ros2-release.git version: 1.0.3 sick_scan_xd: - tag: release/jazzy/sick_scan_xd/3.7.0-1 + tag: release/jazzy/sick_scan_xd/3.8.0-1 url: https://github.com/ros2-gbp/sick_scan_xd-release.git - version: 3.7.0 + version: 3.8.0 simple_actions: tag: release/jazzy/simple_actions/0.4.0-1 url: https://github.com/ros2-gbp/simple_actions-release.git @@ -5892,9 +6024,9 @@ smach_ros: url: https://github.com/ros2-gbp/executive_smach-release.git version: 3.0.3 small_gicp_vendor: - tag: release/jazzy/small_gicp_vendor/2.0.3-1 + tag: release/jazzy/small_gicp_vendor/2.0.4-1 url: https://github.com/ros2-gbp/multisensor_calibration-release.git - version: 2.0.3 + version: 2.0.4 smclib: tag: release/jazzy/smclib/4.1.2-1 url: https://github.com/ros2-gbp/bond_core-release.git @@ -6000,9 +6132,9 @@ std_srvs: url: https://github.com/ros2-gbp/common_interfaces-release.git version: 5.3.6 steering_controllers_library: - tag: release/jazzy/steering_controllers_library/4.32.0-1 + tag: release/jazzy/steering_controllers_library/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 steering_functions: tag: release/jazzy/steering_functions/0.3.0-1 url: https://github.com/ros2-gbp/steering_functions-release.git @@ -6132,57 +6264,57 @@ test_msgs: url: https://github.com/ros2-gbp/rcl_interfaces-release.git version: 2.0.3 tf2: - tag: release/jazzy/tf2/0.36.14-1 + tag: release/jazzy/tf2/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_2d: tag: release/jazzy/tf2_2d/1.4.1-1 url: https://github.com/ros2-gbp/tf2_2d-release.git version: 1.4.1 tf2_bullet: - tag: release/jazzy/tf2_bullet/0.36.14-1 + tag: release/jazzy/tf2_bullet/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_eigen: - tag: release/jazzy/tf2_eigen/0.36.14-1 + tag: release/jazzy/tf2_eigen/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_eigen_kdl: - tag: release/jazzy/tf2_eigen_kdl/0.36.14-1 + tag: release/jazzy/tf2_eigen_kdl/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_geometry_msgs: - tag: release/jazzy/tf2_geometry_msgs/0.36.14-1 + tag: release/jazzy/tf2_geometry_msgs/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_kdl: - tag: release/jazzy/tf2_kdl/0.36.14-1 + tag: release/jazzy/tf2_kdl/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_msgs: - tag: release/jazzy/tf2_msgs/0.36.14-1 + tag: release/jazzy/tf2_msgs/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_py: - tag: release/jazzy/tf2_py/0.36.14-1 + tag: release/jazzy/tf2_py/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_ros: - tag: release/jazzy/tf2_ros/0.36.14-1 + tag: release/jazzy/tf2_ros/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_ros_py: - tag: release/jazzy/tf2_ros_py/0.36.14-1 + tag: release/jazzy/tf2_ros_py/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_sensor_msgs: - tag: release/jazzy/tf2_sensor_msgs/0.36.14-1 + tag: release/jazzy/tf2_sensor_msgs/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_tools: - tag: release/jazzy/tf2_tools/0.36.14-1 + tag: release/jazzy/tf2_tools/0.36.15-1 url: https://github.com/ros2-gbp/geometry2-release.git - version: 0.36.14 + version: 0.36.15 tf2_web_republisher: tag: release/jazzy/tf2_web_republisher/1.0.0-1 url: https://github.com/ros2-gbp/tf2_web_republisher-release.git @@ -6227,10 +6359,6 @@ tlsf_cpp: tag: release/jazzy/tlsf_cpp/0.17.1-3 url: https://github.com/ros2-gbp/realtime_support-release.git version: 0.17.1 -topic_based_ros2_control: - tag: release/jazzy/topic_based_ros2_control/0.3.0-4 - url: https://github.com/ros2-gbp/topic_based_ros2_control-release.git - version: 0.3.0 topic_monitor: tag: release/jazzy/topic_monitor/0.33.7-1 url: https://github.com/ros2-gbp/demos-release.git @@ -6296,29 +6424,29 @@ trajectory_msgs: url: https://github.com/ros2-gbp/common_interfaces-release.git version: 5.3.6 transmission_interface: - tag: release/jazzy/transmission_interface/4.37.0-1 + tag: release/jazzy/transmission_interface/4.38.0-1 url: https://github.com/ros2-gbp/ros2_control-release.git - version: 4.37.0 + version: 4.38.0 tricycle_controller: - tag: release/jazzy/tricycle_controller/4.32.0-1 + tag: release/jazzy/tricycle_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 tricycle_steering_controller: - tag: release/jazzy/tricycle_steering_controller/4.32.0-1 + tag: release/jazzy/tricycle_steering_controller/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 tsid: - tag: release/jazzy/tsid/1.8.0-1 + tag: release/jazzy/tsid/1.9.0-1 url: https://github.com/ros2-gbp/tsid-release.git - version: 1.8.0 + version: 1.9.0 turbojpeg_compressed_image_transport: tag: release/jazzy/turbojpeg_compressed_image_transport/0.2.1-5 url: https://github.com/ros2-gbp/turbojpeg_compressed_image_transport-release.git version: 0.2.1 turtle_nest: - tag: release/jazzy/turtle_nest/1.2.0-1 + tag: release/jazzy/turtle_nest/1.2.1-1 url: https://github.com/ros2-gbp/turtle_nest-release.git - version: 1.2.0 + version: 1.2.1 turtle_tf2_cpp: tag: release/jazzy/turtle_tf2_cpp/0.5.0-1 url: https://github.com/ros2-gbp/geometry_tutorials-release.git @@ -6660,49 +6788,49 @@ unique_identifier_msgs: url: https://github.com/ros2-gbp/unique_identifier_msgs-release.git version: 2.5.0 ur: - tag: release/jazzy/ur/3.4.0-1 + tag: release/jazzy/ur/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur10_inverse_dynamics_solver: tag: release/jazzy/ur10_inverse_dynamics_solver/2.0.0-1 url: https://github.com/ros2-gbp/inverse_dynamics_solver-release.git version: 2.0.0 ur_calibration: - tag: release/jazzy/ur_calibration/3.4.0-1 + tag: release/jazzy/ur_calibration/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur_client_library: - tag: release/jazzy/ur_client_library/2.3.0-1 + tag: release/jazzy/ur_client_library/2.4.0-1 url: https://github.com/ros2-gbp/Universal_Robots_Client_Library-release.git - version: 2.3.0 + version: 2.4.0 ur_controllers: - tag: release/jazzy/ur_controllers/3.4.0-1 + tag: release/jazzy/ur_controllers/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur_dashboard_msgs: - tag: release/jazzy/ur_dashboard_msgs/3.4.0-1 + tag: release/jazzy/ur_dashboard_msgs/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur_description: - tag: release/jazzy/ur_description/3.3.0-1 + tag: release/jazzy/ur_description/3.5.0-1 url: https://github.com/ros2-gbp/ur_description-release.git - version: 3.3.0 + version: 3.5.0 ur_moveit_config: - tag: release/jazzy/ur_moveit_config/3.4.0-1 + tag: release/jazzy/ur_moveit_config/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur_msgs: tag: release/jazzy/ur_msgs/2.3.0-1 url: https://github.com/ros2-gbp/ur_msgs-release.git version: 2.3.0 ur_robot_driver: - tag: release/jazzy/ur_robot_driver/3.4.0-1 + tag: release/jazzy/ur_robot_driver/3.5.0-1 url: https://github.com/ros2-gbp/Universal_Robots_ROS2_Driver-release.git - version: 3.4.0 + version: 3.5.0 ur_simulation_gz: - tag: release/jazzy/ur_simulation_gz/2.4.0-1 + tag: release/jazzy/ur_simulation_gz/2.5.0-1 url: https://github.com/ros2-gbp/ur_simulation_gz-release.git - version: 2.4.0 + version: 2.5.0 urdf: tag: release/jazzy/urdf/2.10.0-3 url: https://github.com/ros2-gbp/urdf-release.git @@ -6752,9 +6880,9 @@ v4l2_camera: url: https://github.com/ros2-gbp/ros2_v4l2_camera-release.git version: 0.7.1 velocity_controllers: - tag: release/jazzy/velocity_controllers/4.32.0-1 + tag: release/jazzy/velocity_controllers/4.33.1-1 url: https://github.com/ros2-gbp/ros2_controllers-release.git - version: 4.32.0 + version: 4.33.1 velodyne: tag: release/jazzy/velodyne/2.5.1-1 url: https://github.com/ros2-gbp/velodyne-release.git @@ -6904,33 +7032,33 @@ xacro: url: https://github.com/ros2-gbp/xacro-release.git version: 2.1.1 yaets: - tag: release/jazzy/yaets/0.0.2-1 + tag: release/jazzy/yaets/1.0.4-1 url: https://github.com/fmrico/yaets-release.git - version: 0.0.2 + version: 1.0.4 yaml_cpp_vendor: tag: release/jazzy/yaml_cpp_vendor/9.0.1-1 url: https://github.com/ros2-gbp/yaml_cpp_vendor-release.git version: 9.0.1 yasmin: - tag: release/jazzy/yasmin/3.4.0-1 + tag: release/jazzy/yasmin/3.5.1-1 url: https://github.com/ros2-gbp/yasmin-release.git - version: 3.4.0 + version: 3.5.1 yasmin_demos: - tag: release/jazzy/yasmin_demos/3.4.0-1 + tag: release/jazzy/yasmin_demos/3.5.1-1 url: https://github.com/ros2-gbp/yasmin-release.git - version: 3.4.0 + version: 3.5.1 yasmin_msgs: - tag: release/jazzy/yasmin_msgs/3.4.0-1 + tag: release/jazzy/yasmin_msgs/3.5.1-1 url: https://github.com/ros2-gbp/yasmin-release.git - version: 3.4.0 + version: 3.5.1 yasmin_ros: - tag: release/jazzy/yasmin_ros/3.4.0-1 + tag: release/jazzy/yasmin_ros/3.5.1-1 url: https://github.com/ros2-gbp/yasmin-release.git - version: 3.4.0 + version: 3.5.1 yasmin_viewer: - tag: release/jazzy/yasmin_viewer/3.4.0-1 + tag: release/jazzy/yasmin_viewer/3.5.1-1 url: https://github.com/ros2-gbp/yasmin-release.git - version: 3.4.0 + version: 3.5.1 zbar_ros: tag: release/jazzy/zbar_ros/0.6.0-1 url: https://github.com/ros2-gbp/zbar_ros-release.git @@ -6940,25 +7068,25 @@ zbar_ros_interfaces: url: https://github.com/ros2-gbp/zbar_ros-release.git version: 0.6.0 zed_msgs: - tag: release/jazzy/zed_msgs/5.0.1-2 + tag: release/jazzy/zed_msgs/5.1.1-1 url: https://github.com/ros2-gbp/zed-ros2-interfaces-release.git - version: 5.0.1 + version: 5.1.1 zenoh_bridge_dds: tag: release/jazzy/zenoh_bridge_dds/0.5.0-5 url: https://github.com/ros2-gbp/zenoh_bridge_dds-release.git version: 0.5.0 zenoh_cpp_vendor: - tag: release/jazzy/zenoh_cpp_vendor/0.2.7-1 + tag: release/jazzy/zenoh_cpp_vendor/0.2.8-1 url: https://github.com/ros2-gbp/rmw_zenoh-release.git - version: 0.2.7 + version: 0.2.8 zenoh_security_tools: - tag: release/jazzy/zenoh_security_tools/0.2.7-1 + tag: release/jazzy/zenoh_security_tools/0.2.8-1 url: https://github.com/ros2-gbp/rmw_zenoh-release.git - version: 0.2.7 + version: 0.2.8 zlib_point_cloud_transport: - tag: release/jazzy/zlib_point_cloud_transport/4.0.1-1 + tag: release/jazzy/zlib_point_cloud_transport/4.0.2-1 url: https://github.com/ros2-gbp/point_cloud_transport_plugins-release.git - version: 4.0.1 + version: 4.0.2 zmqpp_vendor: tag: release/jazzy/zmqpp_vendor/0.0.2-4 url: https://github.com/ros2-gbp/zmqpp_vendor-release.git @@ -6968,9 +7096,9 @@ zstd_image_transport: url: https://github.com/ros2-gbp/image_transport_plugins-release.git version: 4.0.6 zstd_point_cloud_transport: - tag: release/jazzy/zstd_point_cloud_transport/4.0.1-1 + tag: release/jazzy/zstd_point_cloud_transport/4.0.2-1 url: https://github.com/ros2-gbp/point_cloud_transport_plugins-release.git - version: 4.0.1 + version: 4.0.2 zstd_vendor: tag: release/jazzy/zstd_vendor/0.26.9-1 url: https://github.com/ros2-gbp/rosbag2-release.git diff --git a/vinca.yaml b/vinca.yaml index 424ded93a..3c289c2ed 100644 --- a/vinca.yaml +++ b/vinca.yaml @@ -5,12 +5,12 @@ conda_index: - robostack.yaml - packages-ignore.yaml -# Reminder for next full rebuild, the next build number should be 12 -build_number: 10 +# Reminder for next full rebuild, the next build number should be 13 +build_number: 12 mutex_package: name: "ros2-distro-mutex" - version: "0.11.0" + version: "0.12.0" upper_bound: "x.x" run_constraints: - libboost 1.86.*