diff --git a/meta-ros-common/conf/ros-distro/include/ros-world-recipe-blacklist.inc b/meta-ros-common/conf/ros-distro/include/ros-world-recipe-blacklist.inc index c7d3393a771..c817a77d5c3 100644 --- a/meta-ros-common/conf/ros-distro/include/ros-world-recipe-blacklist.inc +++ b/meta-ros-common/conf/ros-distro/include/ros-world-recipe-blacklist.inc @@ -40,7 +40,7 @@ SKIP_RECIPE[wiringpi] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-i SKIP_RECIPE[packagegroup-rpi-test] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['world-issues'], 'world-issues: Depends on blacklisted packages like wiringpi and recipes from meta-multimedia we do not depend on: bigbuckbunny-480p, bigbuckbunny-720p, bigbuckbunny-1080p and wireless-regdb from meta-networking', '', d)}" SKIP_RECIPE[kernel-selftest] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Fails to build with linux-yocto kernel: WARNING: clang >= 6.0 with bpf support is needed with kernel 4.18+ so either install it and add it to HOSTTOOLS, or add clang-native from meta-clang to dependency and then /bin/sh: 1: llc: not found + /bin/sh: 1: clang: not found + /bin/sh: 1: llvm-readelf: not found', '', d)}" SKIP_RECIPE[vboxguestdrivers] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Fails to build with linux-yocto kernel: vboxguestdrivers/5.2.22-r0/vbox_module/vboxguest/r0drv/linux/time-r0drv-linux.c:175:5: error: implicit declaration of function ktime_get_real_ts; did you mean ktime_get_real_ns? [-Werror=implicit-function-declaration]', '', d)}" -SKIP_RECIPE[renderdoc] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Depends on mesa-gl without setting correct REQUIRED_DISTRO_FEATURES to match it: mesa-gl PROVIDES virtual/libgl but was skipped: one of vulkan opengl needs to be in DISTRO_FEATURES', '', d)}" +#SKIP_RECIPE[renderdoc] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Depends on mesa-gl without setting correct REQUIRED_DISTRO_FEATURES to match it: mesa-gl PROVIDES virtual/libgl but was skipped: one of vulkan opengl needs to be in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[python-ldap] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Depends on cyrus-sasl from meta-networking, skipped since http://lists.openembedded.org/pipermail/openembedded-devel/2020-February/205123.html', '', d)}" SKIP_RECIPE[python-networkmanager] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'world-issues', 'Depends on networkmanager, skipped since http://lists.openembedded.org/pipermail/openembedded-devel/2020-February/205124.html', '', d)}" diff --git a/meta-ros-common/recipes-devtools/gazebo/gz-cmake3_3.5.3.bb b/meta-ros-common/recipes-devtools/gazebo/gz-cmake3_3.5.3.bb new file mode 100644 index 00000000000..9bcfa956783 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/gz-cmake3_3.5.3.bb @@ -0,0 +1,23 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-cmake.git;protocol=https;branch=gz-cmake3" + +SRCREV = "ddd38ff196640024d6e054ff59cf5fea1ef01d73" + +S = "${WORKDIR}/git" + +FILES:${PN} += "${datadir}/gz/gz-cmake3/*" +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +FILES:${PN}-dev += " \ + pkgconfig/gz-cmake3.pc \ + ${includedir} \ + ${datadir}/cmake/gz-cmake3/cmake3/ \ + ${datadir}/gz/gz-cmake3/ \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/gz-tools2/backward-ros-include-dir.patch b/meta-ros-common/recipes-devtools/gazebo/gz-tools2/backward-ros-include-dir.patch new file mode 100644 index 00000000000..93f4133235d --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/gz-tools2/backward-ros-include-dir.patch @@ -0,0 +1,13 @@ +Index: git/src/backward.cc +=================================================================== +--- git.orig/src/backward.cc ++++ git/src/backward.cc +@@ -15,7 +15,7 @@ + * + */ + +-#include "backward.hpp" ++#include "backward_ros/backward.hpp" + + namespace gz { + namespace tools { diff --git a/meta-ros-common/recipes-devtools/gazebo/gz-tools2_2.0.1.bb b/meta-ros-common/recipes-devtools/gazebo/gz-tools2_2.0.1.bb new file mode 100644 index 00000000000..367ae24673f --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/gz-tools2_2.0.1.bb @@ -0,0 +1,43 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = " \ + git://github.com/gazebosim/gz-tools.git;protocol=https;branch=gz-tools2 \ + file://backward-ros-include-dir.patch \ +" + +SRCREV = "efcc504bd3665151266f38db627c9095e5a5773f" + +S = "${WORKDIR}/git" + +inherit cmake + +EXTRA_OECMAKE = "-DUSE_SYSTEM_BACKWARDCPP:BOOL=ON" + +DEPENDS = " \ + doxygen \ + jsoncpp \ + libyaml \ + libzip \ + backward-ros \ + gz-cmake3 \ +" + + +FILES:${PN} = " \ + ${bindir}/gz \ + ${datadir}/bash-completion/completions/gz \ + ${libdir}/libgz-tools2-backward.so.2 \ + ${libdir}/libgz-tools2-backward.so.2.0.1 \ + ${datadir}/gz/gz.completion \ +" + +FILES:${PN}-dev = " \ + ${libdir}/libgz-tools2-backward.so \ + ${libdir}/pkgconfig/gz-tools.pc \ + ${libdir}/cmake/gz-tools2-all/gz-tools2-all-config-version.cmake \ + ${libdir}/cmake/gz-tools2-all/gz-tools2-all-targets.cmake \ + ${libdir}/cmake/gz-tools2-all/gz-tools2-all-config.cmake \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-cmake2_2.17.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-cmake2_2.17.1.bb new file mode 100644 index 00000000000..09927acb0e9 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-cmake2_2.17.1.bb @@ -0,0 +1,23 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-cmake.git;protocol=https;branch=ign-cmake2" + +SRCREV = "7e694a02c412d4595d92cb3351a5f7b6e0b44b0d" + +S = "${WORKDIR}/git" + +FILES:${PN} += "${datadir}/ignition/ignition-cmake2/*" +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +FILES:${PN}-dev += " \ + pkgconfig/ignition-cmake2.pc \ + ${includedir} \ + ${datadir}/cmake/ignition-cmake2/cmake2/ \ + ${datadir}/ignition/ignition-cmake2/ \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-common4/cleanup-long-deprecated-ifdefs.patch b/meta-ros-common/recipes-devtools/gazebo/ignition-common4/cleanup-long-deprecated-ifdefs.patch new file mode 100644 index 00000000000..4f5001b950d --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-common4/cleanup-long-deprecated-ifdefs.patch @@ -0,0 +1,851 @@ +# https://github.com/gazebosim/gz-common/commit/870eaf029e43ec52d34e0dd026d78fbb961a5f77.patch +From 870eaf029e43ec52d34e0dd026d78fbb961a5f77 Mon Sep 17 00:00:00 2001 +From: Michael Carroll +Date: Wed, 31 Aug 2022 13:13:24 -0500 +Subject: [PATCH] Cleanup long-deprecated ifdefs (#329) + +Signed-off-by: Michael Carroll + +Co-authored-by: Louise Poubel +--- + CMakeLists.txt | 1 + + av/include/gz/common/ffmpeg_inc.hh | 60 +++++++++- + av/src/AudioDecoder.cc | 97 ++-------------- + av/src/Video.cc | 58 ++++++---- + av/src/VideoEncoder.cc | 175 ++++++----------------------- + av/src/ffmpeg_inc.cc | 25 ----- + 6 files changed, 135 insertions(+), 281 deletions(-) + +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -103,6 +103,7 @@ ign_find_package(SWSCALE REQUIRED_BY av + #------------------------------------ + # Find avdevice + ign_find_package(AVDEVICE VERSION 56.4.100 REQUIRED_BY av PRETTY libavdevice) ++set(HAVE_AVDEVICE ${AVDEVICE_FOUND}) + + #------------------------------------ + # Find avformat +Index: git/av/include/gz/common/ffmpeg_inc.hh +=================================================================== +--- git.orig/av/include/gz/common/ffmpeg_inc.hh ++++ git/av/include/gz/common/ffmpeg_inc.hh +@@ -17,6 +17,60 @@ + #ifndef GZ_COMMON_FFMPEG_INC_HH_ + #define GZ_COMMON_FFMPEG_INC_HH_ + ++/// Versions of FFMPEG on Gazebo supported platforms ++// v4.2.7 (Ubuntu Focal) ++// libavutil 56. 31.100 / 56. 31.100 ++// libavcodec 58. 54.100 / 58. 54.100 ++// libavformat 58. 29.100 / 58. 29.100 ++// libavdevice 58. 8.100 / 58. 8.100 ++// libavfilter 7. 57.100 / 7. 57.100 ++// libavresample 4. 0. 0 / 4. 0. 0 ++// libswscale 5. 5.100 / 5. 5.100 ++// libswresample 3. 5.100 / 3. 5.100 ++// libpostproc 55. 5.100 / 55. 5.100 ++ ++// v4.4.1 (Windows CI vcpkg) ++// libavutil 56. 70.100 / 56. 70.100 ++// libavcodec 58.134.100 / 58.134.100 ++// libavformat 58. 76.100 / 58. 76.100 ++// libavdevice 58. 13.100 / 58. 13.100 ++// libavfilter 7.110.100 / 7.110.100 ++// libswscale 5. 9.100 / 5. 9.100 ++// libswresample 3. 9.100 / 3. 9.100 ++// libpostproc 55. 9.100 / 55. 9.100 ++ ++// v4.4.2 (Ubuntu Jammy) ++// libavutil 56. 70.100 / 56. 70.100 ++// libavcodec 58.134.100 / 58.134.100 ++// libavformat 58. 76.100 / 58. 76.100 ++// libavdevice 58. 13.100 / 58. 13.100 ++// libavfilter 7.110.100 / 7.110.100 ++// libswscale 5. 9.100 / 5. 9.100 ++// libswresample 3. 9.100 / 3. 9.100 ++// libpostproc 55. 9.100 / 55. 9.100 ++ ++// v5.1 (homebrew) ++// libavutil 57. 28.100 / 57. 28.100 ++// libavcodec 59. 37.100 / 59. 37.100 ++// libavformat 59. 27.100 / 59. 27.100 ++// libavdevice 59. 7.100 / 59. 7.100 ++// libavfilter 8. 44.100 / 8. 44.100 ++// libswscale 6. 7.100 / 6. 7.100 ++// libswresample 4. 7.100 / 4. 7.100 ++// libpostproc 56. 6.100 / 56. 6.100 ++ ++/// Additional versions of FFMPEG not officially supported ++// v5.0.1 (conda-forge) ++// libavutil 57. 17.100 / 57. 17.100 ++// libavcodec 59. 18.100 / 59. 18.100 ++// libavformat 59. 16.100 / 59. 16.100 ++// libavdevice 59. 4.100 / 59. 4.100 ++// libavfilter 8. 24.100 / 8. 24.100 ++// libswscale 6. 4.100 / 6. 4.100 ++// libswresample 4. 3.100 / 4. 3.100 ++// libpostproc 56. 3.100 / 56. 3.100 ++ ++ + #include + + #include +@@ -44,7 +98,7 @@ extern "C" { + #include + #include + +-#if defined(__linux__) && defined(HAVE_AVDEVICE) ++#if defined(HAVE_AVDEVICE) + #include + #endif + } +@@ -57,15 +111,18 @@ namespace ignition + { + /// \brief Helper function to avoid deprecation warnings. + IGNITION_COMMON_AV_VISIBLE ++ IGN_DEPRECATED(5) + AVFrame *AVFrameAlloc(void); + + /// \brief Helper function to avoid deprecation warnings. + IGNITION_COMMON_AV_VISIBLE ++ IGN_DEPRECATED(5) + void AVFrameUnref(AVFrame *_frame); + + /// \brief Helper function to avoid deprecation warnings. + /// \param[in] _packet AVPacket structure that stores compressed data + IGNITION_COMMON_AV_VISIBLE ++ IGN_DEPRECATED(5) + void AVPacketUnref(AVPacket *_packet); + + /// \brief Helper function to avoid deprecation warnings +@@ -80,6 +137,7 @@ namespace ignition + /// \note If the codec is in draining mode, _packet can be null. The return + /// value on success will then be 0, but _gotFrame will be non-zero. + IGNITION_COMMON_AV_VISIBLE ++ IGN_DEPRECATED(5) + int AVCodecDecode(AVCodecContext *_codecCtx, + AVFrame *_frame, int *_gotFrame, AVPacket *_packet); + +Index: git/av/src/AudioDecoder.cc +=================================================================== +--- git.orig/av/src/AudioDecoder.cc ++++ git/av/src/AudioDecoder.cc +@@ -35,7 +35,7 @@ class common::AudioDecoderPrivate + public: AVCodecContext *codecCtx; + + /// \brief libavcodec audio codec. +- public: const AVCodec *codec; ++ public: const AVCodec *codec {nullptr}; + + /// \brief Index of the audio stream. + public: int audioStream; +@@ -77,12 +77,7 @@ void AudioDecoder::Cleanup() + ///////////////////////////////////////////////// + bool AudioDecoder::Decode(uint8_t **_outBuffer, unsigned int *_outBufferSize) + { +-#if LIBAVFORMAT_VERSION_MAJOR < 59 +- AVPacket *packet, packet1; +- int bytesDecoded = 0; +-#else + AVPacket *packet; +-#endif + unsigned int maxBufferSize = 0; + AVFrame *decodedFrame = nullptr; + +@@ -108,7 +103,7 @@ bool AudioDecoder::Decode(uint8_t **_out + + bool result = true; + +- if (!(decodedFrame = AVFrameAlloc())) ++ if (!(decodedFrame = av_frame_alloc())) + { + ignerr << "Audio decoder out of memory\n"; + result = false; +@@ -125,7 +120,6 @@ bool AudioDecoder::Decode(uint8_t **_out + { + if (packet->stream_index == this->data->audioStream) + { +-#if LIBAVFORMAT_VERSION_MAJOR >= 59 + // Inspired from + // https://github.com/FFmpeg/FFmpeg/blob/n5.0/doc/examples/decode_audio.c#L71 + +@@ -152,12 +146,18 @@ bool AudioDecoder::Decode(uint8_t **_out + return false; + } + ++#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(59, 24, 100) ++ int numChannels = this->data->codecCtx->ch_layout.nb_channels; ++#else ++ int numChannels = this->data->codecCtx->channels; ++#endif ++ + // Total size of the data. Some padding can be added to + // decodedFrame->data[0], which is why we can't use + // decodedFrame->linesize[0]. + int size = decodedFrame->nb_samples * + av_get_bytes_per_sample(this->data->codecCtx->sample_fmt) * +- this->data->codecCtx->ch_layout.nb_channels; ++ numChannels; + // Resize the audio buffer as necessary + if (*_outBufferSize + size > maxBufferSize) + { +@@ -170,51 +170,7 @@ bool AudioDecoder::Decode(uint8_t **_out + size); + *_outBufferSize += size; + } +-#else +- int gotFrame = 0; +- +- packet1 = *packet; +- while (packet1.size) +- { +- // Some frames rely on multiple packets, so we have to make sure +- // the frame is finished before we can use it +-#ifndef _WIN32 +-# pragma GCC diagnostic push +-# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +-#endif +- bytesDecoded = avcodec_decode_audio4(this->data->codecCtx, decodedFrame, +- &gotFrame, &packet1); +-#ifndef _WIN32 +-# pragma GCC diagnostic pop +-#endif +- +- if (gotFrame) +- { +- // Total size of the data. Some padding can be added to +- // decodedFrame->data[0], which is why we can't use +- // decodedFrame->linesize[0]. +- int size = decodedFrame->nb_samples * +- av_get_bytes_per_sample(this->data->codecCtx->sample_fmt) * +- this->data->codecCtx->channels; +- +- // Resize the audio buffer as necessary +- if (*_outBufferSize + size > maxBufferSize) +- { +- maxBufferSize += size * 5; +- *_outBuffer = reinterpret_cast(realloc(*_outBuffer, +- maxBufferSize * sizeof(*_outBuffer[0]))); +- } +- +- memcpy(*_outBuffer + *_outBufferSize, decodedFrame->data[0], +- size); +- *_outBufferSize += size; +- } +- +- packet1.data += bytesDecoded; +- packet1.size -= bytesDecoded; +- } +-#endif + } + av_packet_unref(packet); + } + +@@ -271,20 +226,8 @@ bool AudioDecoder::SetFile(const std::st + this->data->audioStream = -1; + for (i = 0; i < this->data->formatCtx->nb_streams; ++i) + { +-#ifndef _WIN32 +-# pragma GCC diagnostic push +-# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +-#endif +-#if LIBAVFORMAT_VERSION_MAJOR >= 59 + if (this->data->formatCtx->streams[i]->codecpar->codec_type == // NOLINT(*) + AVMEDIA_TYPE_AUDIO) +-#else +- if (this->data->formatCtx->streams[i]->codec->codec_type == // NOLINT(*) +- AVMEDIA_TYPE_AUDIO) +-#endif +-#ifndef _WIN32 +-# pragma GCC diagnostic pop +-#endif + { + this->data->audioStream = i; + break; +@@ -300,21 +243,7 @@ bool AudioDecoder::SetFile(const std::st + return false; + } + +- // Get the audio stream codec +-#ifndef _WIN32 +-# pragma GCC diagnostic push +-# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +-#endif +-#if LIBAVFORMAT_VERSION_MAJOR < 59 +- this->data->codecCtx = this->data->formatCtx->streams[ +- this->data->audioStream]->codec; +-#endif +-#ifndef _WIN32 +-# pragma GCC diagnostic pop +-#endif +- + // Find a decoder +-#if LIBAVFORMAT_VERSION_MAJOR >= 59 + this->data->codec = avcodec_find_decoder(this->data->formatCtx->streams[ + this->data->audioStream]->codecpar->codec_id); + if (!this->data->codec) +@@ -331,9 +260,6 @@ bool AudioDecoder::SetFile(const std::st + // Copy all relevant parameters from codepar to codecCtx + avcodec_parameters_to_context(this->data->codecCtx, + this->data->formatCtx->streams[this->data->audioStream]->codecpar); +-#else +- this->data->codec = avcodec_find_decoder(this->data->codecCtx->codec_id); +-#endif + + if (this->data->codec == nullptr) + { +@@ -344,13 +270,8 @@ bool AudioDecoder::SetFile(const std::st + return false; + } + +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(56, 60, 100) + if (this->data->codec->capabilities & AV_CODEC_CAP_TRUNCATED) + this->data->codecCtx->flags |= AV_CODEC_FLAG_TRUNCATED; +-#else +- if (this->data->codec->capabilities & CODEC_CAP_TRUNCATED) +- this->data->codecCtx->flags |= CODEC_FLAG_TRUNCATED; +-#endif + + // Open codec + if (avcodec_open2(this->data->codecCtx, this->data->codec, nullptr) < 0) +Index: git/av/src/Video.cc +=================================================================== +--- git.orig/av/src/Video.cc ++++ git/av/src/Video.cc +@@ -59,6 +59,37 @@ class common::VideoPrivate + public: bool drainingMode = false; + }; + ++int AVCodecDecode(AVCodecContext *_codecCtx, ++ AVFrame *_frame, int *_gotFrame, AVPacket *_packet) ++{ ++ // from https://blogs.gentoo.org/lu_zero/2016/03/29/new-avcodec-api/ ++ int ret; ++ ++ *_gotFrame = 0; ++ ++ if (_packet) ++ { ++ ret = avcodec_send_packet(_codecCtx, _packet); ++ if (ret < 0) ++ { ++ return ret == AVERROR_EOF ? 0 : ret; ++ } ++ } ++ ++ ret = avcodec_receive_frame(_codecCtx, _frame); ++ if (ret < 0 && ret != AVERROR(EAGAIN)) ++ { ++ return ret; ++ } ++ if (ret >= 0) ++ { ++ *_gotFrame = 1; ++ } ++ ++ // new API always consumes the whole packet ++ return _packet ? _packet->size : 0; ++} ++ + ///////////////////////////////////////////////// + Video::Video() + : dataPtr(new VideoPrivate) +@@ -100,7 +131,7 @@ bool Video::Load(const std::string &_fil + this->Cleanup(); + } + +- this->dataPtr->avFrame = AVFrameAlloc(); ++ this->dataPtr->avFrame = av_frame_alloc(); + + // Open video file + if (avformat_open_input(&this->dataPtr->formatCtx, _filename.c_str(), +@@ -121,13 +152,7 @@ bool Video::Load(const std::string &_fil + for (unsigned int i = 0; i < this->dataPtr->formatCtx->nb_streams; ++i) + { + enum AVMediaType codec_type; +- // codec parameter deprecated in ffmpeg version 3.1 +- // github.com/FFmpeg/FFmpeg/commit/9200514ad8717c +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 48, 101) + codec_type = this->dataPtr->formatCtx->streams[i]->codecpar->codec_type; +-#else +- codec_type = this->dataPtr->formatCtx->streams[i]->codec->codec_type; +-#endif + if (codec_type == AVMEDIA_TYPE_VIDEO) + { + this->dataPtr->videoStream = static_cast(i); +@@ -143,18 +168,13 @@ bool Video::Load(const std::string &_fil + + // Find the decoder for the video stream + auto stream = this->dataPtr->formatCtx->streams[this->dataPtr->videoStream]; +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 48, 101) + codec = avcodec_find_decoder(stream->codecpar->codec_id); +-#else +- codec = avcodec_find_decoder(stream->codec->codec_id); +-#endif + if (codec == nullptr) + { + ignerr << "Codec not found\n"; + return false; + } + +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 48, 101) + // AVCodecContext is not included in an AVStream as of ffmpeg 3.1 + // allocate a codec context based on updated example + // github.com/FFmpeg/FFmpeg/commit/bba6a03b2816d805d44bce4f9701a71f7d3f8dad +@@ -173,21 +193,11 @@ bool Video::Load(const std::string &_fil + << std::endl; + return false; + } +-#else +- // Get a pointer to the codec context for the video stream +- this->dataPtr->codecCtx = this->dataPtr->formatCtx->streams[ +- this->dataPtr->videoStream]->codec; +-#endif + + // Inform the codec that we can handle truncated bitstreams -- i.e., + // bitstreams where frame boundaries can fall in the middle of packets +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(56, 60, 100) + if (codec->capabilities & AV_CODEC_CAP_TRUNCATED) + this->dataPtr->codecCtx->flags |= AV_CODEC_FLAG_TRUNCATED; +-#else +- if (codec->capabilities & CODEC_CAP_TRUNCATED) +- this->dataPtr->codecCtx->flags |= CODEC_FLAG_TRUNCATED; +-#endif + + // Open codec + if (avcodec_open2(this->dataPtr->codecCtx, codec, nullptr) < 0) +@@ -212,7 +222,7 @@ bool Video::Load(const std::string &_fil + } + + // swscale needs 32-byte-aligned output frame on some systems +- this->dataPtr->avFrameDst = AVFrameAlloc(); ++ this->dataPtr->avFrameDst = av_frame_alloc(); + this->dataPtr->avFrameDst->format = this->dataPtr->dstPixelFormat; + this->dataPtr->avFrameDst->width = this->dataPtr->codecCtx->width; + this->dataPtr->avFrameDst->height = this->dataPtr->codecCtx->height; +@@ -291,7 +301,7 @@ bool Video::NextFrame(unsigned char **_b + } + + // Process all the data in the frame +- ret = AVCodecDecode( ++ ret = ::AVCodecDecode( + this->dataPtr->codecCtx, this->dataPtr->avFrame, &frameAvailable, + this->dataPtr->drainingMode ? nullptr : packet); + +Index: git/av/src/VideoEncoder.cc +=================================================================== +--- git.orig/av/src/VideoEncoder.cc ++++ git/av/src/VideoEncoder.cc +@@ -14,6 +14,7 @@ + * limitations under the License. + * + */ ++ + #include + + #include +@@ -32,6 +33,14 @@ using namespace ignition; + using namespace common; + using namespace std; + ++// After AVDevice 59.0.100, const pointers are used. ++#if LIBAVDEVICE_VERSION_INT >= AV_VERSION_INT(59, 0, 100) ++using OutputFormat = const AVOutputFormat*; ++#else ++using OutputFormat = AVOutputFormat*; ++#endif ++ ++ + // Private data class + // hidden visibility specifier has to be explicitly set to silent a gcc warning + class IGNITION_COMMON_AV_HIDDEN common::VideoEncoderPrivate +@@ -53,11 +62,7 @@ class IGNITION_COMMON_AV_HIDDEN common:: + public: AVFrame *avOutFrame = nullptr; + + /// \brief libav input image data (aligned to 32 bytes) +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- public: AVPicture *avInFrame = nullptr; +-#else + public: AVFrame *avInFrame = nullptr; +-#endif + + /// \brief Pixel format of the input frame. So far it is hardcoded. + public: AVPixelFormat inPixFormat = AV_PIX_FMT_RGB24; +@@ -340,34 +345,37 @@ bool VideoEncoder::Start( + // Special case for video4linux2. Here we attempt to find the v4l2 device + if (this->dataPtr->format.compare("v4l2") == 0) + { +-#if LIBAVDEVICE_VERSION_INT >= AV_VERSION_INT(56, 4, 100) +- AVOutputFormat *outputFormat = nullptr; +- while ((outputFormat = av_output_video_device_next(outputFormat)) +- != nullptr) +- { +- // Break when the output device name matches 'v4l2' +- if (this->dataPtr->format.compare(outputFormat->name) == 0) ++#if defined(HAVE_AVDEVICE) ++ OutputFormat outputFormat = nullptr; ++ do ++ { ++ outputFormat = av_output_video_device_next(outputFormat); ++ ++ if (outputFormat) + { +- // Allocate the context using the correct outputFormat +- auto result = avformat_alloc_output_context2(&this->dataPtr->formatCtx, +- outputFormat, nullptr, this->dataPtr->filename.c_str()); +- if (result < 0) ++ // Break when the output device name matches 'v4l2' ++ if (this->dataPtr->format.compare(outputFormat->name) == 0) + { +- ignerr << "Failed to allocate AV context [" << av_err2str_cpp(result) +- << "]" << std::endl; ++ // Allocate the context using the correct outputFormat ++ auto result = avformat_alloc_output_context2(&this->dataPtr->formatCtx, ++ outputFormat, nullptr, this->dataPtr->filename.c_str()); ++ if (result < 0) ++ { ++ ignerr << "Failed to allocate AV context [" << av_err2str_cpp(result) ++ << "]" << std::endl; ++ } ++ break; + } +- break; + } + } +-#else +- ignerr << "libavdevice version >= 56.4.100 is required for v4l2 recording. " +- << "This version is available on Ubuntu Xenial or greater.\n"; +- return false; ++ while (outputFormat); ++ ++ + #endif + } + else + { +- const AVOutputFormat *outputFormat = av_guess_format(nullptr, ++ auto* outputFormat = av_guess_format(nullptr, + this->dataPtr->filename.c_str(), nullptr); + + if (!outputFormat) +@@ -376,28 +384,6 @@ bool VideoEncoder::Start( + << "Using MPEG.\n"; + } + +-#if LIBAVFORMAT_VERSION_INT < AV_VERSION_INT(56, 40, 1) +- this->dataPtr->formatCtx = avformat_alloc_context(); +- if (outputFormat) +- { +- this->dataPtr->formatCtx->oformat = outputFormat; +- } +- else +- { +- this->dataPtr->formatCtx->oformat = +- av_guess_format("mpeg", nullptr, nullptr); +- } +-#ifdef WIN32 +- _sprintf(this->dataPtr->formatCtx->filename, +- sizeof(this->dataPtr->formatCtx->filename), +- "%s", _filename.c_str()); +-#else +- snprintf(this->dataPtr->formatCtx->filename, +- sizeof(this->dataPtr->formatCtx->filename), +- "%s", _filename.c_str()); +-#endif +- +-#else + auto result = avformat_alloc_output_context2(&this->dataPtr->formatCtx, + nullptr, nullptr, this->dataPtr->filename.c_str()); + if (result < 0) +@@ -405,7 +391,6 @@ bool VideoEncoder::Start( + ignerr << "Failed to allocate AV context [" << av_err2str_cpp(result) + << "]" << std::endl; + } +-#endif + } + + // Make sure allocation occurred. +@@ -428,11 +413,7 @@ bool VideoEncoder::Start( + if (!encoder) + { + ignerr << "Codec for[" +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- << this->dataPtr->formatCtx->oformat->name +-#else + << avcodec_get_name(codecId) +-#endif + << "] not found. Video encoding is not started.\n"; + this->Reset(); + return false; +@@ -441,13 +422,8 @@ bool VideoEncoder::Start( + ignmsg << "Using encoder " << encoder->name << std::endl; + + // Create a new video stream +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- this->dataPtr->videoStream = avformat_new_stream(this->dataPtr->formatCtx, +- encoder); +-#else + this->dataPtr->videoStream = avformat_new_stream(this->dataPtr->formatCtx, + nullptr); +-#endif + + if (!this->dataPtr->videoStream) + { +@@ -458,11 +434,7 @@ bool VideoEncoder::Start( + this->dataPtr->videoStream->id = this->dataPtr->formatCtx->nb_streams-1; + + // Allocate a new video context +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- this->dataPtr->codecCtx = this->dataPtr->videoStream->codec; +-#else + this->dataPtr->codecCtx = avcodec_alloc_context3(encoder); +-#endif + + if (!this->dataPtr->codecCtx) + { +@@ -475,11 +447,7 @@ bool VideoEncoder::Start( + // some formats want stream headers to be separate + if (this->dataPtr->formatCtx->oformat->flags & AVFMT_GLOBALHEADER) + { +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- this->dataPtr->codecCtx->flags |= CODEC_FLAG_GLOBAL_HEADER; +-#else + this->dataPtr->codecCtx->flags |= AV_CODEC_FLAG_GLOBAL_HEADER; +-#endif + } + + // Frames per second +@@ -517,13 +485,7 @@ bool VideoEncoder::Start( + if (this->dataPtr->codecCtx->codec_id == AV_CODEC_ID_H264) + { + av_opt_set(this->dataPtr->codecCtx->priv_data, "preset", "slow", 0); +- +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- av_opt_set(this->dataPtr->videoStream->codec->priv_data, +- "preset", "slow", 0); +-#else + av_opt_set(this->dataPtr->videoStream->priv_data, "preset", "slow", 0); +-#endif + } + + // we misuse this field a bit, as docs say it is unused in encoders +@@ -560,11 +522,7 @@ bool VideoEncoder::Start( + return false; + } + +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55, 28, 1) +- this->dataPtr->avOutFrame = avcodec_alloc_frame(); +-#else + this->dataPtr->avOutFrame = av_frame_alloc(); +-#endif + + if (!this->dataPtr->avOutFrame) + { +@@ -589,14 +547,9 @@ bool VideoEncoder::Start( + } + + // Copy parameters from the context to the video stream +-#if LIBAVFORMAT_VERSION_INT < AV_VERSION_INT(57, 40, 101) +-// ret = avcodec_copy_context(this->dataPtr->videoStream->codec, +-// this->dataPtr->codecCtx); +-#else + // codecpar was implemented in ffmpeg version 3.1 + ret = avcodec_parameters_from_context( + this->dataPtr->videoStream->codecpar, this->dataPtr->codecCtx); +-#endif + if (ret < 0) + { + ignerr << "Could not copy the stream parameters:" << av_err2str_cpp(ret) +@@ -690,11 +643,7 @@ bool VideoEncoder::AddFrame(const unsign + this->dataPtr->swsCtx = nullptr; + + if (this->dataPtr->avInFrame) +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- av_free(this->dataPtr->avInFrame); +-#else + av_frame_free(&this->dataPtr->avInFrame); +-#endif + this->dataPtr->avInFrame = nullptr; + } + +@@ -705,19 +654,12 @@ bool VideoEncoder::AddFrame(const unsign + + if (!this->dataPtr->avInFrame) + { +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- this->dataPtr->avInFrame = new AVPicture; +- avpicture_alloc(this->dataPtr->avInFrame, +- this->dataPtr->inPixFormat, this->dataPtr->inWidth, +- this->dataPtr->inHeight); +-#else + this->dataPtr->avInFrame = av_frame_alloc(); + this->dataPtr->avInFrame->width = this->dataPtr->inWidth; + this->dataPtr->avInFrame->height = this->dataPtr->inHeight; + this->dataPtr->avInFrame->format = this->dataPtr->inPixFormat; + + av_frame_get_buffer(this->dataPtr->avInFrame, 32); +-#endif + } + + av_image_fill_linesizes(this->dataPtr->inputLineSizes, +@@ -779,24 +721,6 @@ bool VideoEncoder::AddFrame(const unsign + { + frameToEncode->pts = this->dataPtr->frameCount++; + +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 40, 101) +- int gotOutput = 0; +- AVPacket avPacket; +- av_init_packet(&avPacket); +- avPacket.data = nullptr; +- avPacket.size = 0; +- +- ret = avcodec_encode_video2(this->dataPtr->codecCtx, &avPacket, +- frameToEncode, &gotOutput); +- +- if (ret >= 0 && gotOutput == 1) +- ret = ProcessPacket(&avPacket); +- +- av_free_packet(&avPacket); +- +- // #else for libavcodec version check +-#else +- + AVPacket* avPacket = av_packet_alloc(); + + avPacket->data = nullptr; +@@ -817,7 +741,6 @@ bool VideoEncoder::AddFrame(const unsign + } + + av_packet_unref(avPacket); +-#endif + } + return ret >= 0 || ret == AVERROR(EAGAIN); + } +@@ -859,31 +782,6 @@ bool VideoEncoder::Stop() + // drain remaining packets from the encoder + if (this->dataPtr->encoding && this->dataPtr->codecCtx) + { +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 40, 101) +- if ((this->dataPtr->codecCtx->capabilities & AV_CODEC_CAP_DELAY) > 0) +- { +- int gotOutput = 1; +- int ret = 0; +- AVPacket avPacket; +- av_init_packet(&avPacket); +- avPacket.data = nullptr; +- avPacket.size = 0; +- +- while (ret >= 0 && gotOutput == 1) +- { +- ret = avcodec_encode_video2(this->dataPtr->codecCtx, &avPacket, +- nullptr, &gotOutput); +- +- if (ret >= 0 && gotOutput == 1) +- ret = ProcessPacket(&avPacket); +- } +- +- av_free_packet(&avPacket); +- } +- +-// #else for libavcodec version check +-#else +- + int ret = 0; + // enter drain state + ret = avcodec_send_frame(this->dataPtr->codecCtx, nullptr); +@@ -906,32 +804,21 @@ bool VideoEncoder::Stop() + } + av_packet_unref(avPacket); + } +-#endif + } + + if (this->dataPtr->encoding && this->dataPtr->formatCtx) + av_write_trailer(this->dataPtr->formatCtx); + +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 24, 1) + if (this->dataPtr->codecCtx) + avcodec_free_context(&this->dataPtr->codecCtx); +-#endif + this->dataPtr->codecCtx = nullptr; + + if (this->dataPtr->avInFrame) +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- av_free(this->dataPtr->avInFrame); +-#else + av_frame_free(&this->dataPtr->avInFrame); +-#endif + this->dataPtr->avInFrame = nullptr; + + if (this->dataPtr->avOutFrame) +-#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(57, 24, 1) +- av_free(this->dataPtr->avOutFrame); +-#else + av_frame_free(&this->dataPtr->avOutFrame); +-#endif + this->dataPtr->avOutFrame = nullptr; + + if (this->dataPtr->swsCtx) +Index: git/av/src/ffmpeg_inc.cc +=================================================================== +--- git.orig/av/src/ffmpeg_inc.cc ++++ git/av/src/ffmpeg_inc.cc +@@ -21,38 +21,25 @@ using namespace ignition; + ////////////////////////////////////////////////// + AVFrame *common::AVFrameAlloc(void) + { +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(55, 28, 1) + return av_frame_alloc(); +-#else +- return avcodec_alloc_frame(); +-#endif + } + + ////////////////////////////////////////////////// + void common::AVFrameUnref(AVFrame *_frame) + { +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(55, 28, 1) + av_frame_unref(_frame); +-#else +- avcodec_get_frame_defaults(_frame); +-#endif + } + + ////////////////////////////////////////////////// + void common::AVPacketUnref(AVPacket *_packet) + { +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 24, 102) + av_packet_unref(_packet); +-#else +- av_free_packet(_packet); +-#endif + } + + ////////////////////////////////////////////////// + int common::AVCodecDecode(AVCodecContext *_codecCtx, + AVFrame *_frame, int *_gotFrame, AVPacket *_packet) + { +-#if LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(57, 48, 101) + // from https://blogs.gentoo.org/lu_zero/2016/03/29/new-avcodec-api/ + int ret; + +@@ -79,16 +66,4 @@ int common::AVCodecDecode(AVCodecContext + + // new API always consumes the whole packet + return _packet ? _packet->size : 0; +-#else +- // this was deprecated in ffmpeg version 3.1 +- // github.com/FFmpeg/FFmpeg/commit/7fc329e2dd6226dfecaa4a1d7adf353bf2773726 +-# ifndef _WIN32 +-# pragma GCC diagnostic push +-# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +-# endif +- return avcodec_decode_video2(_codecCtx, _frame, _gotFrame, _packet); +-# ifndef _WIN32 +-# pragma GCC diagnostic pop +-# endif +-#endif + } diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-common4_2.17.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-common4_2.17.1.bb new file mode 100644 index 00000000000..315a52dd26d --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-common4_2.17.1.bb @@ -0,0 +1,40 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=2e9f68f022747514564aa13818fcb7c6 \ + file://profiler/src/Remotery/LICENSE;md5=34400b68072d710fecd0a2940a0d1658" + +SRC_URI = "git://github.com/gazebosim/gz-common.git;protocol=https;branch=ign-common4 \ + file://cleanup-long-deprecated-ifdefs.patch \ +" + +SRCREV = "ade3fa20db31a094388d1fca96bbddaf5eeb262d" + +S = "${WORKDIR}/git" + +inherit cmake pkgconfig + +# CMake Error: TRY_RUN() invoked in cross-compiling mode, please set the following cache variables appropriately: +# FREEIMAGE_RUNS (advanced) +# FREEIMAGE_RUNS__TRYRUN_OUTPUT (advanced) +EXTRA_OECMAKE += " -DFREEIMAGE_RUNS=1 -DFREEIMAGE_RUNS__TRYRUN_OUTPUT=0" + +DEPENDS = " \ + cppcheck-native \ + doxygen-native \ + graphviz-native \ + gts \ + ffmpeg \ + freeimage \ + ignition-cmake2 \ + ignition-math6 \ + ignition-utils1 \ + libtinyxml2 \ + util-linux \ +" + +FILES:${PN} += " \ + ${datadir}/ignition/ignition-common4/profiler_vis/* \ + ${datadir}/ignition/ignition-common4/ignition-common4.tag.xml \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-fuel-tools7_2.17.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-fuel-tools7_2.17.1.bb new file mode 100644 index 00000000000..ce084a412ec --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-fuel-tools7_2.17.1.bb @@ -0,0 +1,30 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-fuel-tools;protocol=https;branch=ign-fuel-tools7" + +SRCREV = "0bdbb7a0f54a6db260abcc391de064662f193d3e" + +S = "${WORKDIR}/git" + +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-msgs8 \ + jsoncpp \ + libyaml \ + libzip \ + curl \ +" + +FILES:${PN} += " \ + ${libdir}/ruby/ignition/cmdfuel7.rb \ + ${datadir}/gz/gz1.completion.d/fuel7.bash_completion.sh \ + ${datadir}/ignition/fuel7.yaml \ + ${datadir}/ignition/fuel_tools7/config.yaml \ +" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-gazebo6_6.15.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-gazebo6_6.15.0.bb new file mode 100644 index 00000000000..45c694da400 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-gazebo6_6.15.0.bb @@ -0,0 +1,35 @@ +LICENSE = "Apache-2.0 & Artistic-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://src/systems/elevator/vender/afsm/LICENSE;md5=ec4341a201f4b801aba0191a5d2d8f39 \ + file://src/systems/elevator/vender/metapushkin/LICENSE;md5=ec4341a201f4b801aba0191a5d2d8f39" + +SRC_URI = "git://github.com/gazebosim/gz-sim.git;protocol=https;branch=ign-gazebo6" + +SRCREV = "326cef2b4a177bf6ea957fe9e2841c4719d598db" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: Python3 ignition-cmake2 pybind11 +inherit cmake python3-dir + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-fuel-tools7 \ + ignition-gui6 \ + ignition-math6 \ + ignition-msgs8 \ + ignition-physics5 \ + ignition-plugin \ + ignition-rendering6 \ + ignition-sensors6 \ + ignition-tools1 \ + ignition-transport11 \ + ignition-utils1 \ + sdformat \ +" + +RPROVIDES:${PN} += " gazebo" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-gui6_6.8.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-gui6_6.8.0.bb new file mode 100644 index 00000000000..5e211d4e931 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-gui6_6.8.0.bb @@ -0,0 +1,44 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-gui.git;protocol=https;branch=ign-gui6" + +SRCREV = "982aafca1b96dbc6d12ea5de4d8df27c288be532" + +S = "${WORKDIR}/git" + +inherit cmake + +# CMake Error at src/plugins/CMakeLists.txt:26 (QT5_WRAP_CPP): +# Unknown CMake command "QT5_WRAP_CPP". +inherit ${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], '', 'cmake_qt5', d)} + +DEPENDS = " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-math6 \ + ignition-msgs8 \ + ignition-plugin \ + ignition-rendering6 \ + ignition-tools1 \ + ignition-transport11 \ + ignition-utils1 \ + protobuf \ + libtinyxml2 \ + qtbase \ + qtquickcontrols2 \ +" +DEPENDS:append:class-target = "xserver-xorg" + +FILES:${PN} += " \ + ${libdir}/ign-gui-6/plugins/* \ + ${libdir}/ruby/ignition/* \ + ${datadir}/gz/* \ + ${datadir}/ignition/* \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-launch5_5.3.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-launch5_5.3.0.bb new file mode 100644 index 00000000000..1cc38c2ae32 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-launch5_5.3.0.bb @@ -0,0 +1,41 @@ +# Recipe created by recipetool +# This is the basis of a recipe and may need further editing in order to be fully functional. +# (Feel free to remove these comments when editing.) + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-launch.git;protocol=https;branch=ign-launch5" + +SRCREV = "894e2e2319617fbde652960b847e13436391ec9c" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: ignition-cmake2 +# NOTE: the following library dependencies are unknown, ignoring: bfd dwarf +# (this is based on recipes that have previously been built and packaged) +DEPENDS = "elfutils" + +inherit cmake +inherit ${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], '', 'cmake_qt5', d)} + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = " \ + elfutils \ + ignition-cmake2 \ + ignition-common4 \ + ignition-gazebo6 \ + ignition-gui6 \ + ignition-math6 \ + ignition-msgs8 \ + ignition-plugin \ + ignition-rendering6 \ + ignition-tools1 \ + ignition-transport11 \ + ignition-utils1 \ + libwebsockets \ +" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-math6_6.15.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-math6_6.15.0.bb new file mode 100644 index 00000000000..e8b14704e75 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-math6_6.15.0.bb @@ -0,0 +1,29 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-math.git;protocol=https;branch=ign-math6" + +SRCREV = "62768395a0386e596f5a761fb5f426e0a3f1d050" + +S = "${WORKDIR}/git" + +DEPENDS = " \ + ruby-native \ + swig-native \ + python3 \ + python3-pybind11 \ + ignition-cmake2 \ +" + +inherit cmake python3-dir + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = " \ + ignition-cmake2 \ + ignition-cmake2-native \ + libeigen \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8-native_8.7.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8-native_8.7.0.bb new file mode 100644 index 00000000000..5d0e43959f3 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8-native_8.7.0.bb @@ -0,0 +1,6 @@ +include ignition-msgs8.inc + +DEPENDS = "ignition-cmake2-native ignition-math6-native libtinyxml2-native protobuf-native" +EXTRA_OECMAKE += "-DINSTALL_IGN_MSGS_GEN_EXECUTABLE:BOOL=ON" + +inherit native diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8.inc b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8.inc new file mode 100644 index 00000000000..75873f3da8a --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8.inc @@ -0,0 +1,13 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=2e9f68f022747514564aa13818fcb7c6" + +SRC_URI = "git://github.com/gazebosim/gz-msgs.git;protocol=https;branch=ign-msgs8" + +# Modify these as desired +PV = "8.7.0+git${SRCPV}" +SRCREV = "f9acd44dd926433799e5e0c6f5f4af281bc72c57" + +S = "${WORKDIR}/git" + +inherit cmake diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8_8.7.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8_8.7.0.bb new file mode 100644 index 00000000000..4d7477ee663 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-msgs8_8.7.0.bb @@ -0,0 +1,12 @@ +include ignition-msgs8.inc + +DEPENDS = "ignition-math6 libtinyxml2 protobuf protobuf-native ${PN}-native" +DEPENDS += "${PN}-native" +EXTRA_OECMAKE += " -DINSTALL_IGN_MSGS_GEN_EXECUTABLE:BOOL=OFF -DIGN_MSGS_GEN_EXECUTABLE=${WORKDIR}/recipe-sysroot-native/usr/bin/ign_msgs_gen" + +FILES:${PN} += " \ + ${libdir}/ruby/ignition/cmdmsgs8.rb \ + ${libdir}/ruby/ignition/msgs8/* \ + ${datadir}/gz/gz1.completion.d/msgs8.bash_completion.sh \ + ${datadir}/ignition/msgs8.yaml \ +" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-physics5_5.0.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-physics5_5.0.0.bb new file mode 100644 index 00000000000..ea38724e1e3 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-physics5_5.0.0.bb @@ -0,0 +1,23 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=2e9f68f022747514564aa13818fcb7c6 \ + file://tpe/lib/src/aabb_tree/LICENSE;md5=fd0ac4e17e55ad320e9429c05b5c23c7" + +SRC_URI = "git://github.com/gazebosim/gz-physics.git;protocol=https;branch=ign-physics5" + +SRCREV = "ba3eb2c7f32660eef82e27f24401783f80cfcf2b" + +S = "${WORKDIR}/git" + +DEPENDS += " \ + ignition-cmake2 \ + ignition-math6 \ + ignition-common4 \ + ignition-transport11 \ + ignition-rendering6 \ + ignition-msgs8 \ + protobuf \ + sdformat \ +" + +inherit cmake diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-plugin_1.4.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-plugin_1.4.0.bb new file mode 100644 index 00000000000..aa3d5d4dac6 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-plugin_1.4.0.bb @@ -0,0 +1,24 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=2e9f68f022747514564aa13818fcb7c6" + +SRC_URI = "git://github.com/gazebosim/gz-plugin.git;protocol=https;branch=ign-plugin1" + +SRCREV = "1d5a4c987668ed0584ddbf4398dc81b519412c54" + +S = "${WORKDIR}/git" + +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = "ignition-cmake2" + +FILES:${PN} += " \ + ${datadir}/gz/gz1.completion.d/plugin1.bash_completion.sh \ + ${datadir}/ignition/plugin1.yaml \ + ${libdir}/ruby/ignition/cmdplugin1.rb \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6/freeimage_optional.patch b/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6/freeimage_optional.patch new file mode 100644 index 00000000000..b5610bc5ea6 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6/freeimage_optional.patch @@ -0,0 +1,32 @@ +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -48,12 +48,6 @@ ign_find_package(ignition-plugin1 REQUIR + set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR}) + + #-------------------------------------- +-# Find FreeImage +-ign_find_package(FreeImage VERSION 3.9 +- REQUIRED_BY optix +- PRIVATE_FOR optix) +- +-#-------------------------------------- + # Find OpenGL + # See CMP0072 for more details (cmake --help-policy CMP0072) + if ((NOT ${CMAKE_VERSION} VERSION_LESS 3.11) AND (NOT OpenGL_GL_PREFERENCE)) +@@ -139,7 +133,14 @@ if(NOT MSVC) + + if (OptiX_FOUND AND CUDA_FOUND) + set(HAVE_OPTIX TRUE) ++ ++ #-------------------------------------- ++ # Find FreeImage ++ ign_find_package(FreeImage VERSION 3.9 ++ REQUIRED_BY optix ++ PRIVATE_FOR optix) + endif() ++ + endif() + + ##################################### diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6_6.6.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6_6.6.1.bb new file mode 100644 index 00000000000..120fa19dca6 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-rendering6_6.6.1.bb @@ -0,0 +1,53 @@ +LICENSE = "Apache-2.0 & OFL-1.1" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://ogre/src/media/fonts/liberation-sans/SIL%20Open%20Font%20License.txt;md5=a4b00b7892bfb2fc9398e7f292af5b3d" + +SRC_URI = "git://github.com/gazebosim/gz-rendering.git;protocol=https;branch=main \ + file://freeimage_optional.patch" + +SRCREV = "c2c5fdfb889f449a0c7665dc492ee6b67591cadd" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: CUDA ignition-cmake2 +DEPENDS = "boost" + +inherit cmake pkgconfig + +# Copied from rviz_ogre_vendor CMakeLists.txt +OGRE_CXX_FLAGS += " \ + -Wno-deprecated-declarations \ + -Wno-mismatched-new-delete \ + -Wno-range-loop-construct \ + -Wno-undef \ + -Wno-misleading-indentation \ + -Wno-implicit-const-int-float-conversion \ +" + +EXTRA_OECMAKE = " \ + -DSKIP_optix:BOOL=TRUE \ + -DCMAKE_CXX_FLAGS=${OGRE_CXX_FLAGS} \ +" + +DEPENDS = " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-math6 \ + ignition-plugin \ + freeimage \ + ogre \ +" + +OECMAKE_GENERATOR = "Unix Makefiles" + +FILES:${PN} += " \ + ${datadir}/ignition/* \ + ${libdir}/ign-rendering-6/engine-plugins/libignition-rendering6-ogre${SOLIBS} \ +" + +FILES:${PN}-dev += " \ + ${libdir}/ign-rendering-6/engine-plugins/libignition-rendering-ogre.so \ + ${libdir}/ign-rendering-6/engine-plugins/libignition-rendering6-ogre.so \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-sensors6_6.0.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-sensors6_6.0.0.bb new file mode 100644 index 00000000000..a565f1ec6ce --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-sensors6_6.0.0.bb @@ -0,0 +1,21 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=403837d405a17669732f6a98e3f42aed" + +SRC_URI = "git://github.com/gazebosim/gz-sensors.git;protocol=https;branch=ign-sensors6" + +SRCREV = "b0c61c5853f204372018161c5224c17dc523ad9c" + +S = "${WORKDIR}/git" + +DEPENDS += " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-math6 \ + ignition-msgs8 \ + ignition-rendering6 \ + ignition-transport11 \ + protobuf \ +" + +inherit cmake diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-tools1/backward-ros-include-dir.patch b/meta-ros-common/recipes-devtools/gazebo/ignition-tools1/backward-ros-include-dir.patch new file mode 100644 index 00000000000..85dfeae76c4 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-tools1/backward-ros-include-dir.patch @@ -0,0 +1,10 @@ +Index: git/src/backward.cc +=================================================================== +--- git.orig/src/backward.cc ++++ git/src/backward.cc +@@ -1,4 +1,4 @@ +-#include "backward.hpp" ++#include "backward_ros/backward.hpp" + + namespace ignition { + namespace tools { diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-tools1_15.0.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-tools1_15.0.bb new file mode 100644 index 00000000000..7df73b440d6 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-tools1_15.0.bb @@ -0,0 +1,39 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=ba86179b62e9e2c25dd9184dd87e2464" + +SRC_URI = " \ + git://github.com/gazebosim/gz-tools.git;protocol=https;branch=ign-tools1 \ + file://backward-ros-include-dir.patch \ +" + +SRCREV = "67d9d473aca6d33fb849e93e309cd678a75ccd71" + +S = "${WORKDIR}/git" + +inherit cmake + +EXTRA_OECMAKE = "-DUSE_SYSTEM_BACKWARDCPP:BOOL=ON" + +DEPENDS = " \ + doxygen \ + jsoncpp \ + libyaml \ + libzip \ + backward-ros \ +" + + +FILES:${PN} = " \ + ${bindir}/ign \ + ${libdir}/libignition-tools-backward.so \ + ${datadir}/bash-completion/completions/ign \ + ${datadir}/gz/gz1.completion \ +" + +FILES:${PN}-dev = " \ + ${libdir}/pkgconfig/ignition-tools.pc \ + ${libdir}/cmake/ignition-tools/ignition-tools-config.cmake \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-transport11_11.4.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-transport11_11.4.1.bb new file mode 100644 index 00000000000..049cfb79379 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-transport11_11.4.1.bb @@ -0,0 +1,38 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2a461be67a1edf991251f85f3aadd1d0" + +SRC_URI = "git://github.com/gazebosim/gz-transport.git;protocol=https;branch=ign-transport11" + +SRCREV = "69e9592544c36d4e10eed74953258662569d91fd" + +S = "${WORKDIR}/git" + +inherit cmake pkgconfig + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = " \ + ignition-cmake2 \ + ignition-msgs8 \ + ignition-utils1 \ + sqlite3 \ + util-linux-libuuid \ + zeromq \ + cppzmq \ +" + +RDEPENDS:${PN} += "ruby" + +FILES:${PN} += " \ + /usr/lib/ruby/gz/cmdtransport11.rb \ + /usr/lib/ruby/ignition/cmdparam11.rb \ + /usr/lib/ruby/ignition/cmdlog11.rb \ + /usr/share/gz/gz1.completion.d/transport11.bash_completion.sh \ + /usr/share/ignition/transport11.yaml \ + /usr/share/ignition/transportparam11.yaml \ + /usr/share/ignition/transportlog11.yaml \ + /usr/share/ignition/ignition-transport11/sql/0.1.0.sql \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/gazebo/ignition-utils1_1.5.1.bb b/meta-ros-common/recipes-devtools/gazebo/ignition-utils1_1.5.1.bb new file mode 100644 index 00000000000..c024b020734 --- /dev/null +++ b/meta-ros-common/recipes-devtools/gazebo/ignition-utils1_1.5.1.bb @@ -0,0 +1,20 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=881ceadb4a5b6db70a8a48a5f5f0050f \ + file://cli/LICENSE;md5=b73927b18d5c6cd8d2ed28a6ad539733" + +SRC_URI = "git://github.com/gazebosim/gz-utils.git;protocol=https;branch=ign-utils1" + +SRCREV = "36f5dfdbccd6cce7e02df14a2db19c6c2e784c49" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: ignition-cmake2 +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + +DEPENDS = "ignition-cmake2" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.2.0.patch b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.2.0.patch new file mode 100644 index 00000000000..9aae8066b48 --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.2.0.patch @@ -0,0 +1,75 @@ +Upstream-Status: Submitted [https://github.com/OGRECave/ogre-next/issues/430] + +From 480fb368e288f0a4e1c73f6b0a60f27743d5cb63 Mon Sep 17 00:00:00 2001 +From: bchoi +Date: Mon, 22 Jan 2024 16:22:31 +0900 +Subject: [PATCH] Fixed compile error + +--- + .../Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp | 2 +- + .../include/Math/Array/NEON/Single/OgreMathlibNEON.h | 2 +- + OgreMain/src/OgreDefaultSceneQueries.cpp | 2 +- + OgreMain/src/OgreMovableObject.cpp | 2 +- + Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt | 6 ++++-- + 4 files changed, 17 insertions(+), 7 deletions(-) + +Index: git/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h +=================================================================== +--- git.orig/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h ++++ git/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h +@@ -645,7 +645,7 @@ namespace Ogre + //Netwon-Raphson, 2 iterations. + ArrayReal fStep0 = vrsqrteq_f32( f ); + //Nuke NaN when f == 0 +- fStep0 = vreinterpretq_f32_u32( vandq_u32( vtstq_u32( f, f ), ++ fStep0 = vreinterpretq_f32_u32( vandq_u32( vtstq_u32((uint32x4_t)f, (uint32x4_t)f ), + vreinterpretq_u32_f32( fStep0 ) ) ); + // step fStep0 = 1 / sqrt(x) + const ArrayReal fStepParm0 = vmulq_f32( f, fStep0 ); +Index: git/OgreMain/src/OgreDefaultSceneQueries.cpp +=================================================================== +--- git.orig/OgreMain/src/OgreDefaultSceneQueries.cpp ++++ git/OgreMain/src/OgreDefaultSceneQueries.cpp +@@ -535,7 +535,7 @@ namespace Ogre { + { + //For each volume test all planes and AND the dot product. + //If one is false, then we dont intersect with this volume +- ArrayMaskR singleVolumeMask = CastIntToReal( Mathlib::SetAll( 0xffffffff ) ); ++ ArrayMaskR singleVolumeMask = (ArrayMaskR) CastIntToReal( Mathlib::SetAll( 0xffffffff ) ); + ArrayReal dotResult; + ArrayVector3 centerPlusFlippedHS; + +Index: git/OgreMain/src/OgreMovableObject.cpp +=================================================================== +--- git.orig/OgreMain/src/OgreMovableObject.cpp ++++ git/OgreMain/src/OgreMovableObject.cpp +@@ -472,7 +472,7 @@ namespace Ogre { + planes[i].planeNegD = Mathlib::SetAll( -frustumPlanes[i].d ); + } + +- const ArrayMaskR ignoreRenderingDistance = CastIntToReal( ++ const ArrayMaskR ignoreRenderingDistance = (ArrayMaskR) CastIntToReal( + Mathlib::SetAll( lodCamera->getUseRenderingDistance() ? 0 : 0xffffffff ) ); + + //TODO: Profile whether we should use XOR to flip the sign or simple multiplication. +Index: git/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +=================================================================== +--- git.orig/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt ++++ git/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +@@ -11,12 +11,14 @@ macro( add_recursive dir retVal ) + file( GLOB_RECURSE ${retVal} ${dir}/*.h ${dir}/*.cpp ${dir}/*.c ) + endmacro() + ++set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreMain) ++ + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include) + + add_recursive( ./ SOURCE_FILES ) + +-ogre_add_executable(Sample_AnimationTagPoint WIN32 MACOSX_BUNDLE ${SOURCE_FILES} ${SAMPLE_COMMON_RESOURCES}) ++ogre_add_executable(Sample_AnimationTagPoint ${SOURCE_FILES} ${SAMPLE_COMMON_RESOURCES}) + +-target_link_libraries(Sample_AnimationTagPoint ${OGRE_LIBRARIES} ${OGRE_SAMPLES_LIBRARIES}) ++target_link_libraries(Sample_AnimationTagPoint ${OGRE_SAMPLES_LIBRARIES} ${OGRE_LIBRARIES}) + ogre_config_sample_lib(Sample_AnimationTagPoint) + ogre_config_sample_pkg(Sample_AnimationTagPoint) diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.3.3.patch b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.3.3.patch new file mode 100644 index 00000000000..fc6593d67d2 --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-compile-error-2.3.3.patch @@ -0,0 +1,118 @@ +Upstream-Status: Submitted [https://github.com/OGRECave/ogre-next/issues/430] + +From 480fb368e288f0a4e1c73f6b0a60f27743d5cb63 Mon Sep 17 00:00:00 2001 +From: bchoi +Date: Mon, 22 Jan 2024 16:22:31 +0900 +Subject: [PATCH] Fixed compile error + +--- + .../Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp | 2 +- + .../include/Math/Array/NEON/Single/OgreMathlibNEON.h | 2 +- + OgreMain/src/OgreDefaultSceneQueries.cpp | 2 +- + OgreMain/src/OgreMovableObject.cpp | 2 +- + Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt | 6 ++++-- + Tools/CmgenToCubemap/CMakeLists.txt | 10 +++++++++- + 6 files changed, 17 insertions(+), 7 deletions(-) + +diff --git a/Components/Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp b/Components/Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp +index 797f3d68a8..852dab96ec 100644 +--- a/Components/Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp ++++ b/Components/Hlms/Pbs/src/Vct/OgreVctCascadedVoxelizer.cpp +@@ -29,8 +29,8 @@ THE SOFTWARE. + #include "OgreStableHeaders.h" + + #include "Vct/OgreVctCascadedVoxelizer.h" +- + #include "Compositor/OgreCompositorManager2.h" ++#include "Math/Array/OgreMathlib.h" + #include "Math/Array/OgreBooleanMask.h" + #include "OgreItem.h" + #include "OgreSceneManager.h" +diff --git a/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h b/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h +index 94f7bdfd1d..6cfea95135 100644 +--- a/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h ++++ b/OgreMain/include/Math/Array/NEON/Single/OgreMathlibNEON.h +@@ -601,7 +601,7 @@ namespace Ogre + //Netwon-Raphson, 2 iterations. + ArrayReal fStep0 = vrsqrteq_f32( f ); + //Nuke NaN when f == 0 +- fStep0 = vreinterpretq_f32_u32( vandq_u32( vtstq_u32( f, f ), ++ fStep0 = vreinterpretq_f32_u32( vandq_u32( vtstq_u32((uint32x4_t)f, (uint32x4_t)f ), + vreinterpretq_u32_f32( fStep0 ) ) ); + // step fStep0 = 1 / sqrt(x) + const ArrayReal fStepParm0 = vmulq_f32( f, fStep0 ); +diff --git a/OgreMain/src/OgreDefaultSceneQueries.cpp b/OgreMain/src/OgreDefaultSceneQueries.cpp +index b275a7df66..3dee473700 100644 +--- a/OgreMain/src/OgreDefaultSceneQueries.cpp ++++ b/OgreMain/src/OgreDefaultSceneQueries.cpp +@@ -537,7 +537,7 @@ namespace Ogre { + { + //For each volume test all planes and AND the dot product. + //If one is false, then we dont intersect with this volume +- ArrayMaskR singleVolumeMask = CastIntToReal( Mathlib::SetAll( 0xffffffff ) ); ++ ArrayMaskR singleVolumeMask = (ArrayMaskR) CastIntToReal( Mathlib::SetAll( 0xffffffff ) ); + ArrayReal dotResult; + ArrayVector3 centerPlusFlippedHS; + +diff --git a/OgreMain/src/OgreMovableObject.cpp b/OgreMain/src/OgreMovableObject.cpp +index 860e405c9a..16fcd67f1c 100644 +--- a/OgreMain/src/OgreMovableObject.cpp ++++ b/OgreMain/src/OgreMovableObject.cpp +@@ -500,7 +500,7 @@ namespace Ogre { + planes[i].planeNegD = Mathlib::SetAll( -frustumPlanes[i].d ); + } + +- const ArrayMaskR ignoreRenderingDistance = CastIntToReal( ++ const ArrayMaskR ignoreRenderingDistance = (ArrayMaskR) CastIntToReal( + Mathlib::SetAll( lodCamera->getUseRenderingDistance() ? 0 : 0xffffffff ) ); + + //TODO: Profile whether we should use XOR to flip the sign or simple multiplication. +diff --git a/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt b/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +index c19bdd5cce..8b9a115aab 100644 +--- a/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt ++++ b/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +@@ -11,12 +11,14 @@ macro( add_recursive dir retVal ) + file( GLOB_RECURSE ${retVal} ${dir}/*.h ${dir}/*.cpp ${dir}/*.c ) + endmacro() + ++set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreMain) ++ + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include) + + add_recursive( ./ SOURCE_FILES ) + +-ogre_add_executable(Sample_AnimationTagPoint WIN32 MACOSX_BUNDLE ${SOURCE_FILES} ${SAMPLE_COMMON_RESOURCES}) ++ogre_add_executable(Sample_AnimationTagPoint ${SOURCE_FILES} ${SAMPLE_COMMON_RESOURCES}) + +-target_link_libraries(Sample_AnimationTagPoint ${OGRE_LIBRARIES} ${OGRE_SAMPLES_LIBRARIES}) ++target_link_libraries(Sample_AnimationTagPoint ${OGRE_SAMPLES_LIBRARIES} ${OGRE_LIBRARIES}) + ogre_config_sample_lib(Sample_AnimationTagPoint) + ogre_config_sample_pkg(Sample_AnimationTagPoint) +diff --git a/Tools/CmgenToCubemap/CMakeLists.txt b/Tools/CmgenToCubemap/CMakeLists.txt +index c3d67a6c0c..c55fa27bf4 100644 +--- a/Tools/CmgenToCubemap/CMakeLists.txt ++++ b/Tools/CmgenToCubemap/CMakeLists.txt +@@ -13,11 +13,19 @@ macro( add_recursive dir retVal ) + file( GLOB_RECURSE ${retVal} ${dir}/*.h ${dir}/*.cpp ${dir}/*.c ) + endmacro() + ++find_package(JPEG REQUIRED) ++find_package(PNG REQUIRED) ++find_package(TIFF REQUIRED) ++find_package(ZLIB REQUIRED) ++ ++set(PICTURE_LIBS ${JPEG} ${PNG} ${TIFF} ${ZLIB}) ++set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}Main) ++ + add_recursive( ./ SOURCE_FILES ) + + ogre_add_executable(OgreCmgenToCubemap ${SOURCE_FILES}) + +-target_link_libraries(OgreCmgenToCubemap ${OGRE_LIBRARIES}) ++target_link_libraries(OgreCmgenToCubemap ${OGRE_LIBRARIES} ${PICTURE_LIBS}) + + if (APPLE) + set_target_properties(OgreCmgenToCubemap PROPERTIES +-- +2.25.1 + diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-macOS-build.patch b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-macOS-build.patch new file mode 100644 index 00000000000..08855c450a7 --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Fixed-macOS-build.patch @@ -0,0 +1,53 @@ +From 16e2bd3c06fee6039d411c9f2867985fd931e492 Mon Sep 17 00:00:00 2001 +From: Eugene Golushkov +Date: Thu, 3 Dec 2020 12:35:58 +0200 +Subject: [PATCH] Fixed macOS build + +--- + OgreMain/src/OgrePlatformInformation.cpp | 27 +++++++----------------- + 1 file changed, 8 insertions(+), 19 deletions(-) + +Index: git/OgreMain/src/OgrePlatformInformation.cpp +=================================================================== +--- git.orig/OgreMain/src/OgrePlatformInformation.cpp ++++ git/OgreMain/src/OgrePlatformInformation.cpp +@@ -39,31 +39,19 @@ THE SOFTWARE. + #elif (OGRE_COMPILER == OGRE_COMPILER_GNUC || OGRE_COMPILER == OGRE_COMPILER_CLANG) && OGRE_PLATFORM != OGRE_PLATFORM_NACL + #include + #include +-#if OGRE_PLATFORM != OGRE_PLATFORM_WIN32 +- #if OGRE_PLATFORM == OGRE_PLATFORM_ANDROID +- #include +- #else +- #include +- #endif + #endif + +- #if OGRE_PLATFORM == OGRE_PLATFORM_ANDROID +- #include +- #elif OGRE_CPU == OGRE_CPU_ARM +- #if __MACH__ +- #include +- #ifndef CPU_SUBTYPE_ARM64_V8 +- #define CPU_SUBTYPE_ARM64_V8 ((cpu_subtype_t) 1) +- #endif +- #ifndef CPU_SUBTYPE_ARM_V8 +- #define CPU_SUBTYPE_ARM_V8 ((cpu_subtype_t) 13) +- #endif +- #endif +- #endif ++#if OGRE_PLATFORM == OGRE_PLATFORM_ANDROID ++ #include ++ #include ++#endif ++#if OGRE_PLATFORM == OGRE_PLATFORM_APPLE || OGRE_PLATFORM == OGRE_PLATFORM_APPLE_IOS ++ #include ++ #include + #endif + + #if OGRE_PLATFORM == OGRE_PLATFORM_WIN32 || OGRE_PLATFORM == OGRE_PLATFORM_WINRT +- #include "windows.h" ++ #include + #endif + + // Yes, I know, this file looks very ugly, but there aren't other ways to do it better. diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Neon-is-architectural-for-AArch64.patch b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Neon-is-architectural-for-AArch64.patch new file mode 100644 index 00000000000..d5a160942bc --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0001-Neon-is-architectural-for-AArch64.patch @@ -0,0 +1,25 @@ +From f2769df973af39e56538c70ebf2950929135f777 Mon Sep 17 00:00:00 2001 +From: Eugene Golushkov +Date: Mon, 15 Nov 2021 19:41:27 +0200 +Subject: [PATCH] Neon is architectural for AArch64 + +--- + OgreMain/include/OgrePlatform.h | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +diff --git a/OgreMain/include/OgrePlatform.h b/OgreMain/include/OgrePlatform.h +index 8a9826bd80..c94904aebe 100644 +--- a/OgreMain/include/OgrePlatformInformation.h ++++ b/OgreMain/include/OgrePlatformInformation.h +@@ -101,7 +101,7 @@ + + /* Define whether or not Ogre compiled with NEON support. + */ +- #if OGRE_DOUBLE_PRECISION == 0 && OGRE_CPU == OGRE_CPU_ARM && (OGRE_COMPILER == OGRE_COMPILER_GNUC || OGRE_COMPILER == OGRE_COMPILER_CLANG) && defined(__ARM_NEON__) ++ #if OGRE_DOUBLE_PRECISION == 0 && OGRE_CPU == OGRE_CPU_ARM && ( defined(__aarch64__) || defined(__ARM_NEON__) ) + # define __OGRE_HAVE_NEON 1 + #endif + #endif +-- +2.43.0 + diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0002-Use_OGRE_NEXT_prefix_for_libraries.patch b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0002-Use_OGRE_NEXT_prefix_for_libraries.patch new file mode 100644 index 00000000000..440f07251cc --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next/0002-Use_OGRE_NEXT_prefix_for_libraries.patch @@ -0,0 +1,75 @@ +Index: git/CMake/Templates/OGREConfig.cmake.in +=================================================================== +--- git.orig/CMake/Templates/OGREConfig.cmake.in ++++ git/CMake/Templates/OGREConfig.cmake.in +@@ -21,7 +21,7 @@ include(FindPackageMessage) + set(OGRE_PREFIX_DIR "@CMAKE_INSTALL_PREFIX@") + get_filename_component(OGRE_LIBRARY_DIRS "${OGRE_PREFIX_DIR}/lib" ABSOLUTE) + get_filename_component(OGRE_INCLUDE_DIRS "${OGRE_PREFIX_DIR}/include/OGRE" ABSOLUTE) +-set(OGRE_LIBRARIES "OgreMain") ++set(OGRE_LIBRARIES "@OGRE_NEXT@Main") + + message(STATUS "Found OGRE") + message(STATUS " libraries : '${OGRE_LIBRARIES}' from ${OGRE_LIBRARY_DIRS}") +Index: git/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +=================================================================== +--- git.orig/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt ++++ git/Samples/2.0/ApiUsage/AnimationTagPoint/CMakeLists.txt +@@ -11,7 +11,7 @@ macro( add_recursive dir retVal ) + file( GLOB_RECURSE ${retVal} ${dir}/*.h ${dir}/*.cpp ${dir}/*.c ) + endmacro() + +-set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreMain) ++set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}Main) + + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include) + +Index: git/Tests/CMakeLists.txt +=================================================================== +--- git.orig/Tests/CMakeLists.txt ++++ git/Tests/CMakeLists.txt +@@ -113,7 +113,7 @@ if (OGRE_BUILD_TESTS) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/Components/Paging/include) + ogre_add_component_include_dir(Paging) + +- set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgrePaging) ++ set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}Paging) + list(APPEND HEADER_FILES Components/Paging/include/PageCoreTests.h) + list(APPEND SOURCE_FILES Components/Paging/src/PageCoreTests.cpp) + endif () +@@ -121,7 +121,7 @@ if (OGRE_BUILD_TESTS) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/Components/MeshLodGenerator/include) + ogre_add_component_include_dir(MeshLodGenerator) + +- set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreMeshLodGenerator) ++ set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}MeshLodGenerator) + list(APPEND HEADER_FILES Components/MeshLodGenerator/include/MeshLodTests.h) + list(APPEND SOURCE_FILES Components/MeshLodGenerator/src/MeshLodTests.cpp) + endif () +@@ -129,7 +129,7 @@ if (OGRE_BUILD_TESTS) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/Components/Terrain/include) + ogre_add_component_include_dir(Terrain) + +- set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreTerrain) ++ set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}Terrain) + list(APPEND HEADER_FILES Components/Terrain/include/TerrainTests.h) + list(APPEND SOURCE_FILES Components/Terrain/src/TerrainTests.cpp) + endif () +@@ -137,7 +137,7 @@ if (OGRE_BUILD_TESTS) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/Components/Property/include + ${OGRE_SOURCE_DIR}/Components/Property/include) + +- set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreProperty) ++ set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}Property) + list(APPEND HEADER_FILES Components/Property/include/PropertyTests.h) + list(APPEND SOURCE_FILES Components/Property/src/PropertyTests.cpp) + endif () +@@ -265,7 +265,7 @@ if (OGRE_BUILD_TESTS) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/Components/MeshLodGenerator/include) + ogre_add_component_include_dir(MeshLodGenerator) + +- set(OGRE_LIBRARIES ${OGRE_LIBRARIES} OgreMeshLodGenerator) ++ set(OGRE_LIBRARIES ${OGRE_LIBRARIES} ${OGRE_NEXT}MeshLodGenerator) + list(APPEND HEADER_FILES Components/MeshLodGenerator/include/MeshLodTests.h) + list(APPEND SOURCE_FILES Components/MeshLodGenerator/src/MeshLodTests.cpp) + endif () diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.2.0.bb b/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.2.0.bb new file mode 100644 index 00000000000..09e5f600b5f --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.2.0.bb @@ -0,0 +1,68 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +LICENSE = "MIT & Unknown" +LIC_FILES_CHKSUM = "file://CMake/Templates/DemoLicense.rtf;md5=2711c49576d18cf781ec81aad76f40d6 \ + file://COPYING;md5=65d1ee510d57bbd05663424f2ff8d660 \ + file://OgreMain/src/nedmalloc/License.txt;md5=e4224ccaecb14d942c71d31bef20d78c \ + file://Samples/Media/DeferredShadingMedia/COPYING;md5=e3b8d8073136f13f04ebb6f8b84efba6 \ + file://Samples/Media/materials/textures/Cubemaps/License.txt;md5=81b3db517e68c27c535791b2276d5ffd \ + file://Tools/Common/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595 \ + file://Tools/MaterialEditor/wxscintilla_1.69.2/src/scintilla/License.txt;md5=d680acd8db69807fdfb587a342690eac \ + file://Tools/MilkshapeExport/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595 \ + file://Tools/XSIExport/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595" + +SRC_URI = "git://github.com/OGRECave/ogre-next.git;protocol=https;branch=master \ + file://0001-Fixed-compile-error-2.2.0.patch \ + file://0001-Neon-is-architectural-for-AArch64.patch \ + file://0001-Fixed-macOS-build.patch \ +" + +PV = "2.2.0" +SRCREV = "6a814a02e69dfe3c006baf8ec6399aeb611452ca" + +S = "${WORKDIR}/git" + +inherit cmake features_check pkgconfig + +DEPENDS = " \ + cppunit \ + doxygen-native \ + freeimage \ + freetype \ + libsdl2 \ + libx11 \ + libxaw \ + rapidjson \ + renderdoc \ + tbb \ + libtinyxml \ + zlib \ + ${@bb.utils.contains('DISTRO_FEATURES', 'opengl', 'virtual/libgl libglu', '', d)} \ +" + +FILES:${PN}-dev += "${libdir}/OGRE-Next/cmake ${libdir}/OGRE-Next/*${SOLIBSDEV}" +FILES:${PN} += "${datadir}/OGRE-Next ${libdir}/OGRE-Next" + +REQUIRED_DISTRO_FEATURES = "x11" + +EXTRA_OECMAKE += " \ + -DOGRE_SIMD_NEON:BOOL=FALSE \ + -DOGRE_SIMD_SSE2:BOOL=FALSE \ +" + +do_install:append() { + # pkgconfig + sed -i -e "s|/OGRE|/OGRE-Next|g" ${D}${libdir}/pkgconfig/*.pc + + # CMake + sed -i -e "s|share/OGRE/media|share/OGRE-Next/media|g" ${D}${libdir}/OGRE/cmake/FindOGRE.cmake + mv ${D}${libdir}/OGRE/cmake/FindOGRE.cmake ${D}${libdir}/OGRE/cmake/FindOGRE2.cmake + + # Data files + sed -i -e "s|${datadir}/OGRE|${datadir}/OGRE-Next|g" ${D}${datadir}/OGRE/resources.cfg + sed -i -e "s|share/OGRE/docs|share/OGRE-Next/docs|g" ${D}${datadir}/OGRE/docs/CMakeLists.txt + + mv ${D}${datadir}/OGRE ${D}${datadir}/OGRE-Next + + mv ${D}${libdir}/OGRE ${D}${libdir}/OGRE-Next +} diff --git a/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.3.3.bb b/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.3.3.bb new file mode 100644 index 00000000000..0d07c3530d7 --- /dev/null +++ b/meta-ros-common/recipes-devtools/ogre-next/ogre-next_2.3.3.bb @@ -0,0 +1,64 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +LICENSE = "MIT & Unknown" +LIC_FILES_CHKSUM = "file://CMake/Templates/DemoLicense.rtf;md5=2711c49576d18cf781ec81aad76f40d6 \ + file://COPYING;md5=65d1ee510d57bbd05663424f2ff8d660 \ + file://OgreMain/src/nedmalloc/License.txt;md5=e4224ccaecb14d942c71d31bef20d78c \ + file://Samples/Media/DeferredShadingMedia/COPYING;md5=e3b8d8073136f13f04ebb6f8b84efba6 \ + file://Samples/Media/materials/textures/Cubemaps/License.txt;md5=81b3db517e68c27c535791b2276d5ffd \ + file://Tools/Common/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595 \ + file://Tools/MaterialEditor/wxscintilla_1.69.2/src/scintilla/License.txt;md5=d680acd8db69807fdfb587a342690eac \ + file://Tools/MilkshapeExport/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595 \ + file://Tools/XSIExport/setup/License.rtf;md5=e1311ad52d6fe736b3819ce831a2a595" + +SRC_URI = "git://github.com/OGRECave/ogre-next.git;protocol=https;branch=master \ + file://0001-Fixed-compile-error-2.3.3.patch \ + file://0002-Use_OGRE_NEXT_prefix_for_libraries.patch" + +PV = "2.3.3" +SRCREV = "8d4daeaf46d7d8f85f1833f17daedd7dac05daec" + +S = "${WORKDIR}/git" + +inherit cmake features_check pkgconfig + +DEPENDS = " \ + cppunit \ + doxygen-native \ + freeimage \ + freetype \ + glslang \ + libsdl2 \ + libtinyxml2 \ + libx11 \ + libxaw \ + libxcb \ + libxrandr \ + rapidjson \ + renderdoc \ + mesa \ + poco \ + shaderc \ + tbb \ + vulkan-headers \ + zlib \ + zziplib \ + ${@bb.utils.contains('DISTRO_FEATURES', 'opengl', 'virtual/libgl libglu', '', d)} \ +" + +EXTRA_OECMAKE += " \ + -DOGRE_USE_NEW_PROJECT_NAME=ON \ + -DOGRE_FULL_RPATH:BOOL=FALSE \ + -DOGRE_BUILD_RENDERSYSTEM_GLES2:BOOL=TRUE \ + -DOGRE_BUILD_DOCS:BOOL=TRUE \ + -DOGRE_INSTALL_DOCS:BOOL=TRUE \ + -DOGRE_BUILD_SAMPLES:BOOL=FALSE \ + -DOGRE_INSTALL_SAMPLES:BOOL=FALSE \ + -DOGRE_INSTALL_SAMPLES_SOURCE:BOOL=FALSE \ +" + +FILES:${PN}-dev += "${libdir}/OGRE-Next/cmake ${libdir}/OGRE-Next/*${SOLIBSDEV}" +FILES:${PN} += "${datadir}/OGRE-Next ${libdir}/OGRE-Next" + + +REQUIRED_DISTRO_FEATURES = "x11" diff --git a/meta-ros-common/recipes-devtools/python/python3-colorcet_3.0.1.bb b/meta-ros-common/recipes-devtools/python/python3-colorcet_3.0.1.bb new file mode 100644 index 00000000000..4c9620348af --- /dev/null +++ b/meta-ros-common/recipes-devtools/python/python3-colorcet_3.0.1.bb @@ -0,0 +1,17 @@ +SUMMARY = "Collection of perceptually uniform colormaps" +DESCRIPTION = "Colorcet is a collection of perceptually uniform colormaps for \ + use with Python plotting programs like bokeh, matplotlib, holoviews, and \ + datashader based on the set of perceptually uniform colormaps created by \ + Peter Kovesi at the Center for Exploration Targeting." +HOMEPAGE = "https://colorcet.holoviz.org/" + +LICENSE = "CC-BY-4.0" +LIC_FILES_CHKSUM = "file://LICENSE.txt;md5=b443afaf131aa64a6644f9bd3383f208" + +PYPI_PACKAGE = "colorcet" + +inherit pypi setuptools3 + +DEPENDS += "python3-pyct-native python3-param-native" + +SRC_URI[sha256sum] = "51455a20353d12fac91f953772d8409f2474e6a0db1af3fa4f7005f405a2480b" diff --git a/meta-ros-common/recipes-devtools/python/python3-param_1.13.0.bb b/meta-ros-common/recipes-devtools/python/python3-param_1.13.0.bb new file mode 100644 index 00000000000..c280b661eae --- /dev/null +++ b/meta-ros-common/recipes-devtools/python/python3-param_1.13.0.bb @@ -0,0 +1,17 @@ +SUMMARY = "Make your Python code clearer and more reliable by declaring Parameters." +DESCRIPTION = "Param is a library providing Parameters: Python attributes \ + extended to have features such as type and range checking, dynamically \ + generated values, documentation strings, default values, etc., each of \ + which is inherited from parent classes if not specified in a subclass." +HOMEPAGE = "https://pypi.org/project/param/" + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM = "file://LICENSE.txt;md5=120197d29d1cf583abd283ef26669576" + +PYPI_PACKAGE = "param" + +inherit pypi setuptools3 + +SRC_URI[sha256sum] = "59d55048d42a85e148a69837df42bd11c3391d47fad15ba57d118e145f001ef2" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/python/python3-pyct_0.5.0.bb b/meta-ros-common/recipes-devtools/python/python3-pyct_0.5.0.bb new file mode 100644 index 00000000000..d9913a39c3b --- /dev/null +++ b/meta-ros-common/recipes-devtools/python/python3-pyct_0.5.0.bb @@ -0,0 +1,14 @@ +SUMMARY = "Python package common tasks for users (e.g. copy examples, fetch data, ...)" +DESCRIPTION = "A utility package that includes pyct.cmd and pyct.build" +HOMEPAGE = "https://github.com/pyviz-dev/pyct" + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM = "file://LICENSE.txt;md5=a5a58acaa3e8f6b6011f5a17eacc6e1e" + +PYPI_PACKAGE = "pyct" + +inherit pypi setuptools3 + +SRC_URI[sha256sum] = "dd9f4ac5cbd8e37c352c04036062d3c5f67efec76d404761ef16b0cbf26aa6a0" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-devtools/sip/sip/sip-build-cross-platform-support.patch b/meta-ros-common/recipes-devtools/sip/sip/sip-build-cross-platform-support.patch new file mode 100644 index 00000000000..7e33572d09b --- /dev/null +++ b/meta-ros-common/recipes-devtools/sip/sip/sip-build-cross-platform-support.patch @@ -0,0 +1,37 @@ +sip-build: Cross platform build support + +Projects may use the PyQtBuilder in pyproject.toml to automatically +generate the build files and execute the build. + +PyQtBuilder/builder.py invokes buildable.get_module_extension() to +create rules in QMake project files for building Python extensions +for the target. + +However, this determines the module extension using the importlib module. +This provides the extension suffix used for Python modules that +may be imported. However, this is incorrect when running Python +in a cross-build environment. For OpenEmbedded, the correct +extension suffix for the target may be obtained by referring to +the sysconfig EXT_SUFFIX configuration variable. + +Signed-off-by: Rob Woolley + +--- a/sipbuild/buildable.py ++++ b/sipbuild/buildable.py +@@ -150,14 +150,8 @@ class BuildableModule(BuildableFromSourc + if self.project.py_platform == 'win32': + return '.pyd' + +- from importlib.machinery import EXTENSION_SUFFIXES +- +- if self.uses_limited_api: +- for s in EXTENSION_SUFFIXES: +- if '.abi3' in s: +- return s +- +- return EXTENSION_SUFFIXES[0] ++ import sysconfig ++ return sysconfig.get_config_var('EXT_SUFFIX') + + + class BuildableBindings(BuildableModule): diff --git a/meta-ros-common/recipes-devtools/sip/sip_6.8.3.bbappend b/meta-ros-common/recipes-devtools/sip/sip_6.8.3.bbappend new file mode 100644 index 00000000000..dd515283e73 --- /dev/null +++ b/meta-ros-common/recipes-devtools/sip/sip_6.8.3.bbappend @@ -0,0 +1,4 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +SRC_URI += "file://sip-build-cross-platform-support.patch" diff --git a/meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.6.2.bb b/meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.8.0.bb similarity index 93% rename from meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.6.2.bb rename to meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.8.0.bb index bea6a320a30..244c03e1581 100644 --- a/meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.6.2.bb +++ b/meta-ros-common/recipes-devtools/yaml-cpp/yaml-cpp_0.8.0.bb @@ -9,7 +9,7 @@ PR = "r0" S = "${WORKDIR}/git" SRC_URI = "git://github.com/jbeder/${BPN}.git;branch=master;protocol=https" -SRCREV = "562aefc114938e388457e6a531ed7b54d9dc1b62" +SRCREV = "f7320141120f720aecc4c32be25586e7da9eb978" EXTRA_OECMAKE = "-DBUILD_SHARED_LIBS=ON -DYAML_CPP_BUILD_TESTS=OFF -DYAML_CPP_BUILD_TOOLS=OFF -DYAML_CPP_BUILD_CONTRIB=OFF" diff --git a/meta-ros-common/recipes-extended/libdeflate/libdeflate_1.19.bb b/meta-ros-common/recipes-extended/libdeflate/libdeflate_1.19.bb new file mode 100644 index 00000000000..11cdb829052 --- /dev/null +++ b/meta-ros-common/recipes-extended/libdeflate/libdeflate_1.19.bb @@ -0,0 +1,15 @@ +SUMMARY = "libdeflate is a library for fast, whole-buffer DEFLATE-based compression and decompression." +HOMEPAGE = "https://github.com/ebiggers/libdeflate" +LICENSE = "MIT" + +LIC_FILES_CHKSUM = "file://COPYING;md5=7b6977026437092191e9da699ed9f780" + +DEPENDS += "gzip zlib" + +SRC_URI = "git://github.com/ebiggers/libdeflate.git;protocol=https;branch=master" + +S = "${WORKDIR}/git" +SRCREV = "dd12ff2b36d603dbb7fa8838fe7e7176fcbd4f6f" + +inherit cmake pkgconfig + diff --git a/meta-ros-common/recipes-extended/libfreenect/libfreenect_0.5.2.bb b/meta-ros-common/recipes-extended/libfreenect/libfreenect_0.6.4.bb similarity index 80% rename from meta-ros-common/recipes-extended/libfreenect/libfreenect_0.5.2.bb rename to meta-ros-common/recipes-extended/libfreenect/libfreenect_0.6.4.bb index 40984270ed1..c70720f6e86 100644 --- a/meta-ros-common/recipes-extended/libfreenect/libfreenect_0.5.2.bb +++ b/meta-ros-common/recipes-extended/libfreenect/libfreenect_0.6.4.bb @@ -4,7 +4,7 @@ LIC_FILES_CHKSUM = "file://GPL2;md5=eb723b61539feef013de476e68b5c50a" DEPENDS = "libusb1 freeglut libxi libxmu" -SRCREV = "10a80abf425975e66b23898fdfa907a937e2391a" +SRCREV = "f6de60f5291258920ca7d03e8d593f1bab3f7867" ROS_BRANCH ?= "branch=master" SRC_URI = "git://github.com/OpenKinect/libfreenect;${ROS_BRANCH};protocol=https" @@ -13,13 +13,13 @@ S = "${WORKDIR}/git" inherit cmake #force libs always into /usr/lib, even when compiling on 64bit arch -EXTRA_OECMAKE += " -DLIB_SUFFIX=''" +##EXTRA_OECMAKE += " -DLIB_SUFFIX=''" FILES:${PN} += "\ - ${libdir}/fakenect/${BPN}.so.* \ + ${libdir}/fakenect/*.so.* \ ${datadir}/fwfetcher.py \ " -FILES:${PN}-dev += "${libdir}/fakenect/${BPN}.so" +FILES:${PN}-dev += "${libdir}/fakenect/*.so" FILES:${PN}-dbg += "${libdir}/fakenect/.debug" RDEPENDS:${PN} += "bash" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-7.7.0.inc b/meta-ros-common/recipes-extended/suitesparse/suitesparse-7.7.0.inc new file mode 100644 index 00000000000..5101d862272 --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-7.7.0.inc @@ -0,0 +1,13 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +SUMMARY = "SuiteSparse is a suite of sparse matrix algorithms" +DESCRIPTION = "SuiteSparse is a suite of sparse matrix algorithms, including: UMFPACK(multifrontal LU factorization), CHOLMOD(supernodal Cholesky, with CUDA acceleration), SPQR(multifrontal QR) and many other packages." + +LIC_FILES_CHKSUM = "file://../LICENSE.txt;md5=f412ac88bc7d8314b59d3d103e0ffb75" + +S = "${WORKDIR}/git" + +SRC_URI = "git://github.com/DrTimothyAldenDavis/SuiteSparse.git;branch=stable;protocol=https" + +SRCREV = "13806726cbf470914d012d132a85aea1aff9ee77" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_2.4.6.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_2.4.6.bb index 7d28b9fff97..7c3e9516ff1 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_2.4.6.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_2.4.6.bb @@ -10,7 +10,7 @@ DEPENDS = " \ " -S = "${WORKDIR}/SuiteSparse/AMD" +S = "${WORKDIR}/git/AMD" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_3.3.2.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_3.3.2.bb new file mode 100644 index 00000000000..4086dbc3590 --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-amd_3.3.2.bb @@ -0,0 +1,22 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=5ba3300acc9ddc20a56f6c843e2d5e13" + +DEPENDS = " \ + suitesparse-config \ +" + +S = "${WORKDIR}/git/AMD" + +inherit cmake pkgconfig + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-amd-2.4.6-r0 do_package_qa: QA Issue: package suitesparse-amd contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-amd/2.4.6-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-amd/2.4.6-r0/packages-split/suitesparse-amd/usr/lib/libamd.so.2.4.6 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_2.4.6.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_2.4.6.bb index 6e48af2e5c0..16632727dfc 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_2.4.6.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_2.4.6.bb @@ -9,7 +9,7 @@ DEPENDS = " \ suitesparse-config \ " -S = "${WORKDIR}/SuiteSparse/CAMD" +S = "${WORKDIR}/git/CAMD" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_3.3.2.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_3.3.2.bb new file mode 100644 index 00000000000..41626f3c3a3 --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-camd_3.3.2.bb @@ -0,0 +1,22 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=9207c2ee27101a898ff5fc1c60636cee" + +DEPENDS = " \ + suitesparse-config \ +" + +S = "${WORKDIR}/git/CAMD" + +inherit cmake pkgconfig + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-camd-2.4.6-r0 do_package_qa: QA Issue: package suitesparse-camd contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-camd/2.4.6-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-camd/2.4.6-r0/packages-split/suitesparse-camd/usr/lib/libcamd.so.2.4.6 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_2.9.6.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_2.9.6.bb index 6063eecee21..efeebcc4610 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_2.9.6.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_2.9.6.bb @@ -9,7 +9,7 @@ DEPENDS = " \ suitesparse-config \ " -S = "${WORKDIR}/SuiteSparse/CCOLAMD" +S = "${WORKDIR}/git/CCOLAMD" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_3.3.3.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_3.3.3.bb new file mode 100644 index 00000000000..deafcfd4e40 --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-ccolamd_3.3.3.bb @@ -0,0 +1,22 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=6f2bad59ec6185e681f66425faaf13f6" + +DEPENDS = " \ + suitesparse-config \ +" + +S = "${WORKDIR}/git/CCOLAMD" + +inherit cmake pkgconfig + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-ccolamd-2.9.6-r0 do_package_qa: QA Issue: package suitesparse-ccolamd contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-ccolamd/2.9.6-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-ccolamd/2.9.6-r0/packages-split/suitesparse-ccolamd/usr/lib/libccolamd.so.2.9.6 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.4.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.2.1.bb similarity index 69% rename from meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.4.0.bb rename to meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.2.1.bb index 39037b80f57..92e408ccb57 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.4.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cholmod_5.2.1.bb @@ -1,9 +1,10 @@ # Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. -require suitesparse-5.4.0.inc +require suitesparse-7.7.0.inc LICENSE = "LGPL-2.1-or-later" -LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=5d8c39b6ee2eb7c9e0e226a333be30cc" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=56def293641dc4b931815801e87b5aea" DEPENDS = " \ suitesparse-config \ @@ -11,23 +12,15 @@ DEPENDS = " \ suitesparse-colamd \ suitesparse-ccolamd \ suitesparse-camd \ - suitesparse-metis \ lapack \ openblas \ " -S = "${WORKDIR}/SuiteSparse/CHOLMOD" +S = "${WORKDIR}/git/CHOLMOD" -EXTRA_OEMAKE = "CC='${CC}' BLAS='-lblas'" +inherit cmake pkgconfig -do_compile() { - # build only the library, not the demo - oe_runmake library -} - -do_install() { - oe_runmake install INSTALL=${D}${prefix} -} +EXTRA_OECMAKE = "-DSUITESPARSE_USE_64BIT_BLAS=ON -DBLA_PREFER_PKGCONFIG=ON" DEPENDS:append:class-target = " chrpath-replacement-native" # For some reason ends with bad RPATH diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_2.9.6.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_2.9.6.bb index 5f2a4aaa18a..74fc234d5be 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_2.9.6.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_2.9.6.bb @@ -9,7 +9,7 @@ DEPENDS = " \ suitesparse-config \ " -S = "${WORKDIR}/SuiteSparse/COLAMD" +S = "${WORKDIR}/git/COLAMD" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_3.3.3.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_3.3.3.bb new file mode 100644 index 00000000000..95f689a649f --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-colamd_3.3.3.bb @@ -0,0 +1,22 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=93997dd55f2c98be2351a1e84f528ecc" + +DEPENDS = " \ + suitesparse-config \ +" + +S = "${WORKDIR}/git/COLAMD" + +inherit cmake pkgconfig + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-colamd-2.9.6-r0 do_package_qa: QA Issue: package suitesparse-colamd contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-colamd/2.9.6-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-colamd/2.9.6-r0/packages-split/suitesparse-colamd/usr/lib/libcolamd.so.2.9.6 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_5.4.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_5.4.0.bb index 7de4f7bdddb..af36f5eada0 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_5.4.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_5.4.0.bb @@ -5,7 +5,7 @@ require suitesparse-5.4.0.inc LICENSE = "PD" LIC_FILES_CHKSUM += "file://README.txt;md5=9da0dd2832f2ab6d304cae1d28eecc11" -S = "${WORKDIR}/SuiteSparse/SuiteSparse_config" +S = "${WORKDIR}/git/SuiteSparse_config" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_7.7.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_7.7.0.bb new file mode 100644 index 00000000000..15306b77da9 --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-config_7.7.0.bb @@ -0,0 +1,22 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "PD" +LIC_FILES_CHKSUM += "file://README.txt;md5=dabbb8fc940f88cfe4fde254fad9dd68" + +S = "${WORKDIR}/git/SuiteSparse_config" + +inherit cmake pkgconfig + +DEPENDS = "openblas" + +EXTRA_OECMAKE = "-DSUITESPARSE_USE_64BIT_BLAS=ON -DBLA_PREFER_PKGCONFIG=ON" + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-config-5.4.0-r0 do_package_qa: QA Issue: package suitesparse-config contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-config/5.4.0-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-config/5.4.0-r0/packages-split/suitesparse-config/usr/lib/libsuitesparseconfig.so.5.4.0 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_5.4.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_5.4.0.bb index e49f203d8cf..c2def57740c 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_5.4.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_5.4.0.bb @@ -5,7 +5,7 @@ require suitesparse-5.4.0.inc LICENSE = "LGPL-2.1-or-later" LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=c2a06105a6d78da59c0d0c5d0d9b1394" -S = "${WORKDIR}/SuiteSparse/CSparse" +S = "${WORKDIR}/git/CSparse" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_7.7.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_7.7.0.bb new file mode 100644 index 00000000000..492515fe7bf --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-csparse_7.7.0.bb @@ -0,0 +1,20 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "LGPL-2.1-or-later" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=c2a06105a6d78da59c0d0c5d0d9b1394" + +S = "${WORKDIR}/git/CSparse" + +EXTRA_OEMAKE = "CC='${CC}'" + +do_compile() { + # build only the library, not the demo + oe_runmake library +} + +do_install() { + install -D -m0644 ${B}/Lib/libcsparse.a ${D}${libdir}/libcsparse.a +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_5.4.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_5.4.0.bb index 5d2039c025a..a7e8f84a354 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_5.4.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_5.4.0.bb @@ -7,7 +7,7 @@ LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=0e5191611fba4aac850756c5d598ff23 DEPENDS = "suitesparse-config" -S = "${WORKDIR}/SuiteSparse/CXSparse" +S = "${WORKDIR}/git/CXSparse" EXTRA_OEMAKE = "CC='${CC}'" diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_7.7.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_7.7.0.bb new file mode 100644 index 00000000000..8b26fdc9b9c --- /dev/null +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-cxsparse_7.7.0.bb @@ -0,0 +1,24 @@ +# Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. + +require suitesparse-7.7.0.inc + +LICENSE = "LGPL-2.1-or-later" +LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=0e5191611fba4aac850756c5d598ff23" + +DEPENDS = "suitesparse-config" + +S = "${WORKDIR}/git/CXSparse" + +inherit cmake pkgconfig + +# do_install:append() { +# ln -snf . ${D}${includedir}/suitesparse +# } + +DEPENDS:append:class-target = " chrpath-replacement-native" +# For some reason ends with bad RPATH +# WARNING: suitesparse-cxsparse-5.4.0-r0 do_package_qa: QA Issue: package suitesparse-cxsparse contains bad RPATH /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-cxsparse/5.4.0-r0/image/usr/lib in file /jenkins/mjansa/build-ros/ros2-dashing-master/tmp-glibc/work/core2-32-oe-linux/suitesparse-cxsparse/5.4.0-r0/packages-split/suitesparse-cxsparse/usr/lib/libcxsparse.so.3.2.0 [rpaths] +do_install:append() { + chrpath --delete ${D}${libdir}/*${SOLIBS} +} diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-metis_5.1.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-metis_5.1.0.bb index 08ca5210a41..6fe23325b82 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-metis_5.1.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-metis_5.1.0.bb @@ -5,7 +5,7 @@ require suitesparse-5.4.0.inc LICENSE = "Apache-2.0" LIC_FILES_CHKSUM += "file://LICENSE.txt;md5=b46727c71b60d35ad5d2f927c4a3929b" -S = "${WORKDIR}/SuiteSparse/metis-${PV}" +S = "${WORKDIR}/git/metis-${PV}" inherit cmake diff --git a/meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_5.4.0.bb b/meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_4.3.3.bb similarity index 77% rename from meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_5.4.0.bb rename to meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_4.3.3.bb index b9a1f16be83..d1e2efd96b5 100644 --- a/meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_5.4.0.bb +++ b/meta-ros-common/recipes-extended/suitesparse/suitesparse-spqr_4.3.3.bb @@ -1,6 +1,7 @@ # Copyright (c) 2019 LG Electronics, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. -require suitesparse-5.4.0.inc +require suitesparse-7.7.0.inc LICENSE = "GPL-2.0-only" LIC_FILES_CHKSUM += "file://Doc/License.txt;md5=1c0c48edf24526b3cda72ce1a8a20b1d" @@ -11,20 +12,14 @@ DEPENDS = " \ suitesparse-colamd \ suitesparse-cholmod \ lapack \ + openblas \ " -S = "${WORKDIR}/SuiteSparse/SPQR" +S = "${WORKDIR}/git/SPQR" -EXTRA_OEMAKE = "CC='${CC}' BLAS='-lblas'" +inherit cmake pkgconfig -do_compile() { - # build only the library, not the demo - oe_runmake library -} - -do_install() { - oe_runmake install INSTALL=${D}${prefix} -} +EXTRA_OECMAKE = "-DSUITESPARSE_USE_64BIT_BLAS=ON -DBLA_PREFER_PKGCONFIG=ON" DEPENDS:append:class-target = " chrpath-replacement-native" # For some reason ends with bad RPATH diff --git a/meta-ros-common/recipes-graphics/assimp/assimp_5.4.0.bb b/meta-ros-common/recipes-graphics/assimp/assimp_5.4.0.bb new file mode 100644 index 00000000000..035bf4bbf6f --- /dev/null +++ b/meta-ros-common/recipes-graphics/assimp/assimp_5.4.0.bb @@ -0,0 +1,27 @@ +DESCRIPTION = "Open Asset Import Library is a portable Open Source library to import \ + various well-known 3D model formats in a uniform manner." +HOMEPAGE = "http://www.assimp.org/" +SECTION = "devel" + +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM = "file://LICENSE;md5=d9d5275cab4fb13ae624d42ce64865de" + +DEPENDS = "zlib" + +SRC_URI = "git://github.com/assimp/assimp.git;protocol=https;branch=master" +UPSTREAM_CHECK_GITTAGREGEX = "v(?P(\d+(\.\d+)+))" + +SRCREV = "8b9ed34eaa3e6ad24254cb7e058fb9150f66b865" + +S = "${WORKDIR}/git" + +inherit cmake + +EXTRA_OECMAKE = " \ + -DASSIMP_BUILD_ASSIMP_TOOLS=OFF \ + -DASSIMP_BUILD_TESTS=OFF \ + -DASSIMP_LIB_INSTALL_DIR=${baselib} \ + -DASSIMP_BUILD_ZLIB=ON \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Amend-jxrlib-include-dir.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Amend-jxrlib-include-dir.patch new file mode 100644 index 00000000000..79dd9bc3511 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Amend-jxrlib-include-dir.patch @@ -0,0 +1,13 @@ +Index: git/Source/FreeImage/PluginJXR.cpp +=================================================================== +--- git.orig/Source/FreeImage/PluginJXR.cpp ++++ git/Source/FreeImage/PluginJXR.cpp +@@ -23,7 +23,7 @@ + #include "Utilities.h" + #include "../Metadata/FreeImageTag.h" + +-#include ++#include + + // ========================================================== + // Plugin Interface diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/CVE-2019-12211-13.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/CVE-2019-12211-13.patch new file mode 100644 index 00000000000..5774165a67b --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/CVE-2019-12211-13.patch @@ -0,0 +1,162 @@ +Index: freeimage/Source/FreeImage/PluginTIFF.cpp +=================================================================== +--- freeimage.orig/Source/FreeImage/PluginTIFF.cpp ++++ freeimage/Source/FreeImage/PluginTIFF.cpp +@@ -122,9 +122,14 @@ static void ReadThumbnail(FreeImageIO *i + static int s_format_id; + + typedef struct { ++ //! FreeImage IO functions + FreeImageIO *io; ++ //! FreeImage handle + fi_handle handle; ++ //! LibTIFF handle + TIFF *tif; ++ //! Count the number of thumbnails already read (used to avoid recursion on loading) ++ unsigned thumbnailCount; + } fi_TIFFIO; + + // ---------------------------------------------------------- +@@ -184,10 +189,8 @@ Open a TIFF file descriptor for reading + */ + TIFF * + TIFFFdOpen(thandle_t handle, const char *name, const char *mode) { +- TIFF *tif; +- + // Open the file; the callback will set everything up +- tif = TIFFClientOpen(name, mode, handle, ++ TIFF *tif = TIFFClientOpen(name, mode, handle, + _tiffReadProc, _tiffWriteProc, _tiffSeekProc, _tiffCloseProc, + _tiffSizeProc, _tiffMapProc, _tiffUnmapProc); + +@@ -460,9 +463,9 @@ CreateImageType(BOOL header_only, FREE_I + } + + } +- else { ++ else if (bpp <= 32) { + +- dib = FreeImage_AllocateHeader(header_only, width, height, MIN(bpp, 32), FI_RGBA_RED_MASK, FI_RGBA_GREEN_MASK, FI_RGBA_BLUE_MASK); ++ dib = FreeImage_AllocateHeader(header_only, width, height, bpp, FI_RGBA_RED_MASK, FI_RGBA_GREEN_MASK, FI_RGBA_BLUE_MASK); + } + + +@@ -1053,6 +1056,7 @@ Open(FreeImageIO *io, fi_handle handle, + if(!fio) return NULL; + fio->io = io; + fio->handle = handle; ++ fio->thumbnailCount = 0; + + if (read) { + fio->tif = TIFFFdOpen((thandle_t)fio, "", "r"); +@@ -1108,6 +1112,27 @@ check for uncommon bitspersample values + */ + static BOOL + IsValidBitsPerSample(uint16 photometric, uint16 bitspersample, uint16 samplesperpixel) { ++ // get the pixel depth in bits ++ const uint16 pixel_depth = bitspersample * samplesperpixel; ++ ++ // check for a supported pixel depth ++ switch (pixel_depth) { ++ case 1: ++ case 4: ++ case 8: ++ case 16: ++ case 24: ++ case 32: ++ case 48: ++ case 64: ++ case 96: ++ case 128: ++ // OK, go on ++ break; ++ default: ++ // unsupported pixel depth ++ return FALSE; ++ } + + switch(bitspersample) { + case 1: +@@ -1148,6 +1173,8 @@ IsValidBitsPerSample(uint16 photometric, + default: + return FALSE; + } ++ ++ return FALSE; + } + + static TIFFLoadMethod +@@ -1237,16 +1264,32 @@ Read embedded thumbnail + static void + ReadThumbnail(FreeImageIO *io, fi_handle handle, void *data, TIFF *tiff, FIBITMAP *dib) { + FIBITMAP* thumbnail = NULL; ++ ++ fi_TIFFIO *fio = (fi_TIFFIO*)data; ++ ++ /* ++ Thumbnail loading can cause recursions because of the way ++ functions TIFFLastDirectory and TIFFSetSubDirectory are working. ++ We use here a hack to count the number of times the ReadThumbnail function was called. ++ We only allow one call, check for this ++ */ ++ if (fio->thumbnailCount > 0) { ++ return; ++ } ++ else { ++ // update the thumbnail count (used to avoid recursion) ++ fio->thumbnailCount++; ++ } + + // read exif thumbnail (IFD 1) ... + +- /* +- // this code can cause unwanted recursion causing an overflow, it is thus disabled until we have a better solution +- // do we really need to read a thumbnail from the Exif segment ? knowing that TIFF store the thumbnail in the subIFD ... +- // + toff_t exif_offset = 0; + if(TIFFGetField(tiff, TIFFTAG_EXIFIFD, &exif_offset)) { + ++ // this code can cause unwanted recursion causing an overflow, ++ // because of the way TIFFLastDirectory work => this is checked ++ // using ++ + if(!TIFFLastDirectory(tiff)) { + // save current position + const long tell_pos = io->tell_proc(handle); +@@ -1264,7 +1307,6 @@ ReadThumbnail(FreeImageIO *io, fi_handle + TIFFSetDirectory(tiff, cur_dir); + } + } +- */ + + // ... or read the first subIFD + +@@ -1281,6 +1323,10 @@ ReadThumbnail(FreeImageIO *io, fi_handle + const long tell_pos = io->tell_proc(handle); + const uint16 cur_dir = TIFFCurrentDirectory(tiff); + ++ // this code can cause unwanted recursion ++ // causing an overflow, because of the way ++ // TIFFSetSubDirectory work ++ + if(TIFFSetSubDirectory(tiff, subIFD_offsets[0])) { + // load the thumbnail + int page = -1; +@@ -2041,7 +2087,7 @@ Load(FreeImageIO *io, fi_handle handle, + } + + // calculate src line and dst pitch +- int dst_pitch = FreeImage_GetPitch(dib); ++ unsigned dst_pitch = FreeImage_GetPitch(dib); + uint32 tileRowSize = (uint32)TIFFTileRowSize(tif); + uint32 imageRowSize = (uint32)TIFFScanlineSize(tif); + +@@ -2071,7 +2117,7 @@ Load(FreeImageIO *io, fi_handle handle, + BYTE *src_bits = tileBuffer; + BYTE *dst_bits = bits + rowSize; + for(int k = 0; k < nrows; k++) { +- memcpy(dst_bits, src_bits, src_line); ++ memcpy(dst_bits, src_bits, MIN(dst_pitch, src_line)); + src_bits += tileRowSize; + dst_bits -= dst_pitch; + } diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JPEG-transform.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JPEG-transform.patch new file mode 100644 index 00000000000..6206a1cae8f --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JPEG-transform.patch @@ -0,0 +1,42 @@ +From: Ghislain Antony Vaillant +Date: Tue, 3 Nov 2015 18:15:18 +0000 +Subject: Disable testing of JPEG transform. + +Reason: the JPEG transform features are disabled from the Debian build as a +result of the stripping of the vendored dependencies. +--- + TestAPI/testJPEG.cpp | 4 ++++ + 1 file changed, 4 insertions(+) + +Index: FreeImage/TestAPI/testJPEG.cpp +=================================================================== +--- FreeImage.orig/TestAPI/testJPEG.cpp ++++ FreeImage/TestAPI/testJPEG.cpp +@@ -25,6 +25,7 @@ + // Local test functions + // ---------------------------------------------------------- + ++#if 0 + void testJPEGTransform(const char *src_file) { + BOOL bResult; + BOOL perfect; +@@ -193,11 +194,13 @@ void testJPEGSameFile(const char *src_fi + bResult = FreeImage_JPEGTransform("test.jpg", "test.jpg", FIJPEG_OP_ROTATE_270, perfect); + assert(bResult); + } ++#endif + + // Main test function + // ---------------------------------------------------------- + + void testJPEG() { ++#if 0 + const char *src_file = "exif.jpg"; + + printf("testJPEG (should throw exceptions) ...\n"); +@@ -213,4 +216,5 @@ void testJPEG() { + + // using the same file for src & dst is allowed + testJPEGSameFile(src_file); ++#endif + } diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JXR-MemIO.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JXR-MemIO.patch new file mode 100644 index 00000000000..47394b70bd1 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-testing-of-JXR-MemIO.patch @@ -0,0 +1,24 @@ +From: Ghislain Antony Vaillant +Date: Thu, 5 Nov 2015 23:47:23 +0000 +Subject: Disable testing of JXR MemIO. + +Reason: The JXR MemIO test raises an assertion error, whose origin is unknown +and needs to be assessed with upstream. Meanwhile the failing test should be +temporarily disabled. +--- + TestAPI/MainTestSuite.cpp | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +Index: FreeImage/TestAPI/MainTestSuite.cpp +=================================================================== +--- FreeImage.orig/TestAPI/MainTestSuite.cpp ++++ FreeImage/TestAPI/MainTestSuite.cpp +@@ -76,7 +76,7 @@ int main(int argc, char *argv[]) { + + // test memory IO + testMemIO("sample.png"); +- testMemIO("exif.jxr"); ++ //testMemIO("exif.jxr"); + + // test multipage functions + testMultiPage("sample.png"); diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-usage-of-HTML-timestamps-in-doxygen.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-usage-of-HTML-timestamps-in-doxygen.patch new file mode 100644 index 00000000000..4f2c5c67046 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-usage-of-HTML-timestamps-in-doxygen.patch @@ -0,0 +1,22 @@ +From: Ghislain Antony Vaillant +Date: Tue, 10 Nov 2015 13:50:59 +0000 +Subject: Disable usage of HTML timestamps in doxygen. + +Improves package reproducibility. +--- + Wrapper/FreeImagePlus/doc/FreeImagePlus.dox | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +Index: FreeImage/Wrapper/FreeImagePlus/doc/FreeImagePlus.dox +=================================================================== +--- FreeImage.orig/Wrapper/FreeImagePlus/doc/FreeImagePlus.dox ++++ FreeImage/Wrapper/FreeImagePlus/doc/FreeImagePlus.dox +@@ -1166,7 +1166,7 @@ HTML_COLORSTYLE_GAMMA = 80 + # The default value is: NO. + # This tag requires that the tag GENERATE_HTML is set to YES. + +-HTML_TIMESTAMP = YES ++HTML_TIMESTAMP = NO + + # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML + # documentation will contain sections that can be hidden and shown after the diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-vendored-dependencies.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-vendored-dependencies.patch new file mode 100644 index 00000000000..7844a7ee5e8 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Disable-vendored-dependencies.patch @@ -0,0 +1,469 @@ +From: Ghislain Antony Vaillant +Date: Tue, 3 Nov 2015 14:39:33 +0000 +Subject: Disable vendored dependencies. + +This commit disables usage of the embedded dependencies for building +FreeImage and FreeImagePlus. Functionalities which could not use the +packaged dependencies are delibarately disabled for security reasons. + +This patch is based on Fedora's FreeImage-3.17.0_unbundle patch. +--- + Source/FreeImage.h | 9 ++++- + Source/FreeImage/J2KHelper.cpp | 2 +- + Source/FreeImage/PluginEXR.cpp | 20 +++++----- + Source/FreeImage/PluginG3.cpp | 9 +++-- + Source/FreeImage/PluginJ2K.cpp | 2 +- + Source/FreeImage/PluginJP2.cpp | 2 +- + Source/FreeImage/PluginJPEG.cpp | 6 +-- + Source/FreeImage/PluginJXR.cpp | 2 +- + Source/FreeImage/PluginPNG.cpp | 4 +- + Source/FreeImage/PluginRAW.cpp | 2 +- + Source/FreeImage/PluginTIFF.cpp | 4 +- + Source/FreeImage/PluginWebP.cpp | 8 ++-- + Source/FreeImage/ZLibInterface.cpp | 5 +-- + Source/Metadata/XTIFF.cpp | 80 +++++++++++++++++++------------------- + genfipsrclist.sh | 9 +---- + gensrclist.sh | 11 ++---- + 16 files changed, 85 insertions(+), 90 deletions(-) + +Index: freeimage-3.18.0+ds2/Source/FreeImage.h +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage.h ++++ freeimage-3.18.0+ds2/Source/FreeImage.h +@@ -473,6 +473,9 @@ FI_ENUM(FREE_IMAGE_DITHER) { + FID_BAYER16x16 = 6 //! Bayer ordered dispersed dot dithering (order 4 dithering matrix) + }; + ++/* Debian: The JPEGTransform functions are deliberately disabled in our build ++ of FreeImage, since they require usage of the vendored copy of libjpeg. */ ++#if 0 + /** Lossless JPEG transformations + Constants used in FreeImage_JPEGTransform + */ +@@ -486,6 +489,7 @@ FI_ENUM(FREE_IMAGE_JPEG_OPERATION) { + FIJPEG_OP_ROTATE_180 = 6, //! 180-degree rotation + FIJPEG_OP_ROTATE_270 = 7 //! 270-degree clockwise (or 90 ccw) + }; ++#endif + + /** Tone mapping operators. + Constants used in FreeImage_ToneMapping. +@@ -1088,7 +1092,9 @@ DLL_API const char* DLL_CALLCONV FreeIma + // -------------------------------------------------------------------------- + // JPEG lossless transformation routines + // -------------------------------------------------------------------------- +- ++/* Debian: The JPEGTransform functions are deliberately disabled in our build ++ of FreeImage, since they require usage of the vendored copy of libjpeg. */ ++#if 0 + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGTransform(const char *src_file, const char *dst_file, FREE_IMAGE_JPEG_OPERATION operation, BOOL perfect FI_DEFAULT(TRUE)); + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGTransformU(const wchar_t *src_file, const wchar_t *dst_file, FREE_IMAGE_JPEG_OPERATION operation, BOOL perfect FI_DEFAULT(TRUE)); + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGCrop(const char *src_file, const char *dst_file, int left, int top, int right, int bottom); +@@ -1097,6 +1103,7 @@ DLL_API BOOL DLL_CALLCONV FreeImage_JPEG + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGTransformCombined(const char *src_file, const char *dst_file, FREE_IMAGE_JPEG_OPERATION operation, int* left, int* top, int* right, int* bottom, BOOL perfect FI_DEFAULT(TRUE)); + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGTransformCombinedU(const wchar_t *src_file, const wchar_t *dst_file, FREE_IMAGE_JPEG_OPERATION operation, int* left, int* top, int* right, int* bottom, BOOL perfect FI_DEFAULT(TRUE)); + DLL_API BOOL DLL_CALLCONV FreeImage_JPEGTransformCombinedFromMemory(FIMEMORY* src_stream, FIMEMORY* dst_stream, FREE_IMAGE_JPEG_OPERATION operation, int* left, int* top, int* right, int* bottom, BOOL perfect FI_DEFAULT(TRUE)); ++#endif + + + // -------------------------------------------------------------------------- +Index: freeimage-3.18.0+ds2/Source/FreeImage/J2KHelper.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/J2KHelper.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/J2KHelper.cpp +@@ -21,7 +21,7 @@ + + #include "FreeImage.h" + #include "Utilities.h" +-#include "../LibOpenJPEG/openjpeg.h" ++#include + #include "J2KHelper.h" + + // -------------------------------------------------------------------------- +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginEXR.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginEXR.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginEXR.cpp +@@ -28,16 +28,17 @@ + #pragma warning (disable : 4800) // ImfVersion.h - 'const int' : forcing value to bool 'true' or 'false' (performance warning) + #endif + +-#include "../OpenEXR/IlmImf/ImfIO.h" +-#include "../OpenEXR/Iex/Iex.h" +-#include "../OpenEXR/IlmImf/ImfOutputFile.h" +-#include "../OpenEXR/IlmImf/ImfInputFile.h" +-#include "../OpenEXR/IlmImf/ImfRgbaFile.h" +-#include "../OpenEXR/IlmImf/ImfChannelList.h" +-#include "../OpenEXR/IlmImf/ImfRgba.h" +-#include "../OpenEXR/IlmImf/ImfArray.h" +-#include "../OpenEXR/IlmImf/ImfPreviewImage.h" +-#include "../OpenEXR/Half/half.h" ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++#include + + + // ========================================================== +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginG3.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginG3.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginG3.cpp +@@ -20,8 +20,6 @@ + // Use at your own risk! + // ========================================================== + +-#include "../LibTIFF4/tiffiop.h" +- + #include "FreeImage.h" + #include "Utilities.h" + +@@ -31,6 +29,7 @@ + + static int s_format_id; + ++#if 0 + // ========================================================== + // Constant/Macro declarations + // ========================================================== +@@ -192,6 +191,7 @@ copyFaxFile(FreeImageIO *io, fi_handle h + + return (row); + } ++#endif + + + // ========================================================== +@@ -229,7 +229,7 @@ SupportsExportDepth(int depth) { + } + + // ---------------------------------------------------------- +- ++#if 0 + static FIBITMAP * DLL_CALLCONV + Load(FreeImageIO *io, fi_handle handle, int page, int flags, void *data) { + TIFF *faxTIFF = NULL; +@@ -406,6 +406,7 @@ Load(FreeImageIO *io, fi_handle handle, + return dib; + + } ++#endif + + // ========================================================== + // Init +@@ -423,7 +424,7 @@ InitG3(Plugin *plugin, int format_id) { + plugin->close_proc = NULL; + plugin->pagecount_proc = NULL; + plugin->pagecapability_proc = NULL; +- plugin->load_proc = Load; ++ plugin->load_proc = NULL; + plugin->save_proc = NULL; + plugin->validate_proc = NULL; + plugin->mime_proc = MimeType; +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginJ2K.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginJ2K.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginJ2K.cpp +@@ -21,7 +21,7 @@ + + #include "FreeImage.h" + #include "Utilities.h" +-#include "../LibOpenJPEG/openjpeg.h" ++#include + #include "J2KHelper.h" + + // ========================================================== +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginJP2.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginJP2.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginJP2.cpp +@@ -21,7 +21,7 @@ + + #include "FreeImage.h" + #include "Utilities.h" +-#include "../LibOpenJPEG/openjpeg.h" ++#include + #include "J2KHelper.h" + + // ========================================================== +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginJPEG.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginJPEG.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginJPEG.cpp +@@ -35,9 +35,9 @@ extern "C" { + #undef FAR + #include + +-#include "../LibJPEG/jinclude.h" +-#include "../LibJPEG/jpeglib.h" +-#include "../LibJPEG/jerror.h" ++#include ++#include ++#include + } + + #include "FreeImage.h" +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginJXR.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginJXR.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginJXR.cpp +@@ -23,7 +23,7 @@ + #include "Utilities.h" + #include "../Metadata/FreeImageTag.h" + +-#include "../LibJXR/jxrgluelib/JXRGlue.h" ++#include + + // ========================================================== + // Plugin Interface +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginPNG.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginPNG.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginPNG.cpp +@@ -40,8 +40,8 @@ + + // ---------------------------------------------------------- + +-#include "../ZLib/zlib.h" +-#include "../LibPNG/png.h" ++#include ++#include + + // ---------------------------------------------------------- + +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginRAW.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginRAW.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginRAW.cpp +@@ -19,7 +19,7 @@ + // Use at your own risk! + // ========================================================== + +-#include "../LibRawLite/libraw/libraw.h" ++#include + + #include "FreeImage.h" + #include "Utilities.h" +Index: freeimage-3.18.0+ds2/Source/FreeImage/ZLibInterface.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/ZLibInterface.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/ZLibInterface.cpp +@@ -19,10 +19,9 @@ + // Use at your own risk! + // ========================================================== + +-#include "../ZLib/zlib.h" ++#include + #include "FreeImage.h" + #include "Utilities.h" +-#include "../ZLib/zutil.h" /* must be the last header because of error C3163 in VS2008 (_vsnprintf defined in stdio.h) */ + + /** + Compresses a source buffer into a target buffer, using the ZLib library. +@@ -115,7 +114,7 @@ FreeImage_ZLibGZip(BYTE *target, DWORD t + return 0; + case Z_OK: { + // patch header, setup crc and length (stolen from mod_trace_output) +- BYTE *p = target + 8; *p++ = 2; *p = OS_CODE; // xflags, os_code ++ BYTE *p = target + 8; *p++ = 2; *p = 0x03; // xflags, os_code (unix) + crc = crc32(crc, source, source_size); + memcpy(target + 4 + dest_len, &crc, 4); + memcpy(target + 8 + dest_len, &source_size, 4); +Index: freeimage-3.18.0+ds2/Source/Metadata/XTIFF.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/Metadata/XTIFF.cpp ++++ freeimage-3.18.0+ds2/Source/Metadata/XTIFF.cpp +@@ -29,7 +29,7 @@ + #pragma warning (disable : 4786) // identifier was truncated to 'number' characters + #endif + +-#include "../LibTIFF4/tiffiop.h" ++#include + + #include "FreeImage.h" + #include "Utilities.h" +@@ -224,6 +224,33 @@ tiff_write_geotiff_profile(TIFF *tif, FI + // TIFF EXIF tag reading & writing + // ---------------------------------------------------------- + ++static uint32 exif_tag_ids[] = { ++ EXIFTAG_EXPOSURETIME, EXIFTAG_FNUMBER, EXIFTAG_EXPOSUREPROGRAM, ++ EXIFTAG_SPECTRALSENSITIVITY, EXIFTAG_ISOSPEEDRATINGS, EXIFTAG_OECF, ++ EXIFTAG_EXIFVERSION, EXIFTAG_DATETIMEORIGINAL, EXIFTAG_DATETIMEDIGITIZED, ++ EXIFTAG_COMPONENTSCONFIGURATION, EXIFTAG_COMPRESSEDBITSPERPIXEL, ++ EXIFTAG_SHUTTERSPEEDVALUE, EXIFTAG_APERTUREVALUE, ++ EXIFTAG_BRIGHTNESSVALUE, EXIFTAG_EXPOSUREBIASVALUE, ++ EXIFTAG_MAXAPERTUREVALUE, EXIFTAG_SUBJECTDISTANCE, EXIFTAG_METERINGMODE, ++ EXIFTAG_LIGHTSOURCE, EXIFTAG_FLASH, EXIFTAG_FOCALLENGTH, ++ EXIFTAG_SUBJECTAREA, EXIFTAG_MAKERNOTE, EXIFTAG_USERCOMMENT, ++ EXIFTAG_SUBSECTIME, EXIFTAG_SUBSECTIMEORIGINAL, ++ EXIFTAG_SUBSECTIMEDIGITIZED, EXIFTAG_FLASHPIXVERSION, EXIFTAG_COLORSPACE, ++ EXIFTAG_PIXELXDIMENSION, EXIFTAG_PIXELYDIMENSION, ++ EXIFTAG_RELATEDSOUNDFILE, EXIFTAG_FLASHENERGY, ++ EXIFTAG_SPATIALFREQUENCYRESPONSE, EXIFTAG_FOCALPLANEXRESOLUTION, ++ EXIFTAG_FOCALPLANEYRESOLUTION, EXIFTAG_FOCALPLANERESOLUTIONUNIT, ++ EXIFTAG_SUBJECTLOCATION, EXIFTAG_EXPOSUREINDEX, EXIFTAG_SENSINGMETHOD, ++ EXIFTAG_FILESOURCE, EXIFTAG_SCENETYPE, EXIFTAG_CFAPATTERN, ++ EXIFTAG_CUSTOMRENDERED, EXIFTAG_EXPOSUREMODE, EXIFTAG_WHITEBALANCE, ++ EXIFTAG_DIGITALZOOMRATIO, EXIFTAG_FOCALLENGTHIN35MMFILM, ++ EXIFTAG_SCENECAPTURETYPE, EXIFTAG_GAINCONTROL, EXIFTAG_CONTRAST, ++ EXIFTAG_SATURATION, EXIFTAG_SHARPNESS, EXIFTAG_DEVICESETTINGDESCRIPTION, ++ EXIFTAG_SUBJECTDISTANCERANGE, EXIFTAG_GAINCONTROL, EXIFTAG_GAINCONTROL, ++ EXIFTAG_IMAGEUNIQUEID ++}; ++static int nExifTags = sizeof(exif_tag_ids) / sizeof(exif_tag_ids[0]); ++ + /** + Read a single Exif tag + +@@ -575,43 +602,10 @@ tiff_read_exif_tags(TIFF *tif, TagLib::M + + // loop over all Core Directory Tags + // ### uses private data, but there is no other way ++ // -> Fedora: Best we can do without private headers is to hard-code a list of known EXIF tags and read those + if(md_model == TagLib::EXIF_MAIN) { +- const TIFFDirectory *td = &tif->tif_dir; +- +- uint32 lastTag = 0; //<- used to prevent reading some tags twice (as stored in tif_fieldinfo) +- +- for (int fi = 0, nfi = (int)tif->tif_nfields; nfi > 0; nfi--, fi++) { +- const TIFFField *fld = tif->tif_fields[fi]; +- +- const uint32 tag_id = TIFFFieldTag(fld); +- +- if(tag_id == lastTag) { +- continue; +- } +- +- // test if tag value is set +- // (lifted directly from LibTiff _TIFFWriteDirectory) +- +- if( fld->field_bit == FIELD_CUSTOM ) { +- int is_set = FALSE; +- +- for(int ci = 0; ci < td->td_customValueCount; ci++ ) { +- is_set |= (td->td_customValues[ci].info == fld); +- } +- +- if( !is_set ) { +- continue; +- } +- +- } else if(!TIFFFieldSet(tif, fld->field_bit)) { +- continue; +- } +- +- // process *all* other tags (some will be ignored) +- +- tiff_read_exif_tag(tif, tag_id, dib, md_model); +- +- lastTag = tag_id; ++ for (int i = 0; i < nExifTags; ++i) { ++ tiff_read_exif_tag(tif, exif_tag_ids[i], dib, md_model); + } + + } +@@ -723,10 +717,9 @@ tiff_write_exif_tags(TIFF *tif, TagLib:: + + TagLib& tag_lib = TagLib::instance(); + +- for (int fi = 0, nfi = (int)tif->tif_nfields; nfi > 0; nfi--, fi++) { +- const TIFFField *fld = tif->tif_fields[fi]; +- +- const uint32 tag_id = TIFFFieldTag(fld); ++ for (int fi = 0, nfi = nExifTags; nfi > 0; nfi--, fi++) { ++ const uint32 tag_id = exif_tag_ids[fi]; ++ const TIFFField *fld = TIFFFieldWithTag(tif, tag_id); + + if(skip_write_field(tif, tag_id)) { + // skip tags that are already handled by the LibTIFF writing process +@@ -749,7 +742,7 @@ tiff_write_exif_tags(TIFF *tif, TagLib:: + continue; + } + // type of storage may differ (e.g. rationnal array vs float array type) +- if((unsigned)_TIFFDataSize(tif_tag_type) != FreeImage_TagDataWidth(tag_type)) { ++ if((unsigned)TIFFFieldSetGetSize(fld) != FreeImage_TagDataWidth(tag_type)) { + // skip tag or _TIFFmemcpy will fail + continue; + } +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginTIFF.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginTIFF.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginTIFF.cpp +@@ -37,9 +37,9 @@ + + #include "FreeImage.h" + #include "Utilities.h" +-#include "../LibTIFF4/tiffiop.h" ++#include + #include "../Metadata/FreeImageTag.h" +-#include "../OpenEXR/Half/half.h" ++#include "Imath/half.h" + + #include "FreeImageIO.h" + #include "PSDParser.h" +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginWebP.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginWebP.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginWebP.cpp +@@ -24,9 +24,9 @@ + + #include "../Metadata/FreeImageTag.h" + +-#include "../LibWebP/src/webp/decode.h" +-#include "../LibWebP/src/webp/encode.h" +-#include "../LibWebP/src/webp/mux.h" ++#include "webp/decode.h" ++#include "webp/encode.h" ++#include "webp/mux.h" + + // ========================================================== + // Plugin Interface +Index: freeimage-3.18.0+ds2/gensrclist.sh +=================================================================== +--- freeimage-3.18.0+ds2.orig/gensrclist.sh ++++ freeimage-3.18.0+ds2/gensrclist.sh +@@ -6,16 +6,11 @@ echo "VER_MAJOR = 3" > Makefile.srcs + echo "VER_MINOR = 18.0" >> Makefile.srcs + + echo -n "SRCS = " >> Makefile.srcs +-for DIR in $DIRLIST; do +- VCPRJS=`echo $DIR/*.2013.vcxproj` +- if [ "$VCPRJS" != "$DIR/*.2013.vcxproj" ]; then +- egrep 'ClCompile Include=.*\.(c|cpp)' $DIR/*.2013.vcxproj | cut -d'"' -f2 | tr '\\' '/' | awk '{print "'$DIR'/"$0}' | tr '\r\n' ' ' | tr -s ' ' >> Makefile.srcs +- fi +-done ++find Source -name '*.c' -or -name '*.cpp' -not -name 'JPEGTransform.cpp' | LC_ALL=C sort | xargs echo -n >> Makefile.srcs + echo >> Makefile.srcs + + echo -n "INCLS = " >> Makefile.srcs +-find . -name "*.h" -print | xargs echo >> Makefile.srcs ++find Source -name '*.h' | LC_ALL=C sort | xargs echo -n >> Makefile.srcs + echo >> Makefile.srcs + + echo -n "INCLUDE =" >> Makefile.srcs +Index: freeimage-3.18.0+ds2/genfipsrclist.sh +=================================================================== +--- freeimage-3.18.0+ds2.orig/genfipsrclist.sh ++++ freeimage-3.18.0+ds2/genfipsrclist.sh +@@ -7,12 +7,7 @@ echo "VER_MAJOR = 3" > fipMakefile.srcs + echo "VER_MINOR = 18.0" >> fipMakefile.srcs + + echo -n "SRCS = " >> fipMakefile.srcs +-for DIR in $DIRLIST; do +- VCPRJS=`echo $DIR/*.2013.vcxproj` +- if [ "$VCPRJS" != "$DIR/*.2013.vcxproj" ]; then +- egrep 'ClCompile Include=.*\.(c|cpp)' $DIR/*.2013.vcxproj | cut -d'"' -f2 | tr '\\' '/' | awk '{print "'$DIR'/"$0}' | tr '\r\n' ' ' | tr -s ' ' >> fipMakefile.srcs +- fi +-done ++find Wrapper/FreeImagePlus/src -name '*.cpp' -print | LC_ALL=C sort | xargs echo -n >> fipMakefile.srcs + echo >> fipMakefile.srcs + + echo -n "INCLUDE =" >> fipMakefile.srcs diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Enable-substitution-of-pkg-config.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Enable-substitution-of-pkg-config.patch new file mode 100644 index 00000000000..628545b52de --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Enable-substitution-of-pkg-config.patch @@ -0,0 +1,39 @@ +From: Helmut Grohne +Date: Tue, 13 Dec 2016 15:59:00 +0000 +Subject: Enable substitution of pkg-config + +--- + Makefile.gnu | 9 ++++++--- + 1 file changed, 6 insertions(+), 3 deletions(-) + +Index: FreeImage/Makefile.gnu +=================================================================== +--- FreeImage.orig/Makefile.gnu ++++ FreeImage/Makefile.gnu +@@ -11,7 +11,10 @@ INSTALLDIR ?= $(DESTDIR)/usr/lib + # Converts cr/lf to just lf + DOS2UNIX = dos2unix + +-LIBRARIES = -lstdc++ -ljxrglue $(shell pkg-config --libs libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) -lm ++# See Bug-Debian #845279 ++PKG_CONFIG ?= pkg-config ++ ++LIBRARIES = -lstdc++ -ljxrglue $(shell $(PKG_CONFIG) --libs libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) -lm + + MODULES = $(SRCS:.c=.o) + MODULES := $(MODULES:.cpp=.o) +@@ -23,12 +26,12 @@ override CFLAGS += -DOPJ_STATIC + override CFLAGS += -DNO_LCMS + # LibJXR + override CFLAGS += -DDISABLE_PERF_MEASUREMENT -D__ANSI__ +-override CFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell pkg-config --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) ++override CFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) + CXXFLAGS ?= -O3 -fPIC + override CXXFLAGS += -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy + # LibJXR + override CXXFLAGS += -D__ANSI__ +-override CXXFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell pkg-config --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) ++override CXXFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) + + TARGET = freeimage + STATICLIB = lib$(TARGET).a diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-big-endian.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-big-endian.patch new file mode 100644 index 00000000000..a08bbf91e17 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-big-endian.patch @@ -0,0 +1,63 @@ +Description: Fix FTBFS on some big-endian targets +Bug-Debian: https://bugs.debian.org/1002610 +Origin: backport, https://sourceforge.net/p/freeimage/svn/1809/ + +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginBMP.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginBMP.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginBMP.cpp +@@ -518,7 +518,7 @@ LoadWindowsBMP(FreeImageIO *io, fi_handl + io->read_proc(FreeImage_GetPalette(dib), used_colors * sizeof(RGBQUAD), 1, handle); + #if FREEIMAGE_COLORORDER == FREEIMAGE_COLORORDER_RGB + RGBQUAD *pal = FreeImage_GetPalette(dib); +- for(int i = 0; i < used_colors; i++) { ++ for(unsigned i = 0; i < used_colors; i++) { + INPLACESWAP(pal[i].rgbRed, pal[i].rgbBlue); + } + #endif +@@ -1419,7 +1419,7 @@ Save(FreeImageIO *io, FIBITMAP *dib, fi_ + + free(buffer); + #ifdef FREEIMAGE_BIGENDIAN +- } else if (bpp == 16) { ++ } else if (dst_bpp == 16) { + int padding = dst_pitch - dst_width * sizeof(WORD); + WORD pad = 0; + WORD pixel; +@@ -1440,7 +1440,7 @@ Save(FreeImageIO *io, FIBITMAP *dib, fi_ + } + #endif + #if FREEIMAGE_COLORORDER == FREEIMAGE_COLORORDER_RGB +- } else if (bpp == 24) { ++ } else if (dst_bpp == 24) { + int padding = dst_pitch - dst_width * sizeof(FILE_BGR); + DWORD pad = 0; + FILE_BGR bgr; +@@ -1461,7 +1461,7 @@ Save(FreeImageIO *io, FIBITMAP *dib, fi_ + } + } + } +- } else if (bpp == 32) { ++ } else if (dst_bpp == 32) { + FILE_BGRA bgra; + for(unsigned y = 0; y < dst_height; y++) { + BYTE *line = FreeImage_GetScanLine(dib, y); +Index: freeimage-3.18.0+ds2/Source/FreeImage/PluginDDS.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginDDS.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginDDS.cpp +@@ -356,14 +356,6 @@ SwapHeader(DDSHEADER *header) { + for(int i=0; i<11; i++) { + SwapLong(&header->surfaceDesc.dwReserved1[i]); + } +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwSize); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwFlags); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwFourCC); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwRGBBitCount); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwRBitMask); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwGBitMask); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwBBitMask); +- SwapLong(&header->surfaceDesc.ddpfPixelFormat.dwRGBAlphaBitMask); + SwapLong(&header->surfaceDesc.ddsCaps.dwCaps1); + SwapLong(&header->surfaceDesc.ddsCaps.dwCaps2); + SwapLong(&header->surfaceDesc.ddsCaps.dwReserved[0]); diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-compatibility-with-system-libpng.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-compatibility-with-system-libpng.patch new file mode 100644 index 00000000000..4add170a352 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-compatibility-with-system-libpng.patch @@ -0,0 +1,99 @@ +From: Ghislain Antony Vaillant +Date: Tue, 3 Nov 2015 15:20:45 +0000 +Subject: Fix compatibility with system libpng. + +[Ghislain Antony Vaillant] +The PNG plugin of FreeImage makes use of optional features of libpng, which +are not enabled in Debian. This commit adds the necessary guards for FreeImage +to compile and run without these features. + +[Tobias Frost] +Fix FTBFS with libpng 1.6. +--- + Source/FreeImage/PluginPNG.cpp | 35 ++++++++++++++++++++++++++++------- + 1 file changed, 28 insertions(+), 7 deletions(-) + +Index: FreeImage/Source/FreeImage/PluginPNG.cpp +=================================================================== +--- FreeImage.orig/Source/FreeImage/PluginPNG.cpp ++++ FreeImage/Source/FreeImage/PluginPNG.cpp +@@ -115,9 +115,11 @@ ReadMetadata(png_structp png_ptr, png_in + // create a tag + tag = FreeImage_CreateTag(); + if(!tag) return FALSE; +- ++#ifdef PNG_iTXt_SUPPORTED + DWORD tag_length = (DWORD) MAX(text_ptr[i].text_length, text_ptr[i].itxt_length); +- ++#else ++ DWORD tag_length = text_ptr[i].text_length; ++#endif + FreeImage_SetTagLength(tag, tag_length); + FreeImage_SetTagCount(tag, tag_length); + FreeImage_SetTagType(tag, FIDT_ASCII); +@@ -185,14 +187,19 @@ WriteMetadata(png_structp png_ptr, png_i + if(mdhandle) { + do { + memset(&text_metadata, 0, sizeof(png_text)); ++#ifdef PNG_iTXt_SUPPORTED + text_metadata.compression = 1; // iTXt, none ++#else ++ text_metadata.compression = -1; ++#endif + text_metadata.key = (char*)FreeImage_GetTagKey(tag); // keyword, 1-79 character description of "text" + text_metadata.text = (char*)FreeImage_GetTagValue(tag); // comment, may be an empty string (ie "") + text_metadata.text_length = FreeImage_GetTagLength(tag);// length of the text string ++#ifdef PNG_iTXt_SUPPORTED + text_metadata.itxt_length = FreeImage_GetTagLength(tag);// length of the itxt string + text_metadata.lang = 0; // language code, 0-79 characters or a NULL pointer + text_metadata.lang_key = 0; // keyword translated UTF-8 string, 0 or more chars or a NULL pointer +- ++#endif + // set the tag + png_set_text(png_ptr, info_ptr, &text_metadata, 1); + +@@ -211,10 +218,11 @@ WriteMetadata(png_structp png_ptr, png_i + text_metadata.key = (char*)g_png_xmp_keyword; // keyword, 1-79 character description of "text" + text_metadata.text = (char*)FreeImage_GetTagValue(tag); // comment, may be an empty string (ie "") + text_metadata.text_length = FreeImage_GetTagLength(tag);// length of the text string ++#ifdef PNG_iTXt_SUPPORTED + text_metadata.itxt_length = FreeImage_GetTagLength(tag);// length of the itxt string + text_metadata.lang = 0; // language code, 0-79 characters or a NULL pointer + text_metadata.lang_key = 0; // keyword translated UTF-8 string, 0 or more chars or a NULL pointer +- ++#endif + // set the tag + png_set_text(png_ptr, info_ptr, &text_metadata, 1); + bResult &= TRUE; +@@ -707,11 +715,19 @@ Load(FreeImageIO *io, fi_handle handle, + + if (png_get_valid(png_ptr, info_ptr, PNG_INFO_iCCP)) { + png_charp profile_name = NULL; +- png_bytep profile_data = NULL; ++#if PNG_LIBPNG_VER_MAJOR >= 1 && PNG_LIBPNG_VER_MINOR >= 4 ++ png_bytepp profile_data = NULL; ++#else ++ png_charp profile_data = NULL; ++#endif + png_uint_32 profile_length = 0; + int compression_type; + ++#if PNG_LIBPNG_VER_MAJOR >= 1 && PNG_LIBPNG_VER_MINOR >= 4 ++ png_get_iCCP(png_ptr, info_ptr, &profile_name, &compression_type, profile_data, &profile_length); ++#else + png_get_iCCP(png_ptr, info_ptr, &profile_name, &compression_type, &profile_data, &profile_length); ++#endif + + // copy ICC profile data (must be done after FreeImage_AllocateHeader) + +@@ -746,8 +762,9 @@ Load(FreeImageIO *io, fi_handle handle, + for (png_uint_32 k = 0; k < height; k++) { + row_pointers[height - 1 - k] = FreeImage_GetScanLine(dib, k); + } +- ++#ifdef PNG_BENIGN_ERRORS_SUPPORTED + png_set_benign_errors(png_ptr, 1); ++#endif + png_read_image(png_ptr, row_pointers); + + // check if the bitmap contains transparency, if so enable it in the header diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-encoding-of-fi-header.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-encoding-of-fi-header.patch new file mode 100644 index 00000000000..a3ae2453d9c --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-encoding-of-fi-header.patch @@ -0,0 +1,21 @@ +From: Ghislain Antony Vaillant +Date: Sun, 10 Jan 2016 16:03:12 +0000 +Subject: Fix encoding of fi header. + +--- + Source/FreeImage.h | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +Index: FreeImage/Source/FreeImage.h +=================================================================== +--- FreeImage.orig/Source/FreeImage.h ++++ FreeImage/Source/FreeImage.h +@@ -3,7 +3,7 @@ + // + // Design and implementation by + // - Floris van den Berg (flvdberg@wxs.nl) +-// - Hervé Drolon (drolon@infonie.fr) ++// - Herve Drolon (drolon@infonie.fr) + // + // Contributors: + // - see changes log named 'Whatsnew.txt', see header of each .h and .cpp file diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation-2.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation-2.patch new file mode 100644 index 00000000000..7e516527a7d --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation-2.patch @@ -0,0 +1,13 @@ +Index: Source/FreeImage/PluginRAW.cpp +=================================================================== +--- a/Source/FreeImage/PluginRAW.cpp (revision 1894) ++++ b/Source/FreeImage/PluginRAW.cpp (revision 1895) +@@ -701,7 +701,7 @@ + // -------------------------------------------- + + // (-s [0..N-1]) Select one raw image from input file +- RawProcessor->imgdata.params.shot_select = 0; ++ RawProcessor->imgdata.rawparams.shot_select = 0; + // (-w) Use camera white balance, if possible (otherwise, fallback to auto_wb) + RawProcessor->imgdata.params.use_camera_wb = 1; + // (-M) Use any color matrix from the camera metadata. This option only affects Olympus, Leaf, and Phase One cameras. diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation.patch new file mode 100644 index 00000000000..f3aaca12e5a --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-libraw-compilation.patch @@ -0,0 +1,76 @@ +Description: Fix FTBFS against libraw 0.20.0 +Origin: https://sourceforge.net/p/freeimage/svn/1842/ +Acked-By: Anton Gladky +Bug-Debian: https://bugs.debian.org/968637 +Last-update: 2020-08-27 + +Index: freeimage/Source/FreeImage/PluginRAW.cpp +=================================================================== +--- freeimage.orig/Source/FreeImage/PluginRAW.cpp ++++ freeimage/Source/FreeImage/PluginRAW.cpp +@@ -59,21 +59,18 @@ public: + } + + int valid() { +- return (_io && _handle); ++ return (_io && _handle) ? 1 : 0; + } + + int read(void *buffer, size_t size, size_t count) { +- if(substream) return substream->read(buffer, size, count); + return _io->read_proc(buffer, (unsigned)size, (unsigned)count, _handle); + } + + int seek(INT64 offset, int origin) { +- if(substream) return substream->seek(offset, origin); + return _io->seek_proc(_handle, (long)offset, origin); + } + + INT64 tell() { +- if(substream) return substream->tell(); + return _io->tell_proc(_handle); + } + +@@ -83,19 +80,21 @@ public: + + int get_char() { + int c = 0; +- if(substream) return substream->get_char(); +- if(!_io->read_proc(&c, 1, 1, _handle)) return -1; ++ if (!_io->read_proc(&c, 1, 1, _handle)) { ++ return -1; ++ } + return c; + } + + char* gets(char *buffer, int length) { +- if (substream) return substream->gets(buffer, length); + memset(buffer, 0, length); + for(int i = 0; i < length; i++) { +- if(!_io->read_proc(&buffer[i], 1, 1, _handle)) ++ if (!_io->read_proc(&buffer[i], 1, 1, _handle)) { + return NULL; +- if(buffer[i] == 0x0A) ++ } ++ if (buffer[i] == 0x0A) { + break; ++ } + } + return buffer; + } +@@ -104,7 +103,6 @@ public: + std::string buffer; + char element = 0; + bool bDone = false; +- if(substream) return substream->scanf_one(fmt,val); + do { + if(_io->read_proc(&element, 1, 1, _handle) == 1) { + switch(element) { +@@ -127,7 +125,6 @@ public: + } + + int eof() { +- if(substream) return substream->eof(); + return (_io->tell_proc(_handle) >= _eof); + } + diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-macro-redefinition-for-64-bit-integer-types.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-macro-redefinition-for-64-bit-integer-types.patch new file mode 100644 index 00000000000..f63f3b8c7c4 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix-macro-redefinition-for-64-bit-integer-types.patch @@ -0,0 +1,26 @@ +From: Debian QA Group +Date: Fri, 6 Nov 2015 13:51:20 +0000 +Subject: Fix macro redefinition for 64-bit integer types. + +Both FreeImage and LibRAW defines INT64 and UINT64 aliases in their respective +public headers via macros. This commit guards against macro redefinitions for +these types inside the FreeImage.h public header. +--- + Source/FreeImage.h | 2 ++ + 1 file changed, 2 insertions(+) + +Index: FreeImage/Source/FreeImage.h +=================================================================== +--- FreeImage.orig/Source/FreeImage.h ++++ FreeImage/Source/FreeImage.h +@@ -155,8 +155,10 @@ typedef uint8_t BYTE; + typedef uint16_t WORD; + typedef uint32_t DWORD; + typedef int32_t LONG; ++#ifndef _LIBRAW_TYPES_H + typedef int64_t INT64; + typedef uint64_t UINT64; ++#endif + #else + // MS is not C99 ISO compliant + typedef long BOOL; diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix_compilation_external-static.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix_compilation_external-static.patch new file mode 100644 index 00000000000..3c832de46dd --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Fix_compilation_external-static.patch @@ -0,0 +1,16 @@ +Description: Fix compilation due to external-static mismatch +Author: Anton Gladky +Bug-Debian: https://bugs.debian.org/964653 +Last-Update: 2020-07-15 + +--- freeimage-3.18.0+ds2.orig/Source/FreeImage/PluginJPEG.cpp ++++ freeimage-3.18.0+ds2/Source/FreeImage/PluginJPEG.cpp +@@ -502,7 +502,7 @@ marker_is_icc(jpeg_saved_marker_ptr mark + NOTE: if the file contains invalid ICC APP2 markers, we just silently + return FALSE. You might want to issue an error message instead. + */ +-static BOOL ++BOOL + jpeg_read_icc_profile(j_decompress_ptr cinfo, JOCTET **icc_data_ptr, unsigned *icc_data_len) { + jpeg_saved_marker_ptr marker; + int num_markers = 0; diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-dependencies.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-dependencies.patch new file mode 100644 index 00000000000..952fb3b4da2 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-dependencies.patch @@ -0,0 +1,184 @@ +From: Ghislain Antony Vaillant +Date: Thu, 5 Nov 2015 22:47:13 +0000 +Subject: Use system dependencies. + +This commit patches the build system to use the packaged dependencies +for building FreeImage and FreeImagePlus. This patch also modifies some +targets in the corresponding Makefiles to help with the package build process. +--- + Makefile.fip | 45 +++++++++++++++++---------------------------- + Makefile.gnu | 41 ++++++++++++++++++++--------------------- + 2 files changed, 37 insertions(+), 49 deletions(-) + +diff --git a/Makefile.fip b/Makefile.fip +index b59c419..98733cf 100644 +--- a/Makefile.fip ++++ b/Makefile.fip +@@ -11,27 +11,16 @@ INSTALLDIR ?= $(DESTDIR)/usr/lib + # Converts cr/lf to just lf + DOS2UNIX = dos2unix + +-LIBRARIES = -lstdc++ ++LIBRARIES = -lstdc++ -ljxrglue $(shell pkg-config --libs libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) -lm + + MODULES = $(SRCS:.c=.o) + MODULES := $(MODULES:.cpp=.o) +-CFLAGS ?= -O3 -fPIC -fexceptions -fvisibility=hidden +-# OpenJPEG +-CFLAGS += -DOPJ_STATIC +-# LibRaw +-CFLAGS += -DNO_LCMS +-# LibJXR +-CFLAGS += -DDISABLE_PERF_MEASUREMENT -D__ANSI__ +-CFLAGS += $(INCLUDE) +-CXXFLAGS ?= -O3 -fPIC -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy +-# LibJXR +-CXXFLAGS += -D__ANSI__ +-CXXFLAGS += $(INCLUDE) +- +-ifeq ($(shell sh -c 'uname -m 2>/dev/null || echo not'),x86_64) +- CFLAGS += -fPIC +- CXXFLAGS += -fPIC +-endif ++CFLAGS ?= -O3 -fPIC ++override CFLAGS += -fexceptions -fvisibility=hidden ++override CFLAGS += $(INCLUDE) -IDist ++CXXFLAGS ?= -O3 -fPIC ++override CXXFLAGS += -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy ++override CXXFLAGS += $(INCLUDE) -IDist + + TARGET = freeimageplus + STATICLIB = lib$(TARGET).a +@@ -48,31 +37,31 @@ all: dist + + dist: FreeImage + mkdir -p Dist +- cp *.a Dist/ +- cp *.so Dist/ +- cp Source/FreeImage.h Dist/ +- cp Wrapper/FreeImagePlus/FreeImagePlus.h Dist/ ++ cp $(STATICLIB) Dist/ ++ cp $(SHAREDLIB) Dist/ ++ cp $(HEADERFIP) Dist/ ++ ln -sf $(SHAREDLIB) Dist/$(VERLIBNAME) ++ ln -sf $(VERLIBNAME) Dist/$(LIBNAME) + + dos2unix: +- @$(DOS2UNIX) $(SRCS) ++ @$(DOS2UNIX) $(SRCS) $(HEADERFIP) + + FreeImage: $(STATICLIB) $(SHAREDLIB) + + .c.o: +- $(CC) $(CFLAGS) -c $< -o $@ ++ $(CC) $(CFLAGS) $(CPPFLAGS) -c $< -o $@ + + .cpp.o: +- $(CXX) $(CXXFLAGS) -c $< -o $@ ++ $(CXX) $(CXXFLAGS) $(CPPFLAGS) -c $< -o $@ + + $(STATICLIB): $(MODULES) + $(AR) r $@ $(MODULES) + + $(SHAREDLIB): $(MODULES) +- $(CC) -s -shared -Wl,-soname,$(VERLIBNAME) $(LDFLAGS) -o $@ $(MODULES) $(LIBRARIES) ++ $(CC) -shared -Wl,-soname,$(VERLIBNAME) $(LDFLAGS) -o $@ $(MODULES) $(LIBRARIES) + + install: + install -d $(INCDIR) $(INSTALLDIR) +- install -m 644 -o root -g root $(HEADER) $(INCDIR) + install -m 644 -o root -g root $(HEADERFIP) $(INCDIR) + install -m 644 -o root -g root $(STATICLIB) $(INSTALLDIR) + install -m 755 -o root -g root $(SHAREDLIB) $(INSTALLDIR) +@@ -80,5 +69,5 @@ install: + ln -sf $(VERLIBNAME) $(INSTALLDIR)/$(LIBNAME) + + clean: +- rm -f core Dist/*.* u2dtmp* $(MODULES) $(STATICLIB) $(SHAREDLIB) $(LIBNAME) ++ rm -f Dist/lib$(TARGET)* Dist/FreeImagePlus.h $(MODULES) $(STATICLIB) $(SHAREDLIB) $(LIBNAME) + +diff --git a/Makefile.gnu b/Makefile.gnu +index 92f6358..4e61efa 100644 +--- a/Makefile.gnu ++++ b/Makefile.gnu +@@ -11,27 +11,24 @@ INSTALLDIR ?= $(DESTDIR)/usr/lib + # Converts cr/lf to just lf + DOS2UNIX = dos2unix + +-LIBRARIES = -lstdc++ ++LIBRARIES = -lstdc++ -ljxrglue $(shell pkg-config --libs libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) -lm + + MODULES = $(SRCS:.c=.o) + MODULES := $(MODULES:.cpp=.o) +-CFLAGS ?= -O3 -fPIC -fexceptions -fvisibility=hidden ++CFLAGS ?= -O3 -fPIC ++override CFLAGS += -fexceptions -fvisibility=hidden + # OpenJPEG +-CFLAGS += -DOPJ_STATIC ++override CFLAGS += -DOPJ_STATIC + # LibRaw +-CFLAGS += -DNO_LCMS ++override CFLAGS += -DNO_LCMS + # LibJXR +-CFLAGS += -DDISABLE_PERF_MEASUREMENT -D__ANSI__ +-CFLAGS += $(INCLUDE) +-CXXFLAGS ?= -O3 -fPIC -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy ++override CFLAGS += -DDISABLE_PERF_MEASUREMENT -D__ANSI__ ++override CFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell pkg-config --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) ++CXXFLAGS ?= -O3 -fPIC ++override CXXFLAGS += -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy + # LibJXR +-CXXFLAGS += -D__ANSI__ +-CXXFLAGS += $(INCLUDE) +- +-ifeq ($(shell sh -c 'uname -m 2>/dev/null || echo not'),x86_64) +- CFLAGS += -fPIC +- CXXFLAGS += -fPIC +-endif ++override CXXFLAGS += -D__ANSI__ ++override CXXFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell pkg-config --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) + + TARGET = freeimage + STATICLIB = lib$(TARGET).a +@@ -48,9 +45,11 @@ all: dist + + dist: FreeImage + mkdir -p Dist +- cp *.a Dist/ +- cp *.so Dist/ +- cp Source/FreeImage.h Dist/ ++ cp $(STATICLIB) Dist/ ++ cp $(SHAREDLIB) Dist/ ++ cp $(HEADER) Dist/ ++ ln -sf $(SHAREDLIB) Dist/$(VERLIBNAME) ++ ln -sf $(VERLIBNAME) Dist/$(LIBNAME) + + dos2unix: + @$(DOS2UNIX) $(SRCS) $(INCLS) +@@ -58,16 +57,16 @@ dos2unix: + FreeImage: $(STATICLIB) $(SHAREDLIB) + + .c.o: +- $(CC) $(CFLAGS) -c $< -o $@ ++ $(CC) $(CFLAGS) $(CPPFLAGS) -c $< -o $@ + + .cpp.o: +- $(CXX) $(CXXFLAGS) -c $< -o $@ ++ $(CXX) $(CXXFLAGS) $(CPPFLAGS) -c $< -o $@ + + $(STATICLIB): $(MODULES) + $(AR) r $@ $(MODULES) + + $(SHAREDLIB): $(MODULES) +- $(CC) -s -shared -Wl,-soname,$(VERLIBNAME) $(LDFLAGS) -o $@ $(MODULES) $(LIBRARIES) ++ $(CC) -shared -Wl,-soname,$(VERLIBNAME) $(LDFLAGS) -o $@ $(MODULES) $(LIBRARIES) + + install: + install -d $(INCDIR) $(INSTALLDIR) +@@ -79,5 +78,5 @@ install: + # ldconfig + + clean: +- rm -f core Dist/*.* u2dtmp* $(MODULES) $(STATICLIB) $(SHAREDLIB) $(LIBNAME) ++ rm -f Dist/lib$(TARGET)* Dist/FreeImage.h $(MODULES) $(STATICLIB) $(SHAREDLIB) $(LIBNAME) + diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-jpeg_read_icc_profile.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-jpeg_read_icc_profile.patch new file mode 100644 index 00000000000..62edae8e7f8 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/Use-system-jpeg_read_icc_profile.patch @@ -0,0 +1,128 @@ +Description: Use jpeg_read_icc_profile() from libjpeg + Current version of libjpeg8-turbo provides jpeg_read_icc_profile(), which + means our static definition now conflicts with the system headers. Drop + the local implementation in favor of the (compatible) libjpeg one. +Author: Steve Langasek +Last-Modified: 2018-11-14 + +Index: freeimage-3.17.0+ds1/Source/FreeImage/PluginJPEG.cpp +=================================================================== +--- freeimage-3.17.0+ds1.orig/Source/FreeImage/PluginJPEG.cpp ++++ freeimage-3.17.0+ds1/Source/FreeImage/PluginJPEG.cpp +@@ -485,116 +485,6 @@ + } + + /** +- See if there was an ICC profile in the JPEG file being read; +- if so, reassemble and return the profile data. +- +- TRUE is returned if an ICC profile was found, FALSE if not. +- If TRUE is returned, *icc_data_ptr is set to point to the +- returned data, and *icc_data_len is set to its length. +- +- IMPORTANT: the data at **icc_data_ptr has been allocated with malloc() +- and must be freed by the caller with free() when the caller no longer +- needs it. (Alternatively, we could write this routine to use the +- IJG library's memory allocator, so that the data would be freed implicitly +- at jpeg_finish_decompress() time. But it seems likely that many apps +- will prefer to have the data stick around after decompression finishes.) +- +- NOTE: if the file contains invalid ICC APP2 markers, we just silently +- return FALSE. You might want to issue an error message instead. +-*/ +-BOOL +-jpeg_read_icc_profile(j_decompress_ptr cinfo, JOCTET **icc_data_ptr, unsigned *icc_data_len) { +- jpeg_saved_marker_ptr marker; +- int num_markers = 0; +- int seq_no; +- JOCTET *icc_data; +- unsigned total_length; +- +- const int MAX_SEQ_NO = 255; // sufficient since marker numbers are bytes +- BYTE marker_present[MAX_SEQ_NO+1]; // 1 if marker found +- unsigned data_length[MAX_SEQ_NO+1]; // size of profile data in marker +- unsigned data_offset[MAX_SEQ_NO+1]; // offset for data in marker +- +- *icc_data_ptr = NULL; // avoid confusion if FALSE return +- *icc_data_len = 0; +- +- /** +- this first pass over the saved markers discovers whether there are +- any ICC markers and verifies the consistency of the marker numbering. +- */ +- +- memset(marker_present, 0, (MAX_SEQ_NO + 1)); +- +- for(marker = cinfo->marker_list; marker != NULL; marker = marker->next) { +- if (marker_is_icc(marker)) { +- if (num_markers == 0) { +- // number of markers +- num_markers = GETJOCTET(marker->data[13]); +- } +- else if (num_markers != GETJOCTET(marker->data[13])) { +- return FALSE; // inconsistent num_markers fields +- } +- // sequence number +- seq_no = GETJOCTET(marker->data[12]); +- if (seq_no <= 0 || seq_no > num_markers) { +- return FALSE; // bogus sequence number +- } +- if (marker_present[seq_no]) { +- return FALSE; // duplicate sequence numbers +- } +- marker_present[seq_no] = 1; +- data_length[seq_no] = marker->data_length - ICC_HEADER_SIZE; +- } +- } +- +- if (num_markers == 0) +- return FALSE; +- +- /** +- check for missing markers, count total space needed, +- compute offset of each marker's part of the data. +- */ +- +- total_length = 0; +- for(seq_no = 1; seq_no <= num_markers; seq_no++) { +- if (marker_present[seq_no] == 0) { +- return FALSE; // missing sequence number +- } +- data_offset[seq_no] = total_length; +- total_length += data_length[seq_no]; +- } +- +- if (total_length <= 0) +- return FALSE; // found only empty markers ? +- +- // allocate space for assembled data +- icc_data = (JOCTET *) malloc(total_length * sizeof(JOCTET)); +- if (icc_data == NULL) +- return FALSE; // out of memory +- +- // and fill it in +- for (marker = cinfo->marker_list; marker != NULL; marker = marker->next) { +- if (marker_is_icc(marker)) { +- JOCTET FAR *src_ptr; +- JOCTET *dst_ptr; +- unsigned length; +- seq_no = GETJOCTET(marker->data[12]); +- dst_ptr = icc_data + data_offset[seq_no]; +- src_ptr = marker->data + ICC_HEADER_SIZE; +- length = data_length[seq_no]; +- while (length--) { +- *dst_ptr++ = *src_ptr++; +- } +- } +- } +- +- *icc_data_ptr = icc_data; +- *icc_data_len = total_length; +- +- return TRUE; +-} +- +-/** + Read JPEG_APPD marker (IPTC or Adobe Photoshop profile) + */ + static BOOL diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-freeimage-with-libraw-0.21.1.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-freeimage-with-libraw-0.21.1.patch new file mode 100644 index 00000000000..6d5f8349702 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-freeimage-with-libraw-0.21.1.patch @@ -0,0 +1,20 @@ +https://bugs.debian.org/cgi-bin/bugreport.cgi?bug=1040259 +Signed-off-by: Rob Woolley + +Description: Fix FTBFS on some big-endian targets +Bug-Debian: https://bugs.debian.org/1002610 +Origin: backport, https://sourceforge.net/p/freeimage/svn/1809/ + +Index: git/Source/FreeImage/PluginRAW.cpp +=================================================================== +--- git.orig/Source/FreeImage/PluginRAW.cpp ++++ git/Source/FreeImage/PluginRAW.cpp +@@ -691,7 +691,7 @@ Load(FreeImageIO *io, fi_handle handle, + // -------------------------------------------- + + // (-s [0..N-1]) Select one raw image from input file +- RawProcessor->imgdata.params.shot_select = 0; ++ RawProcessor->imgdata.rawparams.shot_select = 0; + // (-w) Use camera white balance, if possible (otherwise, fallback to auto_wb) + RawProcessor->imgdata.params.use_camera_wb = 1; + // (-M) Use any color matrix from the camera metadata. This option only affects Olympus, Leaf, and Phase One cameras. diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-include-dirs.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-include-dirs.patch new file mode 100644 index 00000000000..d3193ca5647 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/fix-include-dirs.patch @@ -0,0 +1,19 @@ +Index: git/Makefile.gnu +=================================================================== +--- git.orig/Makefile.gnu ++++ git/Makefile.gnu +@@ -26,12 +26,12 @@ override CFLAGS += -DOPJ_STATIC + override CFLAGS += -DNO_LCMS + # LibJXR + override CFLAGS += -DDISABLE_PERF_MEASUREMENT -D__ANSI__ +-override CFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) ++override CFLAGS += $(INCLUDE) $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib libjxr) + CXXFLAGS ?= -O3 -fPIC + override CXXFLAGS += -fexceptions -fvisibility=hidden -Wno-ctor-dtor-privacy + # LibJXR + override CXXFLAGS += -D__ANSI__ +-override CXXFLAGS += $(INCLUDE) -I/usr/include/jxrlib $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib) ++override CXXFLAGS += $(INCLUDE) $(shell $(PKG_CONFIG) --cflags libjpeg libopenjp2 libpng libraw libtiff-4 libwebpmux OpenEXR zlib libjxr) + + TARGET = freeimage + STATICLIB = lib$(TARGET).a diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/r1830-minor-refactoring.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1830-minor-refactoring.patch new file mode 100644 index 00000000000..a4da6a12455 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1830-minor-refactoring.patch @@ -0,0 +1,15 @@ +Index: Source/Utilities.h +=================================================================== +diff --git a/Source/Utilities.h b/Source/Utilities.h +--- a/Source/Utilities.h (revision 1829) ++++ b/Source/Utilities.h (revision 1830) +@@ -529,7 +529,8 @@ + static const char *FI_MSG_ERROR_DIB_MEMORY = "DIB allocation failed, maybe caused by an invalid image size or by a lack of memory"; + static const char *FI_MSG_ERROR_PARSING = "Parsing error"; + static const char *FI_MSG_ERROR_MAGIC_NUMBER = "Invalid magic number"; +-static const char *FI_MSG_ERROR_UNSUPPORTED_FORMAT = "Unsupported format"; ++static const char *FI_MSG_ERROR_UNSUPPORTED_FORMAT = "Unsupported image format"; ++static const char *FI_MSG_ERROR_INVALID_FORMAT = "Invalid file format"; + static const char *FI_MSG_ERROR_UNSUPPORTED_COMPRESSION = "Unsupported compression type"; + static const char *FI_MSG_WARNING_INVALID_THUMBNAIL = "Warning: attached thumbnail cannot be written to output file (invalid format) - Thumbnail saving aborted"; + diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/r1832-improved-BMP-plugin-when-working-with-malicious-images.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1832-improved-BMP-plugin-when-working-with-malicious-images.patch new file mode 100644 index 00000000000..e69c0a2d8b3 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1832-improved-BMP-plugin-when-working-with-malicious-images.patch @@ -0,0 +1,455 @@ +Origin: upstream, r1832 +Index: Source/FreeImage/PluginBMP.cpp +--- +diff --git a/Source/FreeImage/PluginBMP.cpp b/Source/FreeImage/PluginBMP.cpp +--- a/Source/FreeImage/PluginBMP.cpp (revision 1831) ++++ b/Source/FreeImage/PluginBMP.cpp (revision 1832) +@@ -181,6 +181,7 @@ + } + } + #endif ++ + #if FREEIMAGE_COLORORDER == FREEIMAGE_COLORORDER_RGB + if (bit_count == 24 || bit_count == 32) { + for(unsigned y = 0; y < FreeImage_GetHeight(dib); y++) { +@@ -202,7 +203,7 @@ + @param handle FreeImage IO handle + @param width Image width + @param height Image height +-@param dib Image to be loaded ++@param dib 4-bit image to be loaded + @return Returns TRUE if successful, returns FALSE otherwise + */ + static BOOL +@@ -217,7 +218,9 @@ + height = abs(height); + + pixels = (BYTE*)malloc(width * height * sizeof(BYTE)); +- if(!pixels) throw(1); ++ if (!pixels) { ++ throw(1); ++ } + memset(pixels, 0, width * height * sizeof(BYTE)); + + BYTE *q = pixels; +@@ -237,7 +240,7 @@ + throw(1); + } + for (int i = 0; i < status_byte; i++) { +- *q++=(BYTE)((i & 0x01) ? (second_byte & 0x0f) : ((second_byte >> 4) & 0x0f)); ++ *q++ = (BYTE)((i & 0x01) ? (second_byte & 0x0f) : ((second_byte >> 4) & 0x0f)); + } + bits += status_byte; + } +@@ -252,7 +255,7 @@ + // End of line + bits = 0; + scanline++; +- q = pixels + scanline*width; ++ q = pixels + scanline * width; + } + break; + +@@ -264,7 +267,6 @@ + case RLE_DELTA: + { + // read the delta values +- + BYTE delta_x = 0; + BYTE delta_y = 0; + +@@ -276,7 +278,6 @@ + } + + // apply them +- + bits += delta_x; + scanline += delta_y; + q = pixels + scanline*width+bits; +@@ -293,7 +294,7 @@ + throw(1); + } + } +- *q++=(BYTE)((i & 0x01) ? (second_byte & 0x0f) : ((second_byte >> 4) & 0x0f)); ++ *q++ = (BYTE)((i & 0x01) ? (second_byte & 0x0f) : ((second_byte >> 4) & 0x0f)); + } + bits += status_byte; + // Read pad byte +@@ -334,7 +335,9 @@ + return TRUE; + + } catch(int) { +- if(pixels) free(pixels); ++ if (pixels) { ++ free(pixels); ++ } + return FALSE; + } + } +@@ -345,7 +348,7 @@ + @param handle FreeImage IO handle + @param width Image width + @param height Image height +-@param dib Image to be loaded ++@param dib 8-bit image to be loaded + @return Returns TRUE if successful, returns FALSE otherwise + */ + static BOOL +@@ -354,103 +357,85 @@ + BYTE second_byte = 0; + int scanline = 0; + int bits = 0; ++ int count = 0; ++ BYTE delta_x = 0; ++ BYTE delta_y = 0; + +- for (;;) { +- if( io->read_proc(&status_byte, sizeof(BYTE), 1, handle) != 1) { ++ height = abs(height); ++ ++ while(scanline < height) { ++ ++ if (io->read_proc(&status_byte, sizeof(BYTE), 1, handle) != 1) { + return FALSE; + } + +- switch (status_byte) { +- case RLE_COMMAND : +- if(io->read_proc(&status_byte, sizeof(BYTE), 1, handle) != 1) { +- return FALSE; +- } ++ if (status_byte == RLE_COMMAND) { ++ if (io->read_proc(&status_byte, sizeof(BYTE), 1, handle) != 1) { ++ return FALSE; ++ } + +- switch (status_byte) { +- case RLE_ENDOFLINE : +- bits = 0; +- scanline++; +- break; ++ switch (status_byte) { ++ case RLE_ENDOFLINE: ++ bits = 0; ++ scanline++; ++ break; + +- case RLE_ENDOFBITMAP : +- return TRUE; ++ case RLE_ENDOFBITMAP: ++ return TRUE; + +- case RLE_DELTA : +- { +- // read the delta values ++ case RLE_DELTA: ++ // read the delta values ++ delta_x = 0; ++ delta_y = 0; ++ if (io->read_proc(&delta_x, sizeof(BYTE), 1, handle) != 1) { ++ return FALSE; ++ } ++ if (io->read_proc(&delta_y, sizeof(BYTE), 1, handle) != 1) { ++ return FALSE; ++ } ++ // apply them ++ bits += delta_x; ++ scanline += delta_y; ++ break; + +- BYTE delta_x = 0; +- BYTE delta_y = 0; +- +- if(io->read_proc(&delta_x, sizeof(BYTE), 1, handle) != 1) { +- return FALSE; +- } +- if(io->read_proc(&delta_y, sizeof(BYTE), 1, handle) != 1) { +- return FALSE; +- } +- +- // apply them +- +- bits += delta_x; +- scanline += delta_y; +- +- break; ++ default: ++ // absolute mode ++ count = MIN((int)status_byte, width - bits); ++ if (count < 0) { ++ return FALSE; + } +- +- default : +- { +- if(scanline >= abs(height)) { +- return TRUE; +- } +- +- int count = MIN((int)status_byte, width - bits); +- +- BYTE *sline = FreeImage_GetScanLine(dib, scanline); +- +- if(io->read_proc((void *)(sline + bits), sizeof(BYTE) * count, 1, handle) != 1) { ++ BYTE *sline = FreeImage_GetScanLine(dib, scanline); ++ if (io->read_proc((void *)(sline + bits), sizeof(BYTE) * count, 1, handle) != 1) { ++ return FALSE; ++ } ++ // align run length to even number of bytes ++ if ((status_byte & 1) == 1) { ++ if (io->read_proc(&second_byte, sizeof(BYTE), 1, handle) != 1) { + return FALSE; + } +- +- // align run length to even number of bytes +- +- if ((status_byte & 1) == 1) { +- if(io->read_proc(&second_byte, sizeof(BYTE), 1, handle) != 1) { +- return FALSE; +- } +- } +- +- bits += status_byte; +- +- break; + } +- } ++ bits += status_byte; ++ break; + +- break; +- +- default : +- { +- if(scanline >= abs(height)) { +- return TRUE; +- } +- +- int count = MIN((int)status_byte, width - bits); +- +- BYTE *sline = FreeImage_GetScanLine(dib, scanline); +- +- if(io->read_proc(&second_byte, sizeof(BYTE), 1, handle) != 1) { +- return FALSE; +- } +- +- for (int i = 0; i < count; i++) { +- *(sline + bits) = second_byte; +- +- bits++; +- } +- +- break; ++ } // switch (status_byte) ++ } ++ else { ++ count = MIN((int)status_byte, width - bits); ++ if (count < 0) { ++ return FALSE; + } ++ BYTE *sline = FreeImage_GetScanLine(dib, scanline); ++ if (io->read_proc(&second_byte, sizeof(BYTE), 1, handle) != 1) { ++ return FALSE; ++ } ++ for (int i = 0; i < count; i++) { ++ *(sline + bits) = second_byte; ++ bits++; ++ } + } + } ++ ++ return FALSE; + } + + // -------------------------------------------------------------------------- +@@ -463,10 +448,12 @@ + BOOL header_only = (flags & FIF_LOAD_NOPIXELS) == FIF_LOAD_NOPIXELS; + + // load the info header +- + BITMAPINFOHEADER bih; ++ memset(&bih, 0, sizeof(BITMAPINFOHEADER)); ++ if (io->read_proc(&bih, sizeof(BITMAPINFOHEADER), 1, handle) != 1) { ++ throw FI_MSG_ERROR_INVALID_FORMAT; ++ } + +- io->read_proc(&bih, sizeof(BITMAPINFOHEADER), 1, handle); + #ifdef FREEIMAGE_BIGENDIAN + SwapInfoHeader(&bih); + #endif +@@ -514,8 +501,8 @@ + } + + // load the palette ++ io->read_proc(FreeImage_GetPalette(dib), used_colors * sizeof(RGBQUAD), 1, handle); + +- io->read_proc(FreeImage_GetPalette(dib), used_colors * sizeof(RGBQUAD), 1, handle); + #if FREEIMAGE_COLORORDER == FREEIMAGE_COLORORDER_RGB + RGBQUAD *pal = FreeImage_GetPalette(dib); + for(unsigned i = 0; i < used_colors; i++) { +@@ -544,7 +531,7 @@ + break; + + case BI_RLE4 : +- if( LoadPixelDataRLE4(io, handle, width, height, dib) ) { ++ if( (bit_count == 4) && LoadPixelDataRLE4(io, handle, width, height, dib) ) { + return dib; + } else { + throw "Error encountered while decoding RLE4 BMP data"; +@@ -552,7 +539,7 @@ + break; + + case BI_RLE8 : +- if( LoadPixelDataRLE8(io, handle, width, height, dib) ) { ++ if( (bit_count == 8) && LoadPixelDataRLE8(io, handle, width, height, dib) ) { + return dib; + } else { + throw "Error encountered while decoding RLE8 BMP data"; +@@ -602,7 +589,7 @@ + + return dib; + } +- break; // 16-bit ++ break; // 16-bit RGB + + case 24 : + case 32 : +@@ -679,10 +666,12 @@ + BOOL header_only = (flags & FIF_LOAD_NOPIXELS) == FIF_LOAD_NOPIXELS; + + // load the info header +- + BITMAPINFOHEADER bih; ++ memset(&bih, 0, sizeof(BITMAPINFOHEADER)); ++ if (io->read_proc(&bih, sizeof(BITMAPINFOHEADER), 1, handle) != 1) { ++ throw FI_MSG_ERROR_INVALID_FORMAT; ++ } + +- io->read_proc(&bih, sizeof(BITMAPINFOHEADER), 1, handle); + #ifdef FREEIMAGE_BIGENDIAN + SwapInfoHeader(&bih); + #endif +@@ -767,17 +756,19 @@ + return dib; + + case BI_RLE4 : +- if( LoadPixelDataRLE4(io, handle, width, height, dib) ) { ++ if ((bit_count == 4) && LoadPixelDataRLE4(io, handle, width, height, dib)) { + return dib; +- } else { ++ } ++ else { + throw "Error encountered while decoding RLE4 BMP data"; + } + break; + + case BI_RLE8 : +- if( LoadPixelDataRLE8(io, handle, width, height, dib) ) { ++ if ((bit_count == 8) && LoadPixelDataRLE8(io, handle, width, height, dib)) { + return dib; +- } else { ++ } ++ else { + throw "Error encountered while decoding RLE8 BMP data"; + } + break; +@@ -863,9 +854,9 @@ + } + } + } catch(const char *message) { +- if(dib) ++ if (dib) { + FreeImage_Unload(dib); +- ++ } + FreeImage_OutputMessageProc(s_format_id, message); + } + +@@ -881,9 +872,13 @@ + try { + BOOL header_only = (flags & FIF_LOAD_NOPIXELS) == FIF_LOAD_NOPIXELS; + ++ // load the info header + BITMAPINFOOS2_1X_HEADER bios2_1x; ++ memset(&bios2_1x, 0, sizeof(BITMAPINFOOS2_1X_HEADER)); ++ if (io->read_proc(&bios2_1x, sizeof(BITMAPINFOOS2_1X_HEADER), 1, handle) != 1) { ++ throw FI_MSG_ERROR_INVALID_FORMAT; ++ } + +- io->read_proc(&bios2_1x, sizeof(BITMAPINFOOS2_1X_HEADER), 1, handle); + #ifdef FREEIMAGE_BIGENDIAN + SwapOS21XHeader(&bios2_1x); + #endif +@@ -1005,9 +1000,9 @@ + } + } + } catch(const char *message) { +- if(dib) ++ if (dib) { + FreeImage_Unload(dib); +- ++ } + FreeImage_OutputMessageProc(s_format_id, message); + } + +@@ -1090,19 +1085,20 @@ + BITMAPFILEHEADER bitmapfileheader; + DWORD type = 0; + +- // we use this offset value to make seemingly absolute seeks relative in the file +- ++ // we use this offset value to make seemingly absolute seeks relative in the file + long offset_in_file = io->tell_proc(handle); + + // read the fileheader ++ memset(&bitmapfileheader, 0, sizeof(BITMAPFILEHEADER)); ++ if (io->read_proc(&bitmapfileheader, sizeof(BITMAPFILEHEADER), 1, handle) != 1) { ++ return NULL; ++ } + +- io->read_proc(&bitmapfileheader, sizeof(BITMAPFILEHEADER), 1, handle); + #ifdef FREEIMAGE_BIGENDIAN + SwapFileHeader(&bitmapfileheader); + #endif + + // check the signature +- + if((bitmapfileheader.bfType != 0x4D42) && (bitmapfileheader.bfType != 0x4142)) { + FreeImage_OutputMessageProc(s_format_id, FI_MSG_ERROR_MAGIC_NUMBER); + return NULL; +@@ -1109,9 +1105,9 @@ + } + + // read the first byte of the infoheader +- + io->read_proc(&type, sizeof(DWORD), 1, handle); + io->seek_proc(handle, 0 - (long)sizeof(DWORD), SEEK_CUR); ++ + #ifdef FREEIMAGE_BIGENDIAN + SwapLong(&type); + #endif +@@ -1138,7 +1134,7 @@ + break; + } + +- FreeImage_OutputMessageProc(s_format_id, "unknown bmp subtype with id %d", type); ++ FreeImage_OutputMessageProc(s_format_id, "Unknown bmp subtype with id %d", type); + } + + return NULL; +@@ -1418,6 +1414,7 @@ + } + + free(buffer); ++ + #ifdef FREEIMAGE_BIGENDIAN + } else if (dst_bpp == 16) { + int padding = dst_pitch - dst_width * sizeof(WORD); +@@ -1439,6 +1436,7 @@ + } + } + #endif ++ + #if FREEIMAGE_COLORORDER == FREEIMAGE_COLORORDER_RGB + } else if (dst_bpp == 24) { + int padding = dst_pitch - dst_width * sizeof(FILE_BGR); diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/r1836-improved-BMP-plugin-when-working-with-malicious-images.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1836-improved-BMP-plugin-when-working-with-malicious-images.patch new file mode 100644 index 00000000000..27b5a45c332 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1836-improved-BMP-plugin-when-working-with-malicious-images.patch @@ -0,0 +1,159 @@ +Origin: upstream, r1836 +Index: Source/FreeImage/PluginBMP.cpp +--- +diff --git a/Source/FreeImage/PluginBMP.cpp b/Source/FreeImage/PluginBMP.cpp +--- a/Source/FreeImage/PluginBMP.cpp (revision 1835) ++++ b/Source/FreeImage/PluginBMP.cpp (revision 1836) +@@ -139,6 +139,75 @@ + // -------------------------------------------------------------------------- + + /** ++Check if a BITMAPINFOHEADER is valid ++@return Returns TRUE if successful, returns FALSE otherwise ++*/ ++static BOOL ++CheckBitmapInfoHeader(BITMAPINFOHEADER *bih) { ++ if (bih->biSize != sizeof(BITMAPINFOHEADER)) { ++ // The size, in bytes, of the image.This may be set to zero for BI_RGB bitmaps. ++ // If biCompression is BI_JPEG or BI_PNG, biSizeImage indicates the size of the JPEG or PNG image buffer, respectively. ++ if ((bih->biSize == 0) && (bih->biCompression != BI_RGB)) { ++ return FALSE; ++ } ++ else if ((bih->biCompression == BI_JPEG) || (bih->biCompression == BI_PNG)) { ++ // JPEG or PNG is not yet supported ++ return FALSE; ++ } ++ else { ++ return FALSE; ++ } ++ } ++ if (bih->biWidth < 0) { ++ return FALSE; ++ } ++ if (bih->biHeight < 0) { ++ // If biHeight is negative, indicating a top-down DIB, biCompression must be either BI_RGB or BI_BITFIELDS. ++ // Top-down DIBs cannot be compressed. ++ // If biCompression is BI_JPEG or BI_PNG, the biHeight member specifies the height of the decompressed JPEG or PNG image file, respectively. ++ if ((bih->biCompression != BI_RGB) && (bih->biCompression != BI_BITFIELDS)) { ++ return FALSE; ++ } ++ } ++ if (bih->biPlanes != 1) { ++ // The number of planes for the target device. This value must be set to 1. ++ return FALSE; ++ } ++ switch (bih->biBitCount) { ++ case 0: ++ // The number of bits-per-pixel is specified or is implied by the JPEG or PNG format. ++ // JPEG or PNG is not yet supported ++ return FALSE; ++ break; ++ case 1: ++ case 4: ++ case 8: ++ case 16: ++ case 24: ++ case 32: ++ break; ++ default: ++ // Unsupported bitdepth ++ return FALSE; ++ } ++ switch (bih->biCompression) { ++ case BI_RGB: ++ case BI_RLE8: ++ case BI_RLE4: ++ case BI_BITFIELDS: ++ break; ++ case BI_JPEG: ++ case BI_PNG: ++ default: ++ return FALSE; ++ } ++ ++ return TRUE; ++} ++ ++// -------------------------------------------------------------------------- ++ ++/** + Load uncompressed image pixels for 1-, 4-, 8-, 16-, 24- and 32-bit dib + @param io FreeImage IO + @param handle FreeImage IO handle +@@ -458,6 +527,10 @@ + SwapInfoHeader(&bih); + #endif + ++ if (CheckBitmapInfoHeader(&bih) == FALSE) { ++ throw FI_MSG_ERROR_INVALID_FORMAT; ++ } ++ + // keep some general information about the bitmap + + unsigned used_colors = bih.biClrUsed; +@@ -555,10 +628,18 @@ + case 16 : + { + int use_bitfields = 0; +- if (bih.biCompression == BI_BITFIELDS) use_bitfields = 3; +- else if (bih.biCompression == BI_ALPHABITFIELDS) use_bitfields = 4; +- else if (type == 52) use_bitfields = 3; +- else if (type >= 56) use_bitfields = 4; ++ if (bih.biCompression == BI_BITFIELDS) { ++ use_bitfields = 3; ++ } ++ else if (bih.biCompression == BI_ALPHABITFIELDS) { ++ use_bitfields = 4; ++ } ++ else if (type == 52) { ++ use_bitfields = 3; ++ } ++ else if (type >= 56) { ++ use_bitfields = 4; ++ } + + if (use_bitfields > 0) { + DWORD bitfields[4]; +@@ -595,10 +676,18 @@ + case 32 : + { + int use_bitfields = 0; +- if (bih.biCompression == BI_BITFIELDS) use_bitfields = 3; +- else if (bih.biCompression == BI_ALPHABITFIELDS) use_bitfields = 4; +- else if (type == 52) use_bitfields = 3; +- else if (type >= 56) use_bitfields = 4; ++ if (bih.biCompression == BI_BITFIELDS) { ++ use_bitfields = 3; ++ } ++ else if (bih.biCompression == BI_ALPHABITFIELDS) { ++ use_bitfields = 4; ++ } ++ else if (type == 52) { ++ use_bitfields = 3; ++ } ++ else if (type >= 56) { ++ use_bitfields = 4; ++ } + + if (use_bitfields > 0) { + DWORD bitfields[4]; +@@ -676,6 +765,10 @@ + SwapInfoHeader(&bih); + #endif + ++ if (CheckBitmapInfoHeader(&bih) == FALSE) { ++ throw FI_MSG_ERROR_INVALID_FORMAT; ++ } ++ + // keep some general information about the bitmap + + unsigned used_colors = bih.biClrUsed; +@@ -780,7 +873,7 @@ + + case 16 : + { +- if (bih.biCompression == 3) { ++ if (bih.biCompression == BI_BITFIELDS) { + DWORD bitfields[3]; + + io->read_proc(bitfields, 3 * sizeof(DWORD), 1, handle); diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/r1848-improved-PFM-plugin-against-malicious-images.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1848-improved-PFM-plugin-against-malicious-images.patch new file mode 100644 index 00000000000..8d2a580d25d --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1848-improved-PFM-plugin-against-malicious-images.patch @@ -0,0 +1,227 @@ +Origin: upstream, r1848 +Index: Source/FreeImage/PluginPFM.cpp +--- +diff --git a/Source/FreeImage/PluginPFM.cpp b/Source/FreeImage/PluginPFM.cpp +--- a/Source/FreeImage/PluginPFM.cpp (revision 1847) ++++ b/Source/FreeImage/PluginPFM.cpp (revision 1848) +@@ -23,6 +23,12 @@ + #include "Utilities.h" + + // ========================================================== ++// Plugin Interface ++// ========================================================== ++ ++static int s_format_id; ++ ++// ========================================================== + // Internal functions + // ========================================================== + +@@ -59,6 +65,9 @@ + + /** + Get an integer value from the actual position pointed by handle ++@param io ++@param handle ++@return Returns -1 in case of failure, returns the found number otherwise + */ + static int + pfm_get_int(FreeImageIO *io, fi_handle handle) { +@@ -65,70 +74,72 @@ + char c = 0; + BOOL bFirstChar; + +- // skip forward to start of next number ++ try { + +- if(!io->read_proc(&c, 1, 1, handle)) { +- throw FI_MSG_ERROR_PARSING; +- } ++ // skip forward to start of next number + +- while (1) { +- // eat comments ++ if (io->read_proc(&c, 1, 1, handle) != 1) { ++ throw FI_MSG_ERROR_PARSING; ++ } + +- if (c == '#') { +- // if we're at a comment, read to end of line ++ while (1) { ++ // eat comments + +- bFirstChar = TRUE; ++ if (c == '#') { ++ // if we're at a comment, read to end of line + +- while (1) { +- if(!io->read_proc(&c, 1, 1, handle)) { +- throw FI_MSG_ERROR_PARSING; +- } ++ bFirstChar = TRUE; + +- if (bFirstChar && c == ' ') { +- // loop off 1 sp after # +- bFirstChar = FALSE; +- } else if (c == '\n') { +- break; ++ while (1) { ++ if (io->read_proc(&c, 1, 1, handle) != 1) { ++ throw FI_MSG_ERROR_PARSING; ++ } ++ ++ if (bFirstChar && c == ' ') { ++ // loop off 1 sp after # ++ bFirstChar = FALSE; ++ } ++ else if (c == '\n') { ++ break; ++ } + } + } +- } + +- if (c >= '0' && c <='9') { +- // we've found what we were looking for +- break; +- } ++ if (c >= '0' && c <= '9') { ++ // we've found what we were looking for ++ break; ++ } + +- if(!io->read_proc(&c, 1, 1, handle)) { +- throw FI_MSG_ERROR_PARSING; ++ if (io->read_proc(&c, 1, 1, handle) != 1) { ++ throw FI_MSG_ERROR_PARSING; ++ } + } +- } + +- // we're at the start of a number, continue until we hit a non-number ++ // we're at the start of a number, continue until we hit a non-number + +- int i = 0; ++ int i = 0; + +- while (1) { +- i = (i * 10) + (c - '0'); ++ while (1) { ++ i = (i * 10) + (c - '0'); + +- if(!io->read_proc(&c, 1, 1, handle)) { +- throw FI_MSG_ERROR_PARSING; +- } ++ if (io->read_proc(&c, 1, 1, handle) != 1) { ++ throw FI_MSG_ERROR_PARSING; ++ } + +- if (c < '0' || c > '9') { +- break; ++ if (c < '0' || c > '9') { ++ break; ++ } + } +- } + +- return i; ++ return i; ++ } ++ catch (const char *message) { ++ FreeImage_OutputMessageProc(s_format_id, message); ++ return -1; ++ } + } + + // ========================================================== +-// Plugin Interface +-// ========================================================== +- +-static int s_format_id; +- +-// ========================================================== + // Plugin Implementation + // ========================================================== + +@@ -230,8 +241,12 @@ + } + + // Read the header information: width, height and the scale value +- unsigned width = (unsigned) pfm_get_int(io, handle); +- unsigned height = (unsigned) pfm_get_int(io, handle); ++ int width = pfm_get_int(io, handle); ++ int height = pfm_get_int(io, handle); ++ if ((width <= 0) || (height <= 0)) { ++ throw FI_MSG_ERROR_PARSING; ++ } ++ + float scalefactor = 1; + + BOOL bResult = pfm_get_line(io, handle, line_buffer, PFM_MAXLINE); +@@ -262,7 +277,7 @@ + throw FI_MSG_ERROR_MEMORY; + } + +- for (unsigned y = 0; y < height; y++) { ++ for (int y = 0; y < height; y++) { + FIRGBF *bits = (FIRGBF*)FreeImage_GetScanLine(dib, height - 1 - y); + + if(io->read_proc(lineBuffer, sizeof(float), lineWidth, handle) != lineWidth) { +@@ -271,7 +286,7 @@ + float *channel = lineBuffer; + if(scalefactor > 0) { + // MSB +- for (unsigned x = 0; x < width; x++) { ++ for (int x = 0; x < width; x++) { + REVERSEBYTES(channel++, &bits[x].red); + REVERSEBYTES(channel++, &bits[x].green); + REVERSEBYTES(channel++, &bits[x].blue); +@@ -278,7 +293,7 @@ + } + } else { + // LSB +- for (unsigned x = 0; x < width; x++) { ++ for (int x = 0; x < width; x++) { + bits[x].red = *channel++; + bits[x].green = *channel++; + bits[x].blue = *channel++; +@@ -296,7 +311,7 @@ + throw FI_MSG_ERROR_MEMORY; + } + +- for (unsigned y = 0; y < height; y++) { ++ for (int y = 0; y < height; y++) { + float *bits = (float*)FreeImage_GetScanLine(dib, height - 1 - y); + + if(io->read_proc(lineBuffer, sizeof(float), lineWidth, handle) != lineWidth) { +@@ -305,12 +320,12 @@ + float *channel = lineBuffer; + if(scalefactor > 0) { + // MSB - File is Big endian +- for (unsigned x = 0; x < width; x++) { ++ for (int x = 0; x < width; x++) { + REVERSEBYTES(channel++, &bits[x]); + } + } else { + // LSB - File is Little Endian +- for (unsigned x = 0; x < width; x++) { ++ for (int x = 0; x < width; x++) { + bits[x] = *channel++; + } + } +@@ -323,9 +338,12 @@ + return dib; + + } catch (const char *text) { +- if(lineBuffer) free(lineBuffer); +- if(dib) FreeImage_Unload(dib); +- ++ if (lineBuffer) { ++ free(lineBuffer); ++ } ++ if (dib) { ++ FreeImage_Unload(dib); ++ } + if(NULL != text) { + FreeImage_OutputMessageProc(s_format_id, text); + } diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/r1877-improved-DDS-plugin-against-malicious-images.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1877-improved-DDS-plugin-against-malicious-images.patch new file mode 100644 index 00000000000..af79c7b866e --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/r1877-improved-DDS-plugin-against-malicious-images.patch @@ -0,0 +1,15 @@ +Origin: upstream, r1877 +Index: Source/FreeImage/PluginDDS.cpp +=================================================================== +diff --git a/Source/FreeImage/PluginDDS.cpp b/Source/FreeImage/PluginDDS.cpp +--- a/Source/FreeImage/PluginDDS.cpp (revision 1876) ++++ b/Source/FreeImage/PluginDDS.cpp (revision 1877) +@@ -617,7 +617,7 @@ + // read the file + // ------------------------------------------------------------------------- + +- const int line = CalculateLine(width, bpp); ++ const int line = CalculateLine(width, FreeImage_GetBPP(dib)); + const int filePitch = ((desc->dwFlags & DDSD_PITCH) == DDSD_PITCH) ? (int)desc->dwPitchOrLinearSize : line; + const long delta = (long)filePitch - (long)line; + diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage/revert-xtiff.patch b/meta-ros-common/recipes-graphics/freeimage/freeimage/revert-xtiff.patch new file mode 100644 index 00000000000..240bb8e81ae --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage/revert-xtiff.patch @@ -0,0 +1,114 @@ +From: Ghislain Antony Vaillant +Date: Tue, 3 Nov 2015 14:39:33 +0000 +Subject: (Revert) Disable vendored dependencies. + +Revert changes to XTIFF from previous Debian patch. + +Index: freeimage-3.18.0+ds2/Source/Metadata/XTIFF.cpp +=================================================================== +--- freeimage-3.18.0+ds2.orig/Source/Metadata/XTIFF.cpp ++++ freeimage-3.18.0+ds2/Source/Metadata/XTIFF.cpp +@@ -224,33 +224,6 @@ tiff_write_geotiff_profile(TIFF *tif, FI + // TIFF EXIF tag reading & writing + // ---------------------------------------------------------- + +-static uint32 exif_tag_ids[] = { +- EXIFTAG_EXPOSURETIME, EXIFTAG_FNUMBER, EXIFTAG_EXPOSUREPROGRAM, +- EXIFTAG_SPECTRALSENSITIVITY, EXIFTAG_ISOSPEEDRATINGS, EXIFTAG_OECF, +- EXIFTAG_EXIFVERSION, EXIFTAG_DATETIMEORIGINAL, EXIFTAG_DATETIMEDIGITIZED, +- EXIFTAG_COMPONENTSCONFIGURATION, EXIFTAG_COMPRESSEDBITSPERPIXEL, +- EXIFTAG_SHUTTERSPEEDVALUE, EXIFTAG_APERTUREVALUE, +- EXIFTAG_BRIGHTNESSVALUE, EXIFTAG_EXPOSUREBIASVALUE, +- EXIFTAG_MAXAPERTUREVALUE, EXIFTAG_SUBJECTDISTANCE, EXIFTAG_METERINGMODE, +- EXIFTAG_LIGHTSOURCE, EXIFTAG_FLASH, EXIFTAG_FOCALLENGTH, +- EXIFTAG_SUBJECTAREA, EXIFTAG_MAKERNOTE, EXIFTAG_USERCOMMENT, +- EXIFTAG_SUBSECTIME, EXIFTAG_SUBSECTIMEORIGINAL, +- EXIFTAG_SUBSECTIMEDIGITIZED, EXIFTAG_FLASHPIXVERSION, EXIFTAG_COLORSPACE, +- EXIFTAG_PIXELXDIMENSION, EXIFTAG_PIXELYDIMENSION, +- EXIFTAG_RELATEDSOUNDFILE, EXIFTAG_FLASHENERGY, +- EXIFTAG_SPATIALFREQUENCYRESPONSE, EXIFTAG_FOCALPLANEXRESOLUTION, +- EXIFTAG_FOCALPLANEYRESOLUTION, EXIFTAG_FOCALPLANERESOLUTIONUNIT, +- EXIFTAG_SUBJECTLOCATION, EXIFTAG_EXPOSUREINDEX, EXIFTAG_SENSINGMETHOD, +- EXIFTAG_FILESOURCE, EXIFTAG_SCENETYPE, EXIFTAG_CFAPATTERN, +- EXIFTAG_CUSTOMRENDERED, EXIFTAG_EXPOSUREMODE, EXIFTAG_WHITEBALANCE, +- EXIFTAG_DIGITALZOOMRATIO, EXIFTAG_FOCALLENGTHIN35MMFILM, +- EXIFTAG_SCENECAPTURETYPE, EXIFTAG_GAINCONTROL, EXIFTAG_CONTRAST, +- EXIFTAG_SATURATION, EXIFTAG_SHARPNESS, EXIFTAG_DEVICESETTINGDESCRIPTION, +- EXIFTAG_SUBJECTDISTANCERANGE, EXIFTAG_GAINCONTROL, EXIFTAG_GAINCONTROL, +- EXIFTAG_IMAGEUNIQUEID +-}; +-static int nExifTags = sizeof(exif_tag_ids) / sizeof(exif_tag_ids[0]); +- + /** + Read a single Exif tag + +@@ -575,10 +602,43 @@ tiff_read_exif_tags(TIFF *tif, TagLib::M + + // loop over all Core Directory Tags + // ### uses private data, but there is no other way +- // -> Fedora: Best we can do without private headers is to hard-code a list of known EXIF tags and read those + if(md_model == TagLib::EXIF_MAIN) { ++ const TIFFDirectory *td = &tif->tif_dir; ++ ++ uint32 lastTag = 0; //<- used to prevent reading some tags twice (as stored in tif_fieldinfo) ++ ++ for (int fi = 0, nfi = (int)tif->tif_nfields; nfi > 0; nfi--, fi++) { ++ const TIFFField *fld = tif->tif_fields[fi]; ++ ++ const uint32 tag_id = TIFFFieldTag(fld); ++ ++ if(tag_id == lastTag) { ++ continue; ++ } ++ ++ // test if tag value is set ++ // (lifted directly from LibTiff _TIFFWriteDirectory) ++ ++ if( fld->field_bit == FIELD_CUSTOM ) { ++ int is_set = FALSE; ++ ++ for(int ci = 0; ci < td->td_customValueCount; ci++ ) { ++ is_set |= (td->td_customValues[ci].info == fld); ++ } ++ ++ if( !is_set ) { ++ continue; ++ } ++ ++ } else if(!TIFFFieldSet(tif, fld->field_bit)) { ++ continue; ++ } ++ ++ // process *all* other tags (some will be ignored) ++ ++ tiff_read_exif_tag(tif, tag_id, dib, md_model); ++ ++ lastTag = tag_id; +- for (int i = 0; i < nExifTags; ++i) { +- tiff_read_exif_tag(tif, exif_tag_ids[i], dib, md_model); + } + + } +@@ -723,9 +717,10 @@ tiff_write_exif_tags(TIFF *tif, TagLib:: + + TagLib& tag_lib = TagLib::instance(); + ++ for (int fi = 0, nfi = (int)tif->tif_nfields; nfi > 0; nfi--, fi++) { ++ const TIFFField *fld = tif->tif_fields[fi]; ++ ++ const uint32 tag_id = TIFFFieldTag(fld); +- for (int fi = 0, nfi = nExifTags; nfi > 0; nfi--, fi++) { +- const uint32 tag_id = exif_tag_ids[fi]; +- const TIFFField *fld = TIFFFieldWithTag(tif, tag_id); + + if(skip_write_field(tif, tag_id)) { + // skip tags that are already handled by the LibTIFF writing process +@@ -749,7 +742,7 @@ tiff_write_exif_tags(TIFF *tif, TagLib:: + continue; + } + // type of storage may differ (e.g. rationnal array vs float array type) ++ if((unsigned)_TIFFDataSize(tif_tag_type) != FreeImage_TagDataWidth(tag_type)) { +- if((unsigned)TIFFFieldSetGetSize(fld) != FreeImage_TagDataWidth(tag_type)) { + // skip tag or _TIFFmemcpy will fail + continue; + } diff --git a/meta-ros-common/recipes-graphics/freeimage/freeimage_3.18.0-2.bb b/meta-ros-common/recipes-graphics/freeimage/freeimage_3.18.0-2.bb new file mode 100644 index 00000000000..b874d1e6515 --- /dev/null +++ b/meta-ros-common/recipes-graphics/freeimage/freeimage_3.18.0-2.bb @@ -0,0 +1,81 @@ +LICENSE = "GPL-2.0-or-later | GPL-3.0-or-later | FIPL-1.0" +LIC_FILES_CHKSUM = "file://Wrapper/Delphi/license.txt;md5=d9993e75dec47df89dbb5da6c939d046 \ + file://license-fi.txt;md5=8e1438cab62c8f655288588dc43daaf6 \ + file://license-gplv2.txt;md5=1fbed70be9d970d3da399f33dae9cc51" + +SRC_URI = " \ + git://salsa.debian.org/science-team/freeimage.git;protocol=https;branch=debian/sid \ + file://Disable-vendored-dependencies.patch \ + file://Use-system-dependencies.patch \ + file://Fix-macro-redefinition-for-64-bit-integer-types.patch \ + file://Fix-compatibility-with-system-libpng.patch \ + file://Disable-usage-of-HTML-timestamps-in-doxygen.patch \ + file://Disable-testing-of-JPEG-transform.patch \ + file://Disable-testing-of-JXR-MemIO.patch \ + file://Fix-encoding-of-fi-header.patch \ + file://Enable-substitution-of-pkg-config.patch \ + file://CVE-2019-12211-13.patch \ + file://Fix_compilation_external-static.patch \ + file://Fix-libraw-compilation.patch \ + file://Use-system-jpeg_read_icc_profile.patch \ + file://Fix-big-endian.patch \ + file://r1830-minor-refactoring.patch \ + file://r1832-improved-BMP-plugin-when-working-with-malicious-images.patch \ + file://r1836-improved-BMP-plugin-when-working-with-malicious-images.patch \ + file://r1848-improved-PFM-plugin-against-malicious-images.patch \ + file://r1877-improved-DDS-plugin-against-malicious-images.patch \ + file://fix-include-dirs.patch \ + file://fix-freeimage-with-libraw-0.21.1.patch \ +" + +PV = "3.18.0-2+git${SRCPV}" +SRCREV = "10780151a1fb824a7fc9f58ca3014624605a50b3" + +S = "${WORKDIR}/git" + +CFLAGS += "-fPIC" +CXXFLAGS += "-fPIC" + +inherit pkgconfig + +DEPENDS = " \ + dos2unix-native \ + libjpeg-turbo \ + libpng \ + libraw \ + libwebp \ + jxrlib \ + openjpeg \ + openexr \ + tiff \ + zlib \ +" + +do_configure () { + # From Debian rules gen-src-list target + sh gensrclist.sh + oe_runmake -f Makefile.gnu dos2unix + sh genfipsrclist.sh + oe_runmake -f Makefile.fip dos2unix +} + +do_compile () { + oe_runmake +} + +do_install () { + oe_runmake DESTDIR="${D}" install +} + +FILES:${PN} = " \ + ${libdir}/libfreeimage-3.18.0.so \ +" + +FILES:${PN}-dev = " \ + ${libdir}/libfreeimage.so \ + ${libdir}/libfreeimage.so.3 \ + ${libdir}/libfreeimage.a \ + ${includedir}/FreeImage.h \ +" + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-graphics/gts/gts/fix-includes.patch b/meta-ros-common/recipes-graphics/gts/gts/fix-includes.patch new file mode 100644 index 00000000000..dd8630cc662 --- /dev/null +++ b/meta-ros-common/recipes-graphics/gts/gts/fix-includes.patch @@ -0,0 +1,37 @@ +# | cc1: warning: include location "/usr/include" is unsafe for cross-compilation [-Wpoison-system-directories] +Index: git/examples/Makefile.am +=================================================================== +--- git.orig/examples/Makefile.am ++++ git/examples/Makefile.am +@@ -1,6 +1,6 @@ + ## Process this file with automake to produce Makefile.in + +-INCLUDES = -I$(top_srcdir) -I$(top_srcdir)/src -I$(includedir)\ ++INCLUDES = -I$(top_builddir) -I$(top_srcdir)/src -I$(top_builddir)/src \ + -DG_LOG_DOMAIN=\"Gts-examples\" + LDADD = $(top_builddir)/src/libgts.la -lm + DEPS = $(top_builddir)/src/libgts.la +Index: git/src/Makefile.am +=================================================================== +--- git.orig/src/Makefile.am ++++ git/src/Makefile.am +@@ -1,6 +1,6 @@ + ## Process this file with automake to produce Makefile.in + +-INCLUDES = -I$(top_srcdir) -I$(includedir) -DG_LOG_DOMAIN=\"Gts\" ++INCLUDES = -I$(top_builddir) -DG_LOG_DOMAIN=\"Gts\" + + bin_SCRIPTS=gts-config + +Index: git/tools/Makefile.am +=================================================================== +--- git.orig/tools/Makefile.am ++++ git/tools/Makefile.am +@@ -1,6 +1,6 @@ + ## Process this file with automake to produce Makefile.in + +-INCLUDES = -I$(top_srcdir) -I$(top_srcdir)/src -I$(includedir)\ ++INCLUDES = -I$(top_builddir) -I$(top_srcdir)/src -I$(top_builddir)/src \ + -DG_LOG_DOMAIN=\"Gts-tools\" + LDADD = $(top_builddir)/src/libgts.la -lm + DEPS = $(top_builddir)/src/libgts.la diff --git a/meta-ros-common/recipes-graphics/gts/gts/fix-predicates_init.patch b/meta-ros-common/recipes-graphics/gts/gts/fix-predicates_init.patch new file mode 100644 index 00000000000..8763b770d55 --- /dev/null +++ b/meta-ros-common/recipes-graphics/gts/gts/fix-predicates_init.patch @@ -0,0 +1,22 @@ +# /bin/bash: line 1: ./predicates_init: No such file or directory +Index: git/src/Makefile.am +=================================================================== +--- git.orig/src/Makefile.am ++++ git/src/Makefile.am +@@ -63,13 +63,13 @@ include_HEADERS = \ + gts.h gtsconfig.h + + predicates.o: predicates.c predicates_init.h predicates.h +- $(COMPILE) -c $(srcdir)/predicates.c ++ $(BUILD_CC) $(INCLUDES) $(BUILD_CPPFLAGS) $(BUILD_CFLAGS) -c $(srcdir)/predicates.c + + predicates_init: predicates_init.c rounding.h +- $(COMPILE) $(srcdir)/predicates_init.c -o $(srcdir)/predicates_init ++ $(BUILD_CC) $(INCLUDES) $(BUILD_CPPFLAGS) $(BUILD_CFLAGS) $(srcdir)/predicates_init.c -o $(builddir)/predicates_init + + predicates_init.h: predicates_init +- ./predicates_init > $(srcdir)/predicates_init.h ++ $(builddir)/predicates_init > $(srcdir)/predicates_init.h + + CLEANFILES = $(BUILT_SOURCES) + diff --git a/meta-ros-common/recipes-graphics/gts/gts_0.7.6.bb b/meta-ros-common/recipes-graphics/gts/gts_0.7.6.bb new file mode 100644 index 00000000000..6611537020a --- /dev/null +++ b/meta-ros-common/recipes-graphics/gts/gts_0.7.6.bb @@ -0,0 +1,19 @@ +LICENSE = "LGPL-2.0-only & Unknown" +LIC_FILES_CHKSUM = "file://COPYING;md5=3bf50002aefd002f49e7bb854063f7e7 \ + file://debian/copyright;md5=98f2cb72cc54864f096332707c784f81" + +SRC_URI = "git://anonscm.debian.org/git/debian-science/packages/gts.git;protocol=https;branch=master \ + file://fix-includes.patch \ + file://fix-predicates_init.patch \ +" + +PV = "0.7.6+git${SRCPV}" +SRCREV = "7cfcef0d9fc44f4fe424455027e78b73864590ec" + +S = "${WORKDIR}/git" + +DEPENDS = "glib-2.0" + +inherit autotools pkgconfig + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/082bb032be1f6c75173bf603252e4f37bfded9fa.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/082bb032be1f6c75173bf603252e4f37bfded9fa.patch new file mode 100644 index 00000000000..66af9afdc4c --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/082bb032be1f6c75173bf603252e4f37bfded9fa.patch @@ -0,0 +1,29 @@ +From 082bb032be1f6c75173bf603252e4f37bfded9fa Mon Sep 17 00:00:00 2001 +From: Milian Wolff +Date: Mon, 7 Jun 2021 09:45:26 +0200 +Subject: [PATCH] Use mkstemp instead of tmpnam + +tmpnam isn't threadsafe and shouldn't be used. Fixes compiler warning: +``` +warning: the use of 'tmpnam' is dangerous, better use 'mkstemp' +``` +--- + image/encode/strenc.c | 4 +++- + 1 file changed, 3 insertions(+), 1 deletion(-) + +diff --git a/image/encode/strenc.c b/image/encode/strenc.c +index d6e970e..65c277e 100644 +--- a/image/encode/strenc.c ++++ b/image/encode/strenc.c +@@ -482,8 +482,10 @@ Int StrIOEncInit(CWMImageStrCodec* pSC) + pSC->ppTempFile[i] = (char *)malloc(FILENAME_MAX * sizeof(char)); + if(pSC->ppTempFile[i] == NULL) return ICERR_ERROR; + +- if ((pFilename = tmpnam(NULL)) == NULL) ++ char tmpnambuf[] = {'f', 'i', 'l', 'e', 'X', 'X', 'X', 'X', 'X', 'X', '\0'}; ++ if (mkstemp(tmpnambuf) == -1) + return ICERR_ERROR; ++ pFilename = tmpnambuf; + strcpy(pSC->ppTempFile[i], pFilename); + #endif + if(CreateWS_File(pSC->ppWStream + i, pFilename, "w+b") != ICERR_OK) return ICERR_ERROR; diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/31df7f88539b77d46ebf408b6a215930ae63bbdd.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/31df7f88539b77d46ebf408b6a215930ae63bbdd.patch new file mode 100644 index 00000000000..328a938d662 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/31df7f88539b77d46ebf408b6a215930ae63bbdd.patch @@ -0,0 +1,76 @@ +From 31df7f88539b77d46ebf408b6a215930ae63bbdd Mon Sep 17 00:00:00 2001 +From: Milian Wolff +Date: Mon, 7 Jun 2021 10:30:46 +0200 +Subject: [PATCH] Fix memory leaks when handling OOM scenario + +If the second or third allocation failed, the code would leak +the first and/or secon allocation. Free all buffers if we return +early to prevent this. +--- + jxrtestlib/JXRTestYUV.c | 18 ++++++++++++++++++ + 1 file changed, 18 insertions(+) + +diff --git a/jxrtestlib/JXRTestYUV.c b/jxrtestlib/JXRTestYUV.c +index 52dc4ca..b803387 100644 +--- a/jxrtestlib/JXRTestYUV.c ++++ b/jxrtestlib/JXRTestYUV.c +@@ -120,6 +120,9 @@ ERR PKImageEncode_WritePixels_IYUV( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + +@@ -198,6 +201,9 @@ ERR PKImageEncode_WritePixels_YUV422( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + //YYUV +@@ -273,6 +279,9 @@ ERR PKImageEncode_WritePixels_YUV444( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + +@@ -491,6 +500,9 @@ ERR PKImageDecode_Copy_IYUV( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + +@@ -564,6 +576,9 @@ ERR PKImageDecode_Copy_YUV422( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + +@@ -635,6 +650,9 @@ ERR PKImageDecode_Copy_YUV444( + + if(pY == NULL || pU == NULL || pV == NULL) + { ++ free(pY); ++ free(pU); ++ free(pV); + return ICERR_ERROR; + } + diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/a684f95783f2f81bd13bf1f8b03ceb12aa87d661.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/a684f95783f2f81bd13bf1f8b03ceb12aa87d661.patch new file mode 100644 index 00000000000..06cce14d184 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/a684f95783f2f81bd13bf1f8b03ceb12aa87d661.patch @@ -0,0 +1,36 @@ +From a684f95783f2f81bd13bf1f8b03ceb12aa87d661 Mon Sep 17 00:00:00 2001 +From: Milian Wolff +Date: Mon, 7 Jun 2021 10:00:09 +0200 +Subject: [PATCH] fix undefined behavior for left-shift of -1 + +My hunch is that (-1 << 31) tries to build INT_MIN, so use that +directly. Compare: + +1 << 31 = 2147483648 +INT_MIN = -2147483648 +--- + image/sys/adapthuff.c | 4 +++- + 1 file changed, 3 insertions(+), 1 deletion(-) + +diff --git a/image/sys/adapthuff.c b/image/sys/adapthuff.c +index a690889..cd83034 100644 +--- a/image/sys/adapthuff.c ++++ b/image/sys/adapthuff.c +@@ -28,6 +28,8 @@ + + #include "strcodec.h" + ++#include ++ + #ifdef MEM_TRACE + #define TRACE_MALLOC 1 + #define TRACE_NEW 0 +@@ -459,7 +461,7 @@ Void AdaptDiscriminant (CAdaptiveHuffman *pAdHuff) + assert (t < gMaxTables[iSym]); + + //pAdHuff->m_iDiscriminant >>= 1; +- pAdHuff->m_iLowerBound = (t == 0) ? (-1 << 31) : -THRESHOLD; ++ pAdHuff->m_iLowerBound = (t == 0) ? INT_MIN : -THRESHOLD; + pAdHuff->m_iUpperBound = (t == gMaxTables[iSym] - 1) ? (1 << 30) : THRESHOLD; + + switch (iSym) { diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/ab9c6b78b7ad3205bdb91ef725b09ddbe3c8945d.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/ab9c6b78b7ad3205bdb91ef725b09ddbe3c8945d.patch new file mode 100644 index 00000000000..54bf84fc97e --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/ab9c6b78b7ad3205bdb91ef725b09ddbe3c8945d.patch @@ -0,0 +1,56 @@ +From ab9c6b78b7ad3205bdb91ef725b09ddbe3c8945d Mon Sep 17 00:00:00 2001 +From: Milian Wolff +Date: Mon, 7 Jun 2021 09:56:37 +0200 +Subject: [PATCH] fix warnings about unaligned loads from UBSAN + +Use memcpy instead to ensure that we don't get warnings about +unaligned loads from UBSAN: + +``` +../3rdParty/jxrlib/image/decode/segdec.c:66:12: runtime error: load of misaligned address 0x7fc3a0544006 for type 'U32', which requires 4 byte alignment +0x7fc3a0544006: note: pointer points here + 01 01 a5 c0 b0 7c 0a 06 05 00 0c 14 10 c2 c0 30 80 38 72 41 ae 1a 8f 54 26 c2 9e f6 c1 25 a9 65 + ^ + #0 0x7fc3e137429a in _load4 ../3rdParty/jxrlib/image/decode/segdec.c:66 + #1 0x7fc3e13748b8 in _flushBit16 ../3rdParty/jxrlib/image/decode/segdec.c:80 + #2 0x7fc3e13749a6 in _getBit16 ../3rdParty/jxrlib/image/decode/segdec.c:86 + #3 0x7fc3e1385d75 in DecodeMacroblockDC ../3rdParty/jxrlib/image/decode/segdec.c:1224 + #4 0x7fc3e131924a in processMacroblockDec ../3rdParty/jxrlib/image/decode/strdec.c:412 + #5 0x7fc3e137207a in ImageStrDecDecode ../3rdParty/jxrlib/image/decode/strdec.c:4003 + #6 0x7fc3e126c0b2 in PKImageDecode_Copy_WMP ../3rdParty/jxrlib/jxrgluelib/JXRGlueJxr.c:1874 +``` +--- + image/decode/segdec.c | 4 +++- + image/sys/strcodec.c | 4 +++- + 2 files changed, 6 insertions(+), 2 deletions(-) + +diff --git a/image/decode/segdec.c b/image/decode/segdec.c +index fb83f2b..3c890af 100644 +--- a/image/decode/segdec.c ++++ b/image/decode/segdec.c +@@ -63,7 +63,9 @@ static U32 _FORCEINLINE _load4(void* pv) + v |= ((U32)((U16 *) pv)[1]) << 16; + return _byteswap_ulong(v); + #else // _M_IA64 +- return _byteswap_ulong(*(U32*)pv); ++ U32 v; ++ memcpy(&v, pv, sizeof(U32)); ++ return _byteswap_ulong(v); + #endif // _M_IA64 + #endif // _BIG__ENDIAN_ + } +diff --git a/image/sys/strcodec.c b/image/sys/strcodec.c +index c746d6f..b0989dd 100644 +--- a/image/sys/strcodec.c ++++ b/image/sys/strcodec.c +@@ -694,7 +694,9 @@ U32 load4BE(void* pv) + v |= ((U32)((U16 *) pv)[1]) << 16; + return _byteswap_ulong(v); + #else // _M_IA64 +- return _byteswap_ulong(*(U32*)pv); ++ U32 v; ++ memcpy(&v, pv, sizeof(U32)); ++ return _byteswap_ulong(v); + #endif // _M_IA64 + #endif // _BIG__ENDIAN_ + } diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug771912.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug771912.patch new file mode 100644 index 00000000000..a9ca33c73e1 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug771912.patch @@ -0,0 +1,32 @@ +Description: Document PNM output +Author: Mathieu Malaterre +Bug-Debian: https://bugs.debian.org/771912 +Forwarded: https://github.com/4creators/jxrlib/pull/4 +Last-Update: 2021-11-26 + +--- jxrlib-1.2~git20170615.f752187.orig/jxrencoderdecoder/JxrDecApp.c ++++ jxrlib-1.2~git20170615.f752187/jxrencoderdecoder/JxrDecApp.c +@@ -82,8 +82,9 @@ void WmpDecAppUsage(const char* szExe) + printf(CRLF); + printf(" -i input.jxr/wdp Input JPEG XR/HD Photo file name" CRLF); + printf(CRLF); +- printf(" -o output.bmp/tif/jxr Output image file name" CRLF); ++ printf(" -o output.bmp/pnm/tif/jxr Output image file name" CRLF); + printf(" bmp: <=8bpc, BGR" CRLF); ++ printf(" pnm: >=8bpc, RGB" CRLF); + printf(" tif: >=8bpc, RGB" CRLF); + printf(" jxr: for compressed domain transcode" CRLF); + printf(CRLF); +--- jxrlib-1.2~git20170615.f752187.orig/jxrencoderdecoder/JxrEncApp.c ++++ jxrlib-1.2~git20170615.f752187/jxrencoderdecoder/JxrEncApp.c +@@ -55,8 +55,9 @@ void WmpEncAppUsage(const char* szExe) + printf(CRLF); + printf("%s [options]..." CRLF, szExe); + printf(CRLF); +- printf(" -i input.bmp/tif/hdr Input image file name" CRLF); ++ printf(" -i input.bmp/pnm/tif/hdr Input image file name" CRLF); + printf(" bmp: <=8bpc, BGR" CRLF); ++ printf(" pnm: >=8bpc, RGB" CRLF); + printf(" tif: >=8bpc, RGB" CRLF); + printf(" hdr: 32bppRGBE only" CRLF); + printf(CRLF); diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug803743.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug803743.patch new file mode 100644 index 00000000000..d2d8e720944 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bug803743.patch @@ -0,0 +1,70 @@ +Description: libjxr-dev: Missing pkgconfig file +Author: Mathieu Malaterre +Bug-Debian: https://bugs.debian.org/803743 +Forwarded: no +Last-Update: 2021-11-26 + +Index: jxrlib/libjxr.pc.in +=================================================================== +--- jxrlib.orig/libjxr.pc.in ++++ jxrlib/libjxr.pc.in +@@ -1,4 +1,4 @@ +-prefix=%(DIR_INSTALL)s ++prefix=@DIR_INSTALL@ + exec_prefix=${prefix} + libdir=${exec_prefix}/lib + includedir=${prefix}/include +@@ -6,7 +6,7 @@ includedir=${prefix}/include + Name: libjxr + Description: A library for reading JPEG XR images. + +-Version: %(JXR_VERSION)s ++Version: @JXR_VERSION@ + Libs: -L${libdir} -ljpegxr -ljxrglue + Libs.private: -lm +-Cflags: -I${includedir}/libjxr/common -I${includedir}/libjxr/image/x86 -I${includedir}/libjxr/image -I${includedir}/libjxr/glue -I${includedir}/libjxr/test -D__ANSI__ -DDISABLE_PERF_MEASUREMENT %(JXR_ENDIAN)s ++Cflags: -I${includedir}/libjxr/common -I${includedir}/libjxr/image/x86 -I${includedir}/libjxr/image -I${includedir}/libjxr/glue -I${includedir}/libjxr/test -D__ANSI__ -DDISABLE_PERF_MEASUREMENT @JXR_ENDIAN@ +Index: jxrlib/CMakeLists.txt +=================================================================== +--- jxrlib.orig/CMakeLists.txt ++++ jxrlib/CMakeLists.txt +@@ -17,6 +17,7 @@ include(TestBigEndian) + test_big_endian(ISBIGENDIAN) + if(ISBIGENDIAN) + set(DEF_ENDIAN _BIG__ENDIAN_) ++ set(JXR_ENDIAN "-D${DEF_ENDIAN}") + endif() + + set(DIR_SYS image/sys) +@@ -73,7 +74,8 @@ set_property(TARGET jpegxr + set_property(TARGET jpegxr PROPERTY LINK_INTERFACE_LIBRARIES "") + set_property(TARGET jpegxr PROPERTY COMPILE_FLAGS -w) + # VERSION/SOVERSION +-set_property(TARGET jpegxr PROPERTY VERSION 1.1) ++set(JXR_VERSION "1.1") ++set_property(TARGET jpegxr PROPERTY VERSION ${JXR_VERSION}) + set_property(TARGET jpegxr PROPERTY SOVERSION 0) + install(TARGETS jpegxr + EXPORT JXRLibTargets +@@ -94,7 +96,7 @@ set_property(TARGET jxrglue + #set_property(TARGET jxrglue PROPERTY LINK_INTERFACE_LIBRARIES "") + set_property(TARGET jxrglue PROPERTY COMPILE_FLAGS -w) + # VERSION/SOVERSION +-set_property(TARGET jxrglue PROPERTY VERSION 1.1) ++set_property(TARGET jxrglue PROPERTY VERSION ${JXR_VERSION}) + set_property(TARGET jxrglue PROPERTY SOVERSION 0) + install(TARGETS jxrglue + EXPORT JXRLibTargets +@@ -133,3 +135,12 @@ install(FILES jxrgluelib/JXRGlue.h jxrgl + install(DIRECTORY common/include/ DESTINATION ${JXRLIB_INSTALL_INCLUDE_DIR} + FILES_MATCHING PATTERN "*.h" + ) ++ ++set(DIR_INSTALL ${CMAKE_INSTALL_PREFIX}) ++configure_file(${CMAKE_CURRENT_SOURCE_DIR}/libjxr.pc.in ++ ${CMAKE_CURRENT_BINARY_DIR}/libjxr.pc ++ @ONLY ++) ++install(FILES ${CMAKE_CURRENT_BINARY_DIR}/libjxr.pc ++ DESTINATION ${JXRLIB_INSTALL_LIB_DIR}/pkgconfig COMPONENT Header ++) diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bump_version.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bump_version.patch new file mode 100644 index 00000000000..b9e7b8d93f4 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/bump_version.patch @@ -0,0 +1,16 @@ +Description: Version is 1.2 +Author: Mathieu Malaterre +Forwarded: not-needed +Last-Update: 2021-11-26 + +--- jxrlib-1.2~git20170615.f752187.orig/CMakeLists.txt ++++ jxrlib-1.2~git20170615.f752187/CMakeLists.txt +@@ -74,7 +74,7 @@ set_property(TARGET jpegxr + set_property(TARGET jpegxr PROPERTY LINK_INTERFACE_LIBRARIES "") + set_property(TARGET jpegxr PROPERTY COMPILE_FLAGS -w) + # VERSION/SOVERSION +-set(JXR_VERSION "1.1") ++set(JXR_VERSION "1.2") + set_property(TARGET jpegxr PROPERTY VERSION ${JXR_VERSION}) + set_property(TARGET jpegxr PROPERTY SOVERSION 0) + install(TARGETS jpegxr diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/cp1251.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/cp1251.patch new file mode 100644 index 00000000000..a292730f204 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/cp1251.patch @@ -0,0 +1,207 @@ +Description: Convert some national-encoding file to utf-8 + W: libjxr-dev: national-encoding usr/include/jxrlib/wmsal.h + Steps: + % iconv -f CP1251 -t UTF-8 input.h -o input.h +Author: Mathieu Malaterre +Forwarded: not-needed +Last-Update: 2021-11-26 + +Index: jxrlib/jxrgluelib/JXRMeta.h +=================================================================== +--- jxrlib.orig/jxrgluelib/JXRMeta.h ++++ jxrlib/jxrgluelib/JXRMeta.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/jxrtestlib/JXRTest.h +=================================================================== +--- jxrlib.orig/jxrtestlib/JXRTest.h ++++ jxrlib/jxrtestlib/JXRTest.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/guiddef.h +=================================================================== +--- jxrlib.orig/common/include/guiddef.h ++++ jxrlib/common/include/guiddef.h +@@ -1,14 +1,14 @@ + //+--------------------------------------------------------------------------- + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/wmspecstring.h +=================================================================== +--- jxrlib.orig/common/include/wmspecstring.h ++++ jxrlib/common/include/wmspecstring.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/image/sys/windowsmediaphoto.h +=================================================================== +--- jxrlib.orig/image/sys/windowsmediaphoto.h ++++ jxrlib/image/sys/windowsmediaphoto.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/wmspecstrings_adt.h +=================================================================== +--- jxrlib.orig/common/include/wmspecstrings_adt.h ++++ jxrlib/common/include/wmspecstrings_adt.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/wmspecstrings_strict.h +=================================================================== +--- jxrlib.orig/common/include/wmspecstrings_strict.h ++++ jxrlib/common/include/wmspecstrings_strict.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/wmspecstrings_undef.h +=================================================================== +--- jxrlib.orig/common/include/wmspecstrings_undef.h ++++ jxrlib/common/include/wmspecstrings_undef.h +@@ -1,14 +1,14 @@ + //*@@@+++@@@@****************************************************************** + // +-// Copyright © Microsoft Corp. ++// Copyright © Microsoft Corp. + // All rights reserved. + // + // Redistribution and use in source and binary forms, with or without + // modification, are permitted provided that the following conditions are met: + // +-// • Redistributions of source code must retain the above copyright notice, ++// • Redistributions of source code must retain the above copyright notice, + // this list of conditions and the following disclaimer. +-// • Redistributions in binary form must reproduce the above copyright notice, ++// • Redistributions in binary form must reproduce the above copyright notice, + // this list of conditions and the following disclaimer in the documentation + // and/or other materials provided with the distribution. + // +Index: jxrlib/common/include/wmsal.h +=================================================================== +--- jxrlib.orig/common/include/wmsal.h ++++ jxrlib/common/include/wmsal.h +@@ -1,15 +1,15 @@ + /*** + *sal.h - markers for documenting the semantics of APIs + * +-* Copyright © Microsoft Corp. ++* Copyright © Microsoft Corp. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * +-* • Redistributions of source code must retain the above copyright notice, ++* • Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. +-* • Redistributions in binary form must reproduce the above copyright notice, ++* • Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pie.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pie.patch new file mode 100644 index 00000000000..e339161942f --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pie.patch @@ -0,0 +1,17 @@ +Description: lintian hardening-no-bindnow +Author: Mathieu Malaterre +Forwarded: not-needed +Last-Update: 2022-01-28 + +--- jxrlib-1.2~git20170615.f752187.orig/CMakeLists.txt ++++ jxrlib-1.2~git20170615.f752187/CMakeLists.txt +@@ -6,6 +6,9 @@ project(jxrlib C) + # Need shared libs for ABI + set(BUILD_SHARED_LIBS ON) + ++# PIE for executables: ++set(CMAKE_POSITION_INDEPENDENT_CODE TRUE) ++ + # helper macro to preserve original Makefile convention + macro(JXR_MAKE_OBJ SET_NAME) + foreach(src ${SRC_${SET_NAME}}) diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pkg-config.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pkg-config.patch new file mode 100644 index 00000000000..bbee01d6144 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/pkg-config.patch @@ -0,0 +1,23 @@ +Description: Incorrect path to include directory in pkg-config (libjxr.pc) + The pkg-config file for libjxr contains incorrect paths to the headers: it + refers to paths used by the upstream Makefile (sub-directories of + /usr/include/libjxr) whereas the Debian package actually installs the headers + directly into a different directory (/usr/include/jxrlib). Therefore, + packages that depend on jxrlib via the pkg-config file fail to build. + . + Original patch did not apply cleanly, rework it (malat) +Author: Yann Leprince +Reviewed-By: Mathieu Malaterre +Forwarded: no +Last-Update: 2022-01-28 + +Index: jxrlib/libjxr.pc.in +=================================================================== +--- jxrlib.orig/libjxr.pc.in ++++ jxrlib/libjxr.pc.in +@@ -9,4 +9,4 @@ Description: A library for reading JPEG + Version: @JXR_VERSION@ + Libs: -L${libdir} -ljpegxr -ljxrglue + Libs.private: -lm +-Cflags: -I${includedir}/libjxr/common -I${includedir}/libjxr/image/x86 -I${includedir}/libjxr/image -I${includedir}/libjxr/glue -I${includedir}/libjxr/test -D__ANSI__ -DDISABLE_PERF_MEASUREMENT @JXR_ENDIAN@ ++Cflags: -I${includedir}/jxrlib -D__ANSI__ -DDISABLE_PERF_MEASUREMENT @JXR_ENDIAN@ diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/remove-hardcoded-defaults.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/remove-hardcoded-defaults.patch new file mode 100644 index 00000000000..6c92902bb3d --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/remove-hardcoded-defaults.patch @@ -0,0 +1,22 @@ +Index: git/Makefile +=================================================================== +--- git.orig/Makefile ++++ git/Makefile +@@ -29,8 +29,6 @@ + ## + build: all + +-CC=cc +- + JXR_VERSION=1.1 + + DIR_SRC=$(CURDIR) +@@ -65,7 +63,7 @@ endif + + CD=cd + MK_DIR=mkdir -p +-CFLAGS=-I. -Icommon/include -I$(DIR_SYS) $(ENDIANFLAG) -D__ANSI__ -DDISABLE_PERF_MEASUREMENT -w $(PICFLAG) -O ++CFLAGS+=$(ENDIANFLAG) -D__ANSI__ -DDISABLE_PERF_MEASUREMENT -w $(PICFLAG) -O + + STATIC_LIBRARIES=$(DIR_BUILD)/libjxrglue.a $(DIR_BUILD)/libjpegxr.a + SHARED_LIBRARIES=$(DIR_BUILD)/libjxrglue.so $(DIR_BUILD)/libjpegxr.so diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/typos.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/typos.patch new file mode 100644 index 00000000000..9de45d60026 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/typos.patch @@ -0,0 +1,16 @@ +Description: Fix typos and remove some warnings +Author: Mathieu Malaterre + +Index: jxrlib/jxrencoderdecoder/JxrEncApp.c +=================================================================== +--- jxrlib.orig/jxrencoderdecoder/JxrEncApp.c ++++ jxrlib/jxrencoderdecoder/JxrEncApp.c +@@ -615,7 +615,7 @@ main(int argc, char* argv[]) + + //================================ + Call(PKCreateCodecFactory(&pCodecFactory, WMP_SDK_VERSION)); +- Call(pCodecFactory->CreateCodec(&IID_PKImageWmpEncode, &pEncoder)); ++ Call(pCodecFactory->CreateCodec(&IID_PKImageWmpEncode, (void**)&pEncoder)); + + //---------------------------------------------------------------- + Call(PKCreateTestFactory(&pTestFactory, WMP_SDK_VERSION)); diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib/usecmake.patch b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/usecmake.patch new file mode 100644 index 00000000000..36dad57f177 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib/usecmake.patch @@ -0,0 +1,144 @@ +Description: Prefer a cmake based build system +Author: Mathieu Malaterre +Forwarded: https://jxrlib.codeplex.com/discussions/440294 + +Index: jxrlib/CMakeLists.txt +=================================================================== +--- /dev/null ++++ jxrlib/CMakeLists.txt +@@ -0,0 +1,135 @@ ++# Copyright Mathieu Malaterre ++# BSD (Same as jxrlib) ++cmake_minimum_required(VERSION 3.13) ++project(jxrlib C) ++ ++# Need shared libs for ABI ++set(BUILD_SHARED_LIBS ON) ++ ++# helper macro to preserve original Makefile convention ++macro(JXR_MAKE_OBJ SET_NAME) ++ foreach(src ${SRC_${SET_NAME}}) ++ list(APPEND OBJ_${SET_NAME} ${DIR_${SET_NAME}}/${src}) ++ endforeach() ++endmacro() ++ ++include(TestBigEndian) ++test_big_endian(ISBIGENDIAN) ++if(ISBIGENDIAN) ++ set(DEF_ENDIAN _BIG__ENDIAN_) ++endif() ++ ++set(DIR_SYS image/sys) ++set(DIR_DEC image/decode) ++set(DIR_ENC image/encode) ++ ++set(DIR_GLUE jxrgluelib) ++set(DIR_TEST jxrtestlib) ++set(DIR_EXEC jxrencoderdecoder) ++ ++if(NOT JXRLIB_INSTALL_BIN_DIR) ++ set(JXRLIB_INSTALL_BIN_DIR "bin") ++endif() ++ ++if(NOT JXRLIB_INSTALL_LIB_DIR) ++ set(JXRLIB_INSTALL_LIB_DIR "lib") ++endif() ++ ++if(NOT JXRLIB_INSTALL_INCLUDE_DIR) ++ set(JXRLIB_INSTALL_INCLUDE_DIR "include/jxrlib") ++endif() ++ ++include_directories( ++ common/include ++ ${DIR_SYS} ++ ${DIR_GLUE} ++ ${DIR_TEST} ++) ++ ++# where is strlcpy ? ++include(CheckSymbolExists) ++check_symbol_exists(strlcpy "string.h" HAVE_STRLCPY) ++#set(CMAKE_REQUIRED_LIBRARIES bsd) ++#CHECK_SYMBOL_EXISTS(strlcpy "string.h" HAVE_STRLCPY4) ++# on linux, strlcpy is in -lbsd: ++#if(NOT HAVE_STRLCPY) ++# include(CheckLibraryExists) ++# find_library(BSD_LIBRARY bsd) ++# check_library_exists(bsd "strlcpy" ${BSD_LIBRARY} HAVE_STRLCPY_BSD) ++#endif() ++ ++# JPEG-XR ++set(SRC_SYS adapthuff.c image.c strcodec.c strPredQuant.c strTransform.c perfTimerANSI.c) ++JXR_MAKE_OBJ(SYS) ++set(SRC_DEC decode.c postprocess.c segdec.c strdec.c strInvTransform.c strPredQuantDec.c JXRTranscode.c) ++JXR_MAKE_OBJ(DEC) ++set(SRC_ENC encode.c segenc.c strenc.c strFwdTransform.c strPredQuantEnc.c) ++JXR_MAKE_OBJ(ENC) ++ ++add_library(jpegxr ${OBJ_ENC} ${OBJ_DEC} ${OBJ_SYS}) ++set_property(TARGET jpegxr ++ PROPERTY COMPILE_DEFINITIONS __ANSI__ DISABLE_PERF_MEASUREMENT ${DEF_ENDIAN} ++) ++set_property(TARGET jpegxr PROPERTY LINK_INTERFACE_LIBRARIES "") ++set_property(TARGET jpegxr PROPERTY COMPILE_FLAGS -w) ++# VERSION/SOVERSION ++set_property(TARGET jpegxr PROPERTY VERSION 1.1) ++set_property(TARGET jpegxr PROPERTY SOVERSION 0) ++install(TARGETS jpegxr ++ EXPORT JXRLibTargets ++ RUNTIME DESTINATION ${JXRLIB_INSTALL_BIN_DIR} COMPONENT Applications ++ LIBRARY DESTINATION ${JXRLIB_INSTALL_LIB_DIR} COMPONENT Libraries ++) ++ ++# JXR-GLUE ++set(SRC_GLUE JXRGlue.c JXRMeta.c JXRGluePFC.c JXRGlueJxr.c) ++JXR_MAKE_OBJ(GLUE) ++set(SRC_TEST JXRTest.c JXRTestBmp.c JXRTestHdr.c JXRTestPnm.c JXRTestTif.c JXRTestYUV.c) ++JXR_MAKE_OBJ(TEST) ++ ++add_library(jxrglue ${OBJ_GLUE} ${OBJ_TEST}) ++set_property(TARGET jxrglue ++ PROPERTY COMPILE_DEFINITIONS __ANSI__ DISABLE_PERF_MEASUREMENT ${DEF_ENDIAN} ++) ++#set_property(TARGET jxrglue PROPERTY LINK_INTERFACE_LIBRARIES "") ++set_property(TARGET jxrglue PROPERTY COMPILE_FLAGS -w) ++# VERSION/SOVERSION ++set_property(TARGET jxrglue PROPERTY VERSION 1.1) ++set_property(TARGET jxrglue PROPERTY SOVERSION 0) ++install(TARGETS jxrglue ++ EXPORT JXRLibTargets ++ RUNTIME DESTINATION ${JXRLIB_INSTALL_BIN_DIR} COMPONENT Applications ++ LIBRARY DESTINATION ${JXRLIB_INSTALL_LIB_DIR} COMPONENT Libraries ++) ++#if(HAVE_STRLCPY_BSD) ++# target_link_libraries(jxrglue ${BSD_LIBRARY}) ++#endif() ++#target_link_libraries(jxrglue m) ++target_link_libraries(jxrglue PRIVATE jpegxr m) ++# Enc app files ++set(ENCAPP JxrEncApp) ++add_executable(${ENCAPP} ${DIR_EXEC}/${ENCAPP}.c) ++set_property(TARGET ${ENCAPP} ++ PROPERTY COMPILE_DEFINITIONS __ANSI__ DISABLE_PERF_MEASUREMENT ${DEF_ENDIAN} ++) ++#set_property(TARGET ${ENCAPP} PROPERTY COMPILE_FLAGS -w) ++target_link_libraries(${ENCAPP} jxrglue) # jpegxr) ++install(TARGETS ${ENCAPP} RUNTIME DESTINATION ${JXRLIB_INSTALL_BIN_DIR}) ++# Dec app files ++set(DECAPP JxrDecApp) ++add_executable(${DECAPP} ${DIR_EXEC}/${DECAPP}.c) ++set_property(TARGET ${DECAPP} ++ PROPERTY COMPILE_DEFINITIONS __ANSI__ DISABLE_PERF_MEASUREMENT ${DEF_ENDIAN} ++) ++set_property(TARGET ${DECAPP} PROPERTY COMPILE_FLAGS -w) ++target_link_libraries(${DECAPP} jxrglue) # jpegxr) ++install(TARGETS ${DECAPP} RUNTIME DESTINATION ${JXRLIB_INSTALL_BIN_DIR}) ++ ++# install rules ++install(FILES jxrgluelib/JXRGlue.h jxrgluelib/JXRMeta.h jxrtestlib/JXRTest.h ++ image/sys/windowsmediaphoto.h ++ DESTINATION ${JXRLIB_INSTALL_INCLUDE_DIR} COMPONENT Headers ++) ++install(DIRECTORY common/include/ DESTINATION ${JXRLIB_INSTALL_INCLUDE_DIR} ++ FILES_MATCHING PATTERN "*.h" ++) diff --git a/meta-ros-common/recipes-graphics/jxrlib/jxrlib_1.2.bb b/meta-ros-common/recipes-graphics/jxrlib/jxrlib_1.2.bb new file mode 100644 index 00000000000..05056dbab33 --- /dev/null +++ b/meta-ros-common/recipes-graphics/jxrlib/jxrlib_1.2.bb @@ -0,0 +1,29 @@ +LICENSE = "BSD-2-Clause" +LIC_FILES_CHKSUM = "file://LICENSE;md5=ea034eb982f97aff03a4704f608ed2b4" + +SRC_URI = " \ + git://salsa.debian.org/debian-phototools-team/jxrlib.git;protocol=https;branch=master \ + file://usecmake.patch \ + file://typos.patch \ + file://cp1251.patch \ + file://bug771912.patch \ + file://bug803743.patch \ + file://bump_version.patch \ + file://pkg-config.patch \ + file://pie.patch \ + file://082bb032be1f6c75173bf603252e4f37bfded9fa.patch \ + file://31df7f88539b77d46ebf408b6a215930ae63bbdd.patch \ + file://a684f95783f2f81bd13bf1f8b03ceb12aa87d661.patch \ + file://ab9c6b78b7ad3205bdb91ef725b09ddbe3c8945d.patch \ + file://remove-hardcoded-defaults.patch \ +" + +# Modify these as desired +PV = "1.2+git${SRCPV}" +SRCREV = "1b84578fa80eae689c2677970cda64f53953880b" + +S = "${WORKDIR}/git" + +inherit cmake + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-graphics/netpbm/netpbm_11.06.01-2.bb b/meta-ros-common/recipes-graphics/netpbm/netpbm_11.06.01-2.bb new file mode 100644 index 00000000000..fc18b6c45a6 --- /dev/null +++ b/meta-ros-common/recipes-graphics/netpbm/netpbm_11.06.01-2.bb @@ -0,0 +1,70 @@ +# Recipe created by recipetool +# This is the basis of a recipe and may need further editing in order to be fully functional. +# (Feel free to remove these comments when editing.) + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +# +# The following license files were not able to be identified and are +# represented as "Unknown" below, you will need to check them yourself: +# converter/other/cameratopam/COPYRIGHT +# converter/other/pnmtopalm/LICENSE +# converter/pbm/pbmtoppa/LICENSE +# converter/ppm/ppmtompeg/COPYRIGHT +# debian/copyright +# doc/COPYRIGHT.PATENT +# doc/GPL_LICENSE.txt +# doc/copyright_summary +# lib/util/LICENSE.txt +# other/pamx/COPYRIGHT +# +# NOTE: multiple licenses have been detected; they have been separated with & +# in the LICENSE value for now since it is a reasonable assumption that all +# of the licenses apply. If instead there is a choice between the multiple +# licenses then you should change the value to separate the licenses with | +# instead of &. If there is any doubt, check the accompanying documentation +# to determine which situation is applicable. +LICENSE = "GPL-2.0-only & Unknown" +LIC_FILES_CHKSUM = "file://converter/other/cameratopam/COPYRIGHT;md5=b599b5fdcb221af54d1ae96023826a79 \ + file://converter/other/jbig/libjbig/COPYING;md5=8ca43cbc842c2336e835926c2166c28b \ + file://converter/other/pnmtopalm/LICENSE;md5=6d644cf37a0fd379433b17c0fefc4c32 \ + file://converter/pbm/pbmtoppa/LICENSE;md5=e6d8a8731b55aec86c981b6474ff0888 \ + file://converter/ppm/ppmtompeg/COPYRIGHT;md5=524ff2e7d68c9b2b9be44fa6dc43b6a9 \ + file://debian/copyright;md5=a24beed3902a60139f7b19bba9f25017 \ + file://doc/COPYRIGHT.PATENT;md5=34528ea0c5550dc4920c69ccc66ea270 \ + file://doc/GPL_LICENSE.txt;md5=079b27cd65c86dbc1b6997ffde902735 \ + file://doc/copyright_summary;md5=6bb45eba960ba79396647dd8925de8b6 \ + file://lib/util/LICENSE.txt;md5=e1f509120273e76ee43e03137569b11e \ + file://other/pamx/COPYRIGHT;md5=70075b407c887a3c57e794e2dbffeb1b" + +SRC_URI = "git://salsa.debian.org/debian-phototools-team/netpbm.git;protocol=https;branch=master" + +# Modify these as desired +PV = "11.06.01-2+git" +SRCREV = "c3658694ae3179142edc504497a36f8f3d62aa28" + +S = "${WORKDIR}/git" + +# NOTE: some of these dependencies may be optional, check the Makefile and/or upstream documentation +DEPENDS = "flex-native libx11" + +# NOTE: this is a Makefile-only piece of software, so we cannot generate much of the +# recipe automatically - you will need to examine the Makefile yourself and ensure +# that the appropriate arguments are passed in. + +do_configure () { + # Specify any needed configure commands here + : +} + +do_compile () { + # You will almost certainly need to add additional arguments here + oe_runmake +} + +do_install () { + # NOTE: unable to determine what to put here - there is a Makefile but no + # target named "install", so you will need to define this yourself + : +} + diff --git a/meta-ros-common/recipes-graphics/openexr/openexr_3.2.1.bb b/meta-ros-common/recipes-graphics/openexr/openexr_3.2.1.bb new file mode 100644 index 00000000000..a6d738eed47 --- /dev/null +++ b/meta-ros-common/recipes-graphics/openexr/openexr_3.2.1.bb @@ -0,0 +1,20 @@ +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM = "file://LICENSE.md;md5=b0f98dc4bafd54ae93bbd833040c68a3" + +SRC_URI = "git://github.com/AcademySoftwareFoundation/openexr.git;protocol=https;branch=main" + +PV = "3.2.1+git${SRCPV}" +SRCREV = "6258740337bf3859ed8abcf8d99a1671b2cdd06d" + +S = "${WORKDIR}/git" + +DEPENDS += " \ + doxygen \ + libdeflate \ + imath \ + clang-native \ +" + +inherit cmake python3-dir python3native pkgconfig + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-Apply-1-suggestion-s-to-1-file-s.patch b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-Apply-1-suggestion-s-to-1-file-s.patch new file mode 100644 index 00000000000..5d15dff1d9b --- /dev/null +++ b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-Apply-1-suggestion-s-to-1-file-s.patch @@ -0,0 +1,27 @@ +From e1640519208121f916da1772a5efb6ca28971b86 Mon Sep 17 00:00:00 2001 +From: Even Rouault +Date: Tue, 31 Oct 2023 15:04:37 +0000 +Subject: [PATCH 3/3] Apply 1 suggestion(s) to 1 file(s) + +CVE: CVE-2023-6277 +Upstream-Status: Backport [https://gitlab.com/libtiff/libtiff/-/merge_requests/545] +Signed-off-by: Khem Raj +--- + libtiff/tif_dirread.c | 1 - + 1 file changed, 1 deletion(-) + +diff --git a/libtiff/tif_dirread.c b/libtiff/tif_dirread.c +index fe8d6f8..58a4276 100644 +--- a/libtiff/tif_dirread.c ++++ b/libtiff/tif_dirread.c +@@ -5306,7 +5306,6 @@ static int EstimateStripByteCounts(TIFF *tif, TIFFDirEntry *dir, + { + uint64_t space; + uint16_t n; +- filesize = TIFFGetFileSize(tif); + if (!(tif->tif_flags & TIFF_BIGTIFF)) + space = sizeof(TIFFHeaderClassic) + 2 + dircount * 12 + 4; + else +-- +2.43.0 + diff --git a/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data-2.patch b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data-2.patch new file mode 100644 index 00000000000..9fc8182fef3 --- /dev/null +++ b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data-2.patch @@ -0,0 +1,36 @@ +From f500facf7723f1cae725dd288b2daad15e45131c Mon Sep 17 00:00:00 2001 +From: Su_Laus +Date: Mon, 30 Oct 2023 21:21:57 +0100 +Subject: [PATCH 2/3] At image reading, compare data size of some tags / data + structures (StripByteCounts, StripOffsets, StripArray, TIFF directory) with + file size to prevent provoked out-of-memory attacks. +MIME-Version: 1.0 +Content-Type: text/plain; charset=UTF-8 +Content-Transfer-Encoding: 8bit + +See issue #614. + +Correct declaration of ‘filesize’ shadows a previous local. + +CVE: CVE-2023-6277 +Upstream-Status: Backport [https://gitlab.com/libtiff/libtiff/-/merge_requests/545] +Signed-off-by: Khem Raj +--- + libtiff/tif_dirread.c | 1 - + 1 file changed, 1 deletion(-) + +diff --git a/libtiff/tif_dirread.c b/libtiff/tif_dirread.c +index c52d41f..fe8d6f8 100644 +--- a/libtiff/tif_dirread.c ++++ b/libtiff/tif_dirread.c +@@ -5305,7 +5305,6 @@ static int EstimateStripByteCounts(TIFF *tif, TIFFDirEntry *dir, + if (td->td_compression != COMPRESSION_NONE) + { + uint64_t space; +- uint64_t filesize; + uint16_t n; + filesize = TIFFGetFileSize(tif); + if (!(tif->tif_flags & TIFF_BIGTIFF)) +-- +2.43.0 + diff --git a/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data.patch b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data.patch new file mode 100644 index 00000000000..d5854a9059b --- /dev/null +++ b/meta-ros-common/recipes-multimedia/libtiff/tiff/CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data.patch @@ -0,0 +1,162 @@ +From b33baa5d9c6aac8ce49b5180dd48e39697ab7a11 Mon Sep 17 00:00:00 2001 +From: Su_Laus +Date: Fri, 27 Oct 2023 22:11:10 +0200 +Subject: [PATCH 1/3] At image reading, compare data size of some tags / data + structures (StripByteCounts, StripOffsets, StripArray, TIFF directory) with + file size to prevent provoked out-of-memory attacks. + +See issue #614. + +CVE: CVE-2023-6277 +Upstream-Status: Backport [https://gitlab.com/libtiff/libtiff/-/merge_requests/545] +Signed-off-by: Khem Raj +--- + libtiff/tif_dirread.c | 90 +++++++++++++++++++++++++++++++++++++++++++ + 1 file changed, 90 insertions(+) + +diff --git a/libtiff/tif_dirread.c b/libtiff/tif_dirread.c +index 2c49dc6..c52d41f 100644 +--- a/libtiff/tif_dirread.c ++++ b/libtiff/tif_dirread.c +@@ -1308,6 +1308,21 @@ TIFFReadDirEntryArrayWithLimit(TIFF *tif, TIFFDirEntry *direntry, + datasize = (*count) * typesize; + assert((tmsize_t)datasize > 0); + ++ /* Before allocating a huge amount of memory for corrupted files, check if ++ * size of requested memory is not greater than file size. ++ */ ++ uint64_t filesize = TIFFGetFileSize(tif); ++ if (datasize > filesize) ++ { ++ TIFFWarningExtR(tif, "ReadDirEntryArray", ++ "Requested memory size for tag %d (0x%x) %" PRIu32 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated, tag not read", ++ direntry->tdir_tag, direntry->tdir_tag, datasize, ++ filesize); ++ return (TIFFReadDirEntryErrAlloc); ++ } ++ + if (isMapped(tif) && datasize > (uint64_t)tif->tif_size) + return TIFFReadDirEntryErrIo; + +@@ -5266,6 +5281,20 @@ static int EstimateStripByteCounts(TIFF *tif, TIFFDirEntry *dir, + if (!_TIFFFillStrilesInternal(tif, 0)) + return -1; + ++ /* Before allocating a huge amount of memory for corrupted files, check if ++ * size of requested memory is not greater than file size. */ ++ uint64_t filesize = TIFFGetFileSize(tif); ++ uint64_t allocsize = (uint64_t)td->td_nstrips * sizeof(uint64_t); ++ if (allocsize > filesize) ++ { ++ TIFFWarningExtR(tif, module, ++ "Requested memory size for StripByteCounts of %" PRIu64 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated", ++ allocsize, filesize); ++ return -1; ++ } ++ + if (td->td_stripbytecount_p) + _TIFFfreeExt(tif, td->td_stripbytecount_p); + td->td_stripbytecount_p = (uint64_t *)_TIFFCheckMalloc( +@@ -5807,6 +5836,20 @@ static uint16_t TIFFFetchDirectory(TIFF *tif, uint64_t diroff, + dircount16 = (uint16_t)dircount64; + dirsize = 20; + } ++ /* Before allocating a huge amount of memory for corrupted files, check ++ * if size of requested memory is not greater than file size. */ ++ uint64_t filesize = TIFFGetFileSize(tif); ++ uint64_t allocsize = (uint64_t)dircount16 * dirsize; ++ if (allocsize > filesize) ++ { ++ TIFFWarningExtR( ++ tif, module, ++ "Requested memory size for TIFF directory of %" PRIu64 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated, TIFF directory not read", ++ allocsize, filesize); ++ return 0; ++ } + origdir = _TIFFCheckMalloc(tif, dircount16, dirsize, + "to read TIFF directory"); + if (origdir == NULL) +@@ -5921,6 +5964,20 @@ static uint16_t TIFFFetchDirectory(TIFF *tif, uint64_t diroff, + "directories not supported"); + return 0; + } ++ /* Before allocating a huge amount of memory for corrupted files, check ++ * if size of requested memory is not greater than file size. */ ++ uint64_t filesize = TIFFGetFileSize(tif); ++ uint64_t allocsize = (uint64_t)dircount16 * dirsize; ++ if (allocsize > filesize) ++ { ++ TIFFWarningExtR( ++ tif, module, ++ "Requested memory size for TIFF directory of %" PRIu64 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated, TIFF directory not read", ++ allocsize, filesize); ++ return 0; ++ } + origdir = _TIFFCheckMalloc(tif, dircount16, dirsize, + "to read TIFF directory"); + if (origdir == NULL) +@@ -5968,6 +6025,8 @@ static uint16_t TIFFFetchDirectory(TIFF *tif, uint64_t diroff, + } + } + } ++ /* No check against filesize needed here because "dir" should have same size ++ * than "origdir" checked above. */ + dir = (TIFFDirEntry *)_TIFFCheckMalloc( + tif, dircount16, sizeof(TIFFDirEntry), "to read TIFF directory"); + if (dir == 0) +@@ -7164,6 +7223,20 @@ static int TIFFFetchStripThing(TIFF *tif, TIFFDirEntry *dir, uint32_t nstrips, + return (0); + } + ++ /* Before allocating a huge amount of memory for corrupted files, check ++ * if size of requested memory is not greater than file size. */ ++ uint64_t filesize = TIFFGetFileSize(tif); ++ uint64_t allocsize = (uint64_t)nstrips * sizeof(uint64_t); ++ if (allocsize > filesize) ++ { ++ TIFFWarningExtR(tif, module, ++ "Requested memory size for StripArray of %" PRIu64 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated", ++ allocsize, filesize); ++ _TIFFfreeExt(tif, data); ++ return (0); ++ } + resizeddata = (uint64_t *)_TIFFCheckMalloc( + tif, nstrips, sizeof(uint64_t), "for strip array"); + if (resizeddata == 0) +@@ -7263,6 +7336,23 @@ static void allocChoppedUpStripArrays(TIFF *tif, uint32_t nstrips, + } + bytecount = last_offset + last_bytecount - offset; + ++ /* Before allocating a huge amount of memory for corrupted files, check if ++ * size of StripByteCount and StripOffset tags is not greater than ++ * file size. ++ */ ++ uint64_t allocsize = (uint64_t)nstrips * sizeof(uint64_t) * 2; ++ uint64_t filesize = TIFFGetFileSize(tif); ++ if (allocsize > filesize) ++ { ++ TIFFWarningExtR(tif, "allocChoppedUpStripArrays", ++ "Requested memory size for StripByteCount and " ++ "StripOffsets %" PRIu64 ++ " is greather than filesize %" PRIu64 ++ ". Memory not allocated", ++ allocsize, filesize); ++ return; ++ } ++ + newcounts = + (uint64_t *)_TIFFCheckMalloc(tif, nstrips, sizeof(uint64_t), + "for chopped \"StripByteCounts\" array"); +-- +2.43.0 + diff --git a/meta-ros-common/recipes-multimedia/libtiff/tiff/public-functions-tifffieldsetget.patch b/meta-ros-common/recipes-multimedia/libtiff/tiff/public-functions-tifffieldsetget.patch new file mode 100644 index 00000000000..de1ab238e46 --- /dev/null +++ b/meta-ros-common/recipes-multimedia/libtiff/tiff/public-functions-tifffieldsetget.patch @@ -0,0 +1,243 @@ +From 11f3f279608ae9e68f014717393197f430f9be58 Mon Sep 17 00:00:00 2001 +From: Su Laus +Date: Sat, 14 May 2022 19:32:11 +0000 +Subject: [PATCH] Public functions TIFFFieldSetGetSize() and + TIFFieldSetGetCountSize() added. + +--- + libtiff/libtiff.def | 2 + + libtiff/tif_dir.c | 7 +-- + libtiff/tif_dirinfo.c | 109 +++++++++++++++++++++++------------------ + libtiff/tif_dirwrite.c | 4 +- + libtiff/tif_print.c | 4 +- + libtiff/tiffio.h | 4 +- + libtiff/tiffiop.h | 4 -- + 7 files changed, 73 insertions(+), 61 deletions(-) + +Index: tiff-4.3.0/libtiff/libtiff.def +=================================================================== +--- tiff-4.3.0.orig/libtiff/libtiff.def ++++ tiff-4.3.0/libtiff/libtiff.def +@@ -33,6 +33,8 @@ EXPORTS TIFFAccessTagMethods + TIFFFieldWithName + TIFFFieldWithTag + TIFFFieldWriteCount ++ TIFFFieldSetGetSize ++ TIFFFieldSetGetCountSize + TIFFFileName + TIFFFileno + TIFFFindCODEC +Index: tiff-4.3.0/libtiff/tif_dir.c +=================================================================== +--- tiff-4.3.0.orig/libtiff/tif_dir.c ++++ tiff-4.3.0/libtiff/tif_dir.c +@@ -605,11 +605,8 @@ _TIFFVSetField(TIFF* tif, uint32_t tag, + /* + * Set custom value ... save a copy of the custom tag value. + */ +- tv_size = _TIFFDataSize(fip->field_type); + /*--: Rational2Double: For Rationals evaluate "set_field_type" to determine internal storage size. */ +- if (fip->field_type == TIFF_RATIONAL || fip->field_type == TIFF_SRATIONAL) { +- tv_size = _TIFFSetGetFieldSize(fip->set_field_type); +- } ++ tv_size = TIFFFieldSetGetSize(fip); + if (tv_size == 0) { + status = 0; + TIFFErrorExt(tif->tif_clientdata, module, +@@ -1245,7 +1242,7 @@ _TIFFVGetField(TIFF* tif, uint32_t tag, + case TIFF_SRATIONAL: + { + /*-- Rational2Double: For Rationals evaluate "set_field_type" to determine internal storage size and return value size. */ +- int tv_size = _TIFFSetGetFieldSize(fip->set_field_type); ++ int tv_size = TIFFFieldSetGetSize(fip); + if (tv_size == 8) { + *va_arg(ap, double*) = *(double *)val; + ret_val = 1; +Index: tiff-4.3.0/libtiff/tif_dirinfo.c +=================================================================== +--- tiff-4.3.0.orig/libtiff/tif_dirinfo.c ++++ tiff-4.3.0/libtiff/tif_dirinfo.c +@@ -563,55 +563,28 @@ TIFFDataWidth(TIFFDataType type) + } + } + +-/* +- * Return size of TIFFDataType in bytes. +- * +- * XXX: We need a separate function to determine the space needed +- * to store the value. For TIFF_RATIONAL values TIFFDataWidth() returns 8, +- * but we use 4-byte float to represent rationals. ++/* ++ * Return internal storage size of TIFFSetGetFieldType in bytes. ++ * TIFFSetField() and TIFFGetField() have to provide the parameter accordingly. ++ * Replaces internal functions _TIFFDataSize() and _TIFFSetGetFieldSize() ++ * with now extern available function TIFFFieldSetGetSize(). + */ +-int +-_TIFFDataSize(TIFFDataType type) ++int ++TIFFFieldSetGetSize(const TIFFField* fip) + { +- switch (type) +- { +- case TIFF_BYTE: +- case TIFF_SBYTE: +- case TIFF_ASCII: +- case TIFF_UNDEFINED: +- return 1; +- case TIFF_SHORT: +- case TIFF_SSHORT: +- return 2; +- case TIFF_LONG: +- case TIFF_SLONG: +- case TIFF_FLOAT: +- case TIFF_IFD: +- case TIFF_RATIONAL: +- case TIFF_SRATIONAL: +- return 4; +- case TIFF_DOUBLE: +- case TIFF_LONG8: +- case TIFF_SLONG8: +- case TIFF_IFD8: +- return 8; +- default: +- return 0; +- } +-} +- + /* +- * Rational2Double: +- * Return size of TIFFSetGetFieldType in bytes. +- * +- * XXX: TIFF_RATIONAL values for FIELD_CUSTOM are stored internally as 4-byte float. +- * However, some of them should be stored internally as 8-byte double. +- * This is now managed by the SetGetField of the tag-definition! +- */ +-int +-_TIFFSetGetFieldSize(TIFFSetGetFieldType setgettype) +-{ +- switch (setgettype) ++ * TIFFSetField() and TIFFGetField() must provide the parameter accordingly to ++ * the definition of "set_field_type" of the tag definition in dir_info.c. ++ * This function returns the data size for that purpose. ++ * ++ * Furthermore, this data size is also used for the internal storage, ++ * even for TIFF_RATIONAL values for FIELD_CUSTOM, which are stored internally as 4-byte float, ++ * but some of them should be stored internally as 8-byte double, ++ * depending on the "set_field_type" _FLOAT_ or _DOUBLE_. ++*/ ++ if (fip == NULL) return 0; ++ ++ switch (fip->set_field_type) + { + case TIFF_SETGET_UNDEFINED: + case TIFF_SETGET_ASCII: +@@ -673,7 +646,48 @@ _TIFFSetGetFieldSize(TIFFSetGetFieldType + default: + return 0; + } +-} /*-- _TIFFSetGetFieldSize --- */ ++} /*-- TIFFFieldSetGetSize() --- */ ++ ++/* ++ * Return size of count parameter of TIFFSetField() and TIFFGetField() ++ * and also if it is required: 0=none, 2=uint16_t, 4=uint32_t ++ */ ++int ++TIFFFieldSetGetCountSize(const TIFFField* fip) ++{ ++ if (fip == NULL) return 0; ++ ++ switch (fip->set_field_type) { ++ case TIFF_SETGET_C16_ASCII: ++ case TIFF_SETGET_C16_UINT8: ++ case TIFF_SETGET_C16_SINT8: ++ case TIFF_SETGET_C16_UINT16: ++ case TIFF_SETGET_C16_SINT16: ++ case TIFF_SETGET_C16_UINT32: ++ case TIFF_SETGET_C16_SINT32: ++ case TIFF_SETGET_C16_FLOAT: ++ case TIFF_SETGET_C16_UINT64: ++ case TIFF_SETGET_C16_SINT64: ++ case TIFF_SETGET_C16_DOUBLE: ++ case TIFF_SETGET_C16_IFD8: ++ return 2; ++ case TIFF_SETGET_C32_ASCII: ++ case TIFF_SETGET_C32_UINT8: ++ case TIFF_SETGET_C32_SINT8: ++ case TIFF_SETGET_C32_UINT16: ++ case TIFF_SETGET_C32_SINT16: ++ case TIFF_SETGET_C32_UINT32: ++ case TIFF_SETGET_C32_SINT32: ++ case TIFF_SETGET_C32_FLOAT: ++ case TIFF_SETGET_C32_UINT64: ++ case TIFF_SETGET_C32_SINT64: ++ case TIFF_SETGET_C32_DOUBLE: ++ case TIFF_SETGET_C32_IFD8: ++ return 4; ++ default: ++ return 0; ++ } ++} /*-- TIFFFieldSetGetCountSize() --- */ + + + const TIFFField* +Index: tiff-4.3.0/libtiff/tif_dirwrite.c +=================================================================== +--- tiff-4.3.0.orig/libtiff/tif_dirwrite.c ++++ tiff-4.3.0/libtiff/tif_dirwrite.c +@@ -819,7 +819,7 @@ TIFFWriteDirectorySec(TIFF* tif, int isi + { + /*-- Rational2Double: For Rationals evaluate "set_field_type" to determine internal storage size. */ + int tv_size; +- tv_size = _TIFFSetGetFieldSize(tif->tif_dir.td_customValues[m].info->set_field_type); ++ tv_size = TIFFFieldSetGetSize(tif->tif_dir.td_customValues[m].info); + if (tv_size == 8) { + if (!TIFFWriteDirectoryTagRationalDoubleArray(tif,&ndir,dir,tag,count,tif->tif_dir.td_customValues[m].value)) + goto bad; +@@ -838,7 +838,7 @@ TIFFWriteDirectorySec(TIFF* tif, int isi + { + /*-- Rational2Double: For Rationals evaluate "set_field_type" to determine internal storage size. */ + int tv_size; +- tv_size = _TIFFSetGetFieldSize(tif->tif_dir.td_customValues[m].info->set_field_type); ++ tv_size = TIFFFieldSetGetSize(tif->tif_dir.td_customValues[m].info); + if (tv_size == 8) { + if (!TIFFWriteDirectoryTagSrationalDoubleArray(tif,&ndir,dir,tag,count,tif->tif_dir.td_customValues[m].value)) + goto bad; +Index: tiff-4.3.0/libtiff/tiffio.h +=================================================================== +--- tiff-4.3.0.orig/libtiff/tiffio.h ++++ tiff-4.3.0/libtiff/tiffio.h +@@ -328,6 +328,8 @@ extern TIFFDataType TIFFFieldDataType(co + extern int TIFFFieldPassCount(const TIFFField*); + extern int TIFFFieldReadCount(const TIFFField*); + extern int TIFFFieldWriteCount(const TIFFField*); ++extern int TIFFFieldSetGetSize(const TIFFField*); /* returns internal storage size of TIFFSetGetFieldType in bytes. */ ++extern int TIFFFieldSetGetCountSize(const TIFFField*); /* returns size of count parameter 0=none, 2=uint16_t, 4=uint32_t */ + + typedef int (*TIFFVSetMethod)(TIFF*, uint32_t, va_list); + typedef int (*TIFFVGetMethod)(TIFF*, uint32_t, va_list); +@@ -483,7 +485,7 @@ extern tmsize_t TIFFWriteEncodedStrip(TI + extern tmsize_t TIFFWriteRawStrip(TIFF* tif, uint32_t strip, void* data, tmsize_t cc); + extern tmsize_t TIFFWriteEncodedTile(TIFF* tif, uint32_t tile, void* data, tmsize_t cc); + extern tmsize_t TIFFWriteRawTile(TIFF* tif, uint32_t tile, void* data, tmsize_t cc); +-extern int TIFFDataWidth(TIFFDataType); /* table of tag datatype widths */ ++extern int TIFFDataWidth(TIFFDataType); /* table of tag datatype widths within TIFF file. */ + extern void TIFFSetWriteOffset(TIFF* tif, toff_t off); + extern void TIFFSwabShort(uint16_t*); + extern void TIFFSwabLong(uint32_t*); +Index: tiff-4.3.0/libtiff/tiffiop.h +=================================================================== +--- tiff-4.3.0.orig/libtiff/tiffiop.h ++++ tiff-4.3.0/libtiff/tiffiop.h +@@ -337,10 +337,6 @@ extern int TIFFSetCompressionScheme(TIFF + extern int TIFFSetDefaultCompressionState(TIFF* tif); + extern uint32_t _TIFFDefaultStripSize(TIFF* tif, uint32_t s); + extern void _TIFFDefaultTileSize(TIFF* tif, uint32_t* tw, uint32_t* th); +-extern int _TIFFDataSize(TIFFDataType type); +- +-/*--: Rational2Double: Return size of TIFFSetGetFieldType in bytes. */ +-extern int _TIFFSetGetFieldSize(TIFFSetGetFieldType setgettype); + + extern void _TIFFsetByteArray(void**, void*, uint32_t); + extern void _TIFFsetString(char**, char*); diff --git a/meta-ros-common/recipes-multimedia/libtiff/tiff_4.6.0.bb b/meta-ros-common/recipes-multimedia/libtiff/tiff_4.6.0.bb new file mode 100644 index 00000000000..4c472f8ef6f --- /dev/null +++ b/meta-ros-common/recipes-multimedia/libtiff/tiff_4.6.0.bb @@ -0,0 +1,63 @@ +SUMMARY = "Provides support for the Tag Image File Format (TIFF)" +DESCRIPTION = "Library provides support for the Tag Image File Format \ +(TIFF), a widely used format for storing image data. This library \ +provide means to easily access and create TIFF image files." +HOMEPAGE = "http://www.libtiff.org/" +LICENSE = "BSD-2-Clause" +LIC_FILES_CHKSUM = "file://LICENSE.md;md5=a3e32d664d6db1386b4689c8121531c3" + +CVE_PRODUCT = "libtiff" + +SRC_URI = "http://download.osgeo.org/libtiff/tiff-${PV}.tar.gz \ + file://CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data.patch \ + file://CVE-2023-6277-At-image-reading-compare-data-size-of-some-tags-data-2.patch \ + file://CVE-2023-6277-Apply-1-suggestion-s-to-1-file-s.patch \ + " + +SRC_URI[sha256sum] = "88b3979e6d5c7e32b50d7ec72fb15af724f6ab2cbf7e10880c360a77e4b5d99a" + +# exclude betas +UPSTREAM_CHECK_REGEX = "tiff-(?P\d+(\.\d+)+).tar" + +CVE_STATUS[CVE-2015-7313] = "fixed-version: Tested with check from https://security-tracker.debian.org/tracker/CVE-2015-7313 and already 4.3.0 doesn't have the issue" + +inherit autotools multilib_header + +CACHED_CONFIGUREVARS = "ax_cv_check_gl_libgl=no" + +PACKAGECONFIG ?= "cxx jpeg zlib lzma \ + strip-chopping extrasample-as-alpha check-ycbcr-subsampling" + +PACKAGECONFIG[cxx] = "--enable-cxx,--disable-cxx,," +PACKAGECONFIG[jbig] = "--enable-jbig,--disable-jbig,jbig," +PACKAGECONFIG[jpeg] = "--enable-jpeg,--disable-jpeg,jpeg," +PACKAGECONFIG[zlib] = "--enable-zlib,--disable-zlib,zlib," +PACKAGECONFIG[lzma] = "--enable-lzma,--disable-lzma,xz," +PACKAGECONFIG[webp] = "--enable-webp,--disable-webp,libwebp," +PACKAGECONFIG[zstd] = "--enable-zstd,--disable-zstd,zstd," +PACKAGECONFIG[libdeflate] = "--enable-libdeflate,--disable-libdeflate,libdeflate," + +# Convert single-strip uncompressed images to multiple strips of specified +# size (default: 8192) to reduce memory usage +PACKAGECONFIG[strip-chopping] = "--enable-strip-chopping,--disable-strip-chopping,," + +# Treat a fourth sample with no EXTRASAMPLE_ value as being ASSOCALPHA +PACKAGECONFIG[extrasample-as-alpha] = "--enable-extrasample-as-alpha,--disable-extrasample-as-alpha,," + +# Control picking up YCbCr subsample info. Disable to support files lacking +# the tag +PACKAGECONFIG[check-ycbcr-subsampling] = "--enable-check-ycbcr-subsampling,--disable-check-ycbcr-subsampling,," + +# Support a mechanism allowing reading large strips (usually one strip files) +# in chunks when using TIFFReadScanline. Experimental 4.0+ feature +PACKAGECONFIG[chunky-strip-read] = "--enable-chunky-strip-read,--disable-chunky-strip-read,," + +PACKAGES =+ "tiffxx tiff-utils" +FILES:tiffxx = "${libdir}/libtiffxx.so.*" +FILES:tiff-utils = "${bindir}/*" + +do_install:append() { + oe_multilib_header tiffconf.h +} + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-fixing-install-location-of-cmake-conf.patch b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-fixing-install-location-of-cmake-conf.patch new file mode 100644 index 00000000000..0b06dbef194 --- /dev/null +++ b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-fixing-install-location-of-cmake-conf.patch @@ -0,0 +1,38 @@ +From f5608ce9238b79a4dfa777315c29f06a797925f2 Mon Sep 17 00:00:00 2001 +From: Matthias Schoepfer +Date: Thu, 11 Apr 2024 12:36:20 +0200 +Subject: [PATCH] CMakeLists.txt: fixing install location of cmake config files + +Fixing the install location of CMake config files to a more common +location. See CMakePackageConfigHelpers "Example Generating Package Files" +in the CMake documentation where the files are installed in this location: + +Upstream-Status: Submitted [https://github.com/orocos/orocos_kinematics_dynamics/pull/460] + +Signed-off-by: Matthias Schoepfer +--- + CMakeLists.txt | 8 ++++---- + 1 file changed, 4 insertions(+), 4 deletions(-) + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index f9d37e0..b070d10 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -118,10 +118,10 @@ CONFIGURE_FILE(orocos_kdl-config.cmake.in + CONFIGURE_FILE(orocos_kdl-config-version.cmake.in + ${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake @ONLY) + +-INSTALL(FILES cmake/FindEigen3.cmake DESTINATION share/orocos_kdl/cmake) +-INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake DESTINATION share/orocos_kdl/cmake) +-INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake DESTINATION share/orocos_kdl/cmake) +-INSTALL(EXPORT OrocosKDLTargets DESTINATION share/orocos_kdl/cmake) ++INSTALL(FILES cmake/FindEigen3.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl) ++INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl) ++INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl) ++INSTALL(EXPORT OrocosKDLTargets DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl) + + # Generate pkg-config package configuration + CONFIGURE_FILE(orocos_kdl.pc.in ${CMAKE_CURRENT_BINARY_DIR}/orocos-kdl.pc @ONLY) +-- +2.43.2 + diff --git a/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-resolving-host-path-injection-in-.pc-.patch b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-resolving-host-path-injection-in-.pc-.patch new file mode 100644 index 00000000000..ec3ef75477c --- /dev/null +++ b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl/0001-CMakeLists.txt-resolving-host-path-injection-in-.pc-.patch @@ -0,0 +1,31 @@ +From e8fec8686cb25be9f037cb6073da0a6c722f995b Mon Sep 17 00:00:00 2001 +From: Matthias Schoepfer +Date: Thu, 11 Apr 2024 12:54:00 +0200 +Subject: [PATCH] CMakeLists.txt: resolving host path injection in .pc file + +Removing the addition of eigen include path into the pc file, which +will cause a TMPDIR leakage. + +Upstream-Status: inappropriate [embedded specific] + +Signed-off-by: Matthias Schoepfer +--- + CMakeLists.txt | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index b070d10..f8fc347 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -54,7 +54,7 @@ if(NOT EIGEN3_FOUND) + include(${PROJ_SOURCE_DIR}/cmake/FindEigen3.cmake) + endif() + include_directories(${EIGEN3_INCLUDE_DIR}) +-SET(KDL_CFLAGS "${KDL_CFLAGS} -I\"${EIGEN3_INCLUDE_DIR}\"") ++SET(KDL_CFLAGS "${KDL_CFLAGS}") + + # Check the platform STL containers capabilities + include(cmake/CheckSTLContainers.cmake) +-- +2.43.2 + diff --git a/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl_1.5.1-87.bb b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl_1.5.1-87.bb new file mode 100644 index 00000000000..755a79ec65a --- /dev/null +++ b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/orocos-kdl_1.5.1-87.bb @@ -0,0 +1,20 @@ +LICENSE = "LGPL-2.1-only" +LIC_FILES_CHKSUM = "file://COPYING;md5=a8ffd58e6eb29a955738b8fcc9e9e8f2 \ + file://debian/copyright;md5=57b48fd56cf39965622e7d8a9ff2ed50" + +SRC_URI = " \ + git://github.com/orocos/orocos_kinematics_dynamics.git;protocol=https;branch=master \ + file://0001-CMakeLists.txt-fixing-install-location-of-cmake-conf.patch \ + file://0001-CMakeLists.txt-resolving-host-path-injection-in-.pc-.patch \ +" + +SRCREV = "129693e571a7822655d1f58bb0f83b385542a3d8" + +S = "${WORKDIR}/git/orocos_kdl" + +DEPENDS = " \ + libeigen \ + boost \ +" + +inherit cmake diff --git a/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl/0001-cmake-Allow-PYTHON_SITE_PACKAGES_INSTALL_DIR-set-ext.patch b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl/0001-cmake-Allow-PYTHON_SITE_PACKAGES_INSTALL_DIR-set-ext.patch new file mode 100644 index 00000000000..b8a8957c6d4 --- /dev/null +++ b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl/0001-cmake-Allow-PYTHON_SITE_PACKAGES_INSTALL_DIR-set-ext.patch @@ -0,0 +1,39 @@ +From e2526b82f8b654696cb5f768bb3e7520219340d6 Mon Sep 17 00:00:00 2001 +From: Matthias Schoepfer +Date: Mon, 6 May 2024 15:51:03 +0200 +Subject: [PATCH] cmake: Allow PYTHON_SITE_PACKAGES_INSTALL_DIR set extern + +The variable PYTHON_SITE_PACKAGES_INSTALL_DIR is kind of +hardcoded in the CMakeLists.txt to .../dist-packages. This +is not true for all linux distros. dist-packages comes +from debian and debian like distros. Python core uses +site-packages. + +We use an unintrusive way and allow the variable to be +passed from cmake, so you at least have the option to +set a different install location (i.e. site-packages) +from extern. + +Upstream-Status: Submitted [https://github.com/orocos/orocos_kinematics_dynamics/pull/461] + +Signed-off-by: Matthias Schoepfer +--- + CMakeLists.txt | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 64fdd21..e0bc2f2 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -28,7 +28,7 @@ set(PYBIND11_PYTHON_VERSION ${PYTHON_VERSION} CACHE STRING "Python version used + find_package(Python ${PYTHON_VERSION} COMPONENTS Interpreter Development REQUIRED) + # get_python_lib in python3 produces path which isn't in sys.path: https://bugs.launchpad.net/ubuntu/+source/python3-stdlib-extensions/+bug/1832215 + # execute_process(COMMAND ${PYTHON_EXECUTABLE} -c "from distutils.sysconfig import get_python_lib; print(get_python_lib(plat_specific=True, prefix=''))" OUTPUT_VARIABLE PYTHON_SITE_PACKAGES OUTPUT_STRIP_TRAILING_WHITESPACE) +-set(PYTHON_SITE_PACKAGES_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/lib/python${Python_VERSION_MAJOR}.${Python_VERSION_MINOR}/dist-packages") # This might be overridden below if built with catkin. ++set(PYTHON_SITE_PACKAGES_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/lib/python${Python_VERSION_MAJOR}.${Python_VERSION_MINOR}/dist-packages" CACHE STRING "Install location of the python package") # This might be overridden below if built with catkin. + set(LIBRARY_NAME "PyKDL") + + # catkin-specific configuration (optional) +-- +2.43.2 + diff --git a/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl_1.5.1-87.bb b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl_1.5.1-87.bb new file mode 100644 index 00000000000..2ae2b6c8456 --- /dev/null +++ b/meta-ros-common/recipes-orocos-kdl/orocos-kdl/python3-pykdl_1.5.1-87.bb @@ -0,0 +1,27 @@ +LICENSE = "LGPL-2.1-only" +LIC_FILES_CHKSUM = "file://../orocos_kdl/COPYING;md5=a8ffd58e6eb29a955738b8fcc9e9e8f2 \ + file://../orocos_kdl/debian/copyright;md5=57b48fd56cf39965622e7d8a9ff2ed50" + +SRC_URI = " \ + git://github.com/orocos/orocos_kinematics_dynamics.git;protocol=https;branch=master \ + file://0001-cmake-Allow-PYTHON_SITE_PACKAGES_INSTALL_DIR-set-ext.patch \ +" + +SRCREV = "129693e571a7822655d1f58bb0f83b385542a3d8" + +S = "${WORKDIR}/git/python_orocos_kdl" + +DEPENDS = " \ + orocos-kdl \ + python3-pybind11-native \ +" + +EXTRA_OECMAKE:append = " \ + -DPYTHON_SITE_PACKAGES_INSTALL_DIR=${PYTHON_SITEPACKAGES_DIR} \ +" + +inherit cmake python3-dir python3native + +FILES:${PN}:append = " \ + ${PYTHON_SITEPACKAGES_DIR}/PyKDL.so \ +" \ No newline at end of file diff --git a/meta-ros-common/recipes-support/asio/asio/0001-examples-cpp03-fix-build-without-std-chrono.patch b/meta-ros-common/recipes-support/asio/asio/0001-examples-cpp03-fix-build-without-std-chrono.patch deleted file mode 100644 index 980c277fc1d..00000000000 --- a/meta-ros-common/recipes-support/asio/asio/0001-examples-cpp03-fix-build-without-std-chrono.patch +++ /dev/null @@ -1,106 +0,0 @@ -From a174445bf5f4e4eebcbd6407b4284226d333d834 Mon Sep 17 00:00:00 2001 -From: Martin Jansa -Date: Wed, 20 May 2020 22:30:05 +0000 -Subject: [PATCH] examples/cpp03: fix build without std::chrono - -* e.g. with ubuntu 16.04 __GXX_EXPERIMENTAL_CXX0X__ isn't enabled by - default in g++ 5.4.0 and default __cplusplus 199711L, because of - that ASIO_HAS_STD_CHRONO doesn't get defined and even when - ASIO_HAS_BOOST_CHRONO is defined later, it doesn't add boost_chrono - library when linking the icmp and timeouts examples, which results - in that linking failure for timeouts/blocking_token_tcp_client: - -g++ -I../../../../asio-1.12.1/src/examples/cpp03/../../../include -isystem/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/include -O2 -pipe -pthread -ftemplate-depth-256 -L/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -L/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-rpath-link,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -Wl,-rpath-link,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-rpath,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -Wl,-rpath,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-O1 -Wl,--allow-shlib-undefined -Wl,--dynamic-linker=/OE/ros1-melodic-thud/tmp-glibc/sysroots-uninative/x86_64-linux/lib/ld-linux-x86-64.so.2 -pthread -o timeouts/blocking_token_tcp_client timeouts/blocking_token_tcp_client.o -lssl -lcrypto -lrt -timeouts/blocking_token_tcp_client.o: In function `unsigned long asio::io_context::run_one_until > >(boost::chrono::time_point > > const&)': -blocking_token_tcp_client.cpp:(.text._ZN4asio10io_context13run_one_untilIN5boost6chrono12steady_clockENS3_8durationIlNS2_5ratioILl1ELl1000000000EEEEEEEmRKNS3_10time_pointIT_T0_EE[_ZN4asio10io_context13run_one_untilIN5boost6chrono12steady_clockENS3_8durationIlNS2_5ratioILl1ELl1000000000EEEEEEEmRKNS3_10time_pointIT_T0_EE]+0x2b): undefined reference to `boost::chrono::steady_clock::now()' -blocking_token_tcp_client.cpp:(.text._ZN4asio10io_context13run_one_untilIN5boost6chrono12steady_clockENS3_8durationIlNS2_5ratioILl1ELl1000000000EEEEEEEmRKNS3_10time_pointIT_T0_EE[_ZN4asio10io_context13run_one_untilIN5boost6chrono12steady_clockENS3_8durationIlNS2_5ratioILl1ELl1000000000EEEEEEEmRKNS3_10time_pointIT_T0_EE]+0x4d1): undefined reference to `boost::chrono::steady_clock::now()' -timeouts/blocking_token_tcp_client.o: In function `unsigned long asio::io_context::run_for >(boost::chrono::duration > const&)': -blocking_token_tcp_client.cpp:(.text._ZN4asio10io_context7run_forIlN5boost5ratioILl1ELl1000000000EEEEEmRKNS2_6chrono8durationIT_T0_EE[_ZN4asio10io_context7run_forIlN5boost5ratioILl1ELl1000000000EEEEEmRKNS2_6chrono8durationIT_T0_EE]+0x1d): undefined reference to `boost::chrono::steady_clock::now()' -timeouts/blocking_token_tcp_client.o: In function `main': -blocking_token_tcp_client.cpp:(.text.startup+0x41c): undefined reference to `boost::chrono::steady_clock::now()' -blocking_token_tcp_client.cpp:(.text.startup+0xb5d): undefined reference to `boost::chrono::steady_clock::now()' -collect2: error: ld returned 1 exit status - - and similarly for icmp/ping: - -g++ -I../../../../asio-1.12.1/src/examples/cpp03/../../../include -isystem/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/include -O2 -pipe -pthread -ftemplate-depth-256 -L/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -L/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-rpath-link,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -Wl,-rpath-link,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-rpath,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/usr/lib -Wl,-rpath,/OE/ros1-melodic-thud/tmp-glibc/work/x86_64-linux/asio-native/1.12.1-r0/recipe-sysroot-native/lib -Wl,-O1 -Wl,--allow-shlib-undefined -Wl,--dynamic-linker=/OE/ros1-melodic-thud/tmp-glibc/sysroots-uninative/x86_64-linux/lib/ld-linux-x86-64.so.2 -pthread -o icmp/ping icmp/ping.o -lssl -lcrypto -lrt -icmp/ping.o: In function `asio::detail::timer_queue > >::wait_duration_msec(long) const': -ping.cpp:(.text._ZNK4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE18wait_duration_msecEl[_ZNK4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE18wait_duration_msecEl]+0x1b): undefined reference to `boost::chrono::steady_clock::now()' -icmp/ping.o: In function `asio::detail::timer_queue > >::wait_duration_usec(long) const': -ping.cpp:(.text._ZNK4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE18wait_duration_usecEl[_ZNK4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE18wait_duration_usecEl]+0x1b): undefined reference to `boost::chrono::steady_clock::now()' -icmp/ping.o: In function `asio::detail::timer_queue > >::get_ready_timers(asio::detail::op_queue&)': -ping.cpp:(.text._ZN4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE16get_ready_timersERNS0_8op_queueINS0_19scheduler_operationEEE[_ZN4asio6detail11timer_queueINS0_18chrono_time_traitsIN5boost6chrono12steady_clockENS_11wait_traitsIS5_EEEEE16get_ready_timersERNS0_8op_queueINS0_19scheduler_operationEEE]+0x33): undefined reference to `boost::chrono::steady_clock::now()' -icmp/ping.o: In function `pinger::handle_receive(unsigned long)': -ping.cpp:(.text._ZN6pinger14handle_receiveEm[_ZN6pinger14handle_receiveEm]+0x4d8): undefined reference to `boost::chrono::steady_clock::now()' -icmp/ping.o: In function `pinger::start_send()': -ping.cpp:(.text._ZN6pinger10start_sendEv[_ZN6pinger10start_sendEv]+0x307): undefined reference to `boost::chrono::steady_clock::now()' -collect2: error: ld returned 1 exit status -Makefile:1349: recipe for target 'icmp/ping' failed -make: *** [icmp/ping] Error 1 - -Upstream-Status: Submitted [https://github.com/chriskohlhoff/asio/pull/487] - -Signed-off-by: Martin Jansa ---- - src/examples/cpp03/Makefile.am | 25 +++++++++++++++++++++++++ - src/tests/Makefile.am | 4 ++++ - 2 files changed, 29 insertions(+) - -Index: asio-1.28.0/src/examples/cpp03/Makefile.am -=================================================================== ---- asio-1.28.0.orig/src/examples/cpp03/Makefile.am -+++ asio-1.28.0/src/examples/cpp03/Makefile.am -@@ -170,6 +170,27 @@ tutorial_daytime4_client_SOURCES = tutor - tutorial_daytime5_server_SOURCES = tutorial/daytime5/server.cpp - tutorial_daytime6_server_SOURCES = tutorial/daytime6/server.cpp - tutorial_daytime7_server_SOURCES = tutorial/daytime7/server.cpp -+if !HAVE_CXX11 -+## ASIO_HAS_STD_CHRONO not set and probably using ASIO_HAS_BOOST_CHRONO -+icmp_ping_LDADD = $(LDADD) -lboost_chrono -+invocation_prioritised_handlers_LDADD = $(LDADD) -lboost_chrono -+iostreams_daytime_client_LDADD = $(LDADD) -lboost_chrono -+iostreams_daytime_server_LDADD = $(LDADD) -lboost_chrono -+iostreams_http_client_LDADD = $(LDADD) -lboost_chrono -+multicast_sender_LDADD = $(LDADD) -lboost_chrono -+porthopper_client_LDADD = $(LDADD) -lboost_chrono -+porthopper_server_LDADD = $(LDADD) -lboost_chrono -+timeouts_async_tcp_client_LDADD = $(LDADD) -lboost_chrono -+timeouts_blocking_tcp_client_LDADD = $(LDADD) -lboost_chrono -+timeouts_blocking_token_tcp_client_LDADD = $(LDADD) -lboost_chrono -+timeouts_blocking_udp_client_LDADD = $(LDADD) -lboost_chrono -+timeouts_server_LDADD = $(LDADD) -lboost_chrono -+tutorial_timer1_timer_LDADD = $(LDADD) -lboost_chrono -+tutorial_timer2_timer_LDADD = $(LDADD) -lboost_chrono -+tutorial_timer3_timer_LDADD = $(LDADD) -lboost_chrono -+tutorial_timer4_timer_LDADD = $(LDADD) -lboost_chrono -+tutorial_timer5_timer_LDADD = $(LDADD) -lboost_chrono -+endif - - if !WINDOWS_TARGET - chat_posix_chat_client_SOURCES = chat/posix_chat_client.cpp -@@ -177,6 +198,10 @@ fork_daemon_SOURCES = fork/daemon.cpp - fork_process_per_connection_SOURCES = fork/process_per_connection.cpp - local_connect_pair_SOURCES = local/connect_pair.cpp - local_iostream_client_SOURCES = local/iostream_client.cpp -+if !HAVE_CXX11 -+## ASIO_HAS_STD_CHRONO not set and probably using ASIO_HAS_BOOST_CHRONO -+local_iostream_client_LDADD = $(LDADD) -lboost_chrono -+endif - local_stream_server_SOURCES = local/stream_server.cpp - local_stream_client_SOURCES = local/stream_client.cpp - endif -Index: asio-1.28.0/src/tests/Makefile.am -=================================================================== ---- asio-1.28.0.orig/src/tests/Makefile.am -+++ asio-1.28.0/src/tests/Makefile.am -@@ -460,6 +460,10 @@ latency_udp_client_SOURCES = latency/udp - latency_udp_server_SOURCES = latency/udp_server.cpp - performance_client_SOURCES = performance/client.cpp - performance_server_SOURCES = performance/server.cpp -+if !HAVE_CXX11 -+## ASIO_HAS_STD_CHRONO not set and probably using ASIO_HAS_BOOST_CHRONO -+performance_client_LDADD = $(LDADD) -lboost_chrono -+endif - endif - - unit_append_SOURCES = unit/append.cpp diff --git a/meta-ros-common/recipes-support/asio/asio_%.bbappend b/meta-ros-common/recipes-support/asio/asio_%.bbappend index db81282b1db..13661a581e9 100644 --- a/meta-ros-common/recipes-support/asio/asio_%.bbappend +++ b/meta-ros-common/recipes-support/asio/asio_%.bbappend @@ -1,6 +1,3 @@ # Copyright (c) 2019-2020 LG Electronics, Inc. BBCLASSEXTEND = "native" - -FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" -SRC_URI += "file://0001-examples-cpp03-fix-build-without-std-chrono.patch" diff --git a/meta-ros-common/recipes-support/ceres-solver/ceres-solver_%.bbappend b/meta-ros-common/recipes-support/ceres-solver/ceres-solver_%.bbappend index 3881a219a24..a8569de3ad0 100644 --- a/meta-ros-common/recipes-support/ceres-solver/ceres-solver_%.bbappend +++ b/meta-ros-common/recipes-support/ceres-solver/ceres-solver_%.bbappend @@ -1,3 +1,9 @@ # Copyright (c) 2019-2021 LG Electronics, Inc. +# Remove suitesparse-metis +PACKAGECONFIG[suitesparse] = "-DSUITESPARSE=ON,-DSUITESPARSE=OFF,suitesparse-config suitesparse-amd suitesparse-camd suitesparse-colamd suitesparse-ccolamd suitesparse-cholmod suitesparse-spqr" PACKAGECONFIG ??= "suitesparse cxsparse lapack" + +# Temporarily disable using Eigen Metis in ceres-solver +# https://github.com/ceres-solver/ceres-solver/issues/828 +# EXTRA_OECMAKE += "-DCERES_NO_EIGEN_METIS=ON" diff --git a/meta-ros-common/recipes-support/imath/imath_3.1.9.bb b/meta-ros-common/recipes-support/imath/imath_3.1.9.bb new file mode 100644 index 00000000000..ac73a7d24b8 --- /dev/null +++ b/meta-ros-common/recipes-support/imath/imath_3.1.9.bb @@ -0,0 +1,39 @@ +# Recipe created by recipetool +# This is the basis of a recipe and may need further editing in order to be fully functional. +# (Feel free to remove these comments when editing.) + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +# +# The following license files were not able to be identified and are +# represented as "Unknown" below, you will need to check them yourself: +# website/license.rst +# +# NOTE: multiple licenses have been detected; they have been separated with & +# in the LICENSE value for now since it is a reasonable assumption that all +# of the licenses apply. If instead there is a choice between the multiple +# licenses then you should change the value to separate the licenses with | +# instead of &. If there is any doubt, check the accompanying documentation +# to determine which situation is applicable. +LICENSE = "BSD-3-Clause & Unknown" +LIC_FILES_CHKSUM = "file://LICENSE.md;md5=0f34c2a8b1c102d683feca7a5835e921" + +SRC_URI = "git://github.com/AcademySoftwareFoundation/Imath.git;protocol=https;branch=main" + +# Modify these as desired +PV = "3.1.9+git${SRCPV}" +SRCREV = "642312b48e4c054198a3887b9e4e53da08fb7531" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: Python2 Python3 Sphinx Doxygen pybind11 Python Imath +DEPENDS = " \ + boost \ + python3-pybind11 \ +" + +inherit cmake python3native + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + diff --git a/meta-ros-common/recipes-support/zziplib/zziplib_0.13.74.bb b/meta-ros-common/recipes-support/zziplib/zziplib_0.13.74.bb new file mode 100644 index 00000000000..d69ffacb591 --- /dev/null +++ b/meta-ros-common/recipes-support/zziplib/zziplib_0.13.74.bb @@ -0,0 +1,23 @@ +SUMMARY = "ZZipLib - libZ-based ZIP-access Library with an Easy-to-Use API" +LICENSE = "LGPL-2.0-only & MPL-1.1 & Zlib" +LIC_FILES_CHKSUM = "file://COPYING.LIB;md5=55ca817ccb7d5b5b66355690e9abc605 \ + file://docs/COPYING.LIB;md5=55ca817ccb7d5b5b66355690e9abc605 \ + file://docs/COPYING.MPL;md5=48ff35a6e75247e702019cddd0eacc21 \ + file://docs/COPYING.ZLIB;md5=391a94bf6bcc911c019db84f178be0d4" + +SRC_URI = "git://github.com/gdraheim/zziplib;protocol=https;branch=master" + +PV = "0.13.74+git" +SRCREV = "df9e9c06634cb0c48bdc42efe9f7ac55847503a5" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: UnixCommands +# NOTE: unable to map the following pkg-config dependencies: sdl2 zzip +# (this is based on recipes that have previously been built and packaged) +DEPENDS = "zlib libsdl2" +# NOTE: spec file indicates the license may be "LGPLv2.1+" +inherit cmake pkgconfig python3native + +EXTRA_OECMAKE = "-DZZIPTEST=OFF" + diff --git a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-preferred-versions.inc b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-preferred-versions.inc index ebf46e317f8..c6aa5eb8c4f 100644 --- a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-preferred-versions.inc +++ b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-preferred-versions.inc @@ -10,3 +10,5 @@ # This is necessary as with ROS1 many recipes fail to build # as documented in https://github.com/ros/meta-ros/pull/936 PREFERRED_VERSION_pcl = "1.12.1+git" + +PREFERRED_VERSION_ogre-next = "2.2.0" diff --git a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-recipe-blacklist.inc b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-recipe-blacklist.inc index b1445077b6e..8f691485179 100644 --- a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-recipe-blacklist.inc +++ b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro-recipe-blacklist.inc @@ -9,7 +9,7 @@ SKIP_RECIPE[ament-clang-tidy] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', SKIP_RECIPE[ament-clang-tidy-native] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'clang', 'clang: depends on clang-tidy', '', d)}" SKIP_RECIPE[ament-cmake-clang-format] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'clang', 'clang: depends on ament-clang-format-native->clang-format', '', d)}" SKIP_RECIPE[ament-cmake-clang-tidy] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'clang', 'clang: depends on ament-clang-tidy-native->clang-tidy', '', d)}" -SKIP_RECIPE[aws-sdk-cpp-vendor] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'aws', 'aws: depends on recipes provided by meta-aws, but not yet tested with meta-ros', '', d)}" +#SKIP_RECIPE[aws-sdk-cpp-vendor] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'aws', 'aws: depends on recipes provided by meta-aws, but not yet tested with meta-ros', '', d)}" SKIP_RECIPE[aws-robomaker-small-warehouse-world] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-plugins and gazebo-ros->gazebo-rosdev->gazebo which is not available', '', d)}" SKIP_RECIPE[cartographer] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'cartographer', 'cartographer: depends on ROS_UNRESOLVED_DEP-libabsl-dev', '', d)}" SKIP_RECIPE[clearpath-gz] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-gz which depends on ros-gz-sim and ros-gz-sim-demos which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" diff --git a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro.inc b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro.inc index a9a7e1d9f88..492a13628ec 100644 --- a/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro.inc +++ b/meta-ros2-humble/conf/ros-distro/include/humble/ros-distro.inc @@ -144,9 +144,6 @@ ROS_WORLD_SKIP_GROUPS += "gazebo" # recipes depending on libqglviewer (https://packages.debian.org/source/stretch/libqglviewer https://packages.debian.org/stretch/libqglviewer2-qt5) ROS_WORLD_SKIP_GROUPS += "libqglviewer" -# recipes depending on ignition-* (ROS_UNRESOLVED_DEP-ignition-gazebo5, ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-msgs7, ROS_UNRESOLVED_DEP-ignition-transport10, ROS_UNRESOLVED_DEP-ignition-rendering5, ROS_UNRESOLVED_DEP-ignition-common4, ROS_UNRESOLVED_DEP-ignition-gui5) -ROS_WORLD_SKIP_GROUPS += "ignition" - # recipes depending on legacy mongo-cxx-driver (https://packages.debian.org/source/stretch/mongo-cxx-driver-legacy) # the mongodb recipe in meta-oe installs just the binaries mongoc, mongos, install_compass # the header files searched by mongo-store, warehouse-ros-mongo cmake files cmake/FindMongoClient.cmake and cmake/FindMongoDB.cmake @@ -360,3 +357,13 @@ ROS_UNRESOLVED_DEP-libserial-dev = "libserial" ROS_UNRESOLVED_DEP-python3-uvloop = "python3-uvloop" ROS_UNRESOLVED_DEP-gz-plugin = "gz-plugin" ROS_UNRESOLVED_DEP-libgdal-dev = "gdal" + +ROS_UNRESOLVED_DEP-python3-tabulate = "python3-tabulate" +ROS_UNRESOLVED_DEP-python3-graphviz = "python3-graphviz" +ROS_UNRESOLVED_DEP-graphviz-dev = "graphviz" +ROS_UNRESOLVED_DEP-python3-tqdm = "python3-tqdm" +ROS_UNRESOLVED_DEP-python3-smbus = "python3-smbus" +ROS_UNRESOLVED_DEP-libopus = "libopus" +ROS_UNRESOLVED_DEP-libopus-dev = "libopus" +ROS_UNRESOLVED_DEP-python3-colorcet = "python3-colorcet" +ROS_UNRESOLVED_DEP-libxkbcommon-dev = "libxkbcommon" diff --git a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior-tree_1.0.9-1.bbappend b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior-tree_1.0.9-1.bbappend index 98dad97dfbc..69afc38b3d5 100644 --- a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior-tree_1.0.9-1.bbappend +++ b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior-tree_1.0.9-1.bbappend @@ -7,6 +7,3 @@ ROS_BUILDTOOL_DEPENDS += " \ # ld: cannot find -lGeographicLib: No such file or directory DEPENDS += "geographiclib" - -FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" -SRC_URI += "file://add-geographiclib-find-package.patch" diff --git a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior_1.0.9-1.bbappend b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior_1.0.9-1.bbappend index 03a8f3df1ce..567511c7f63 100644 --- a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior_1.0.9-1.bbappend +++ b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-behavior_1.0.9-1.bbappend @@ -6,6 +6,3 @@ ROS_BUILDTOOL_DEPENDS += " \ # ld: cannot find -lGeographicLib: No such file or directory DEPENDS += "geographiclib" - -FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" -SRC_URI += "file://add-geographiclib-find-package.patch" diff --git a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-controller_1.0.9-1.bbappend b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-controller_1.0.9-1.bbappend index 04390a8a786..288ac0272cc 100644 --- a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-controller_1.0.9-1.bbappend +++ b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-controller_1.0.9-1.bbappend @@ -1,9 +1,5 @@ # Copyright (c) 2023 Wind River Systems, Inc. -ROS_BUILD_DEPENDS += " \ - pid-controller \ -" - ROS_BUILDTOOL_DEPENDS += " \ ament-cmake-ros-native \ " diff --git a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers/add_geographiclib.patch b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers/add_geographiclib.patch new file mode 100644 index 00000000000..51dda61c260 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers/add_geographiclib.patch @@ -0,0 +1,12 @@ +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -28,6 +28,7 @@ set(PROJECT_DEPENDENCIES + geometry_msgs + trajectory_msgs + Eigen3 ++ GeographicLib + ) + + foreach(DEPENDENCY ${PROJECT_DEPENDENCIES}) diff --git a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers_1.0.9-1.bbappend b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers_1.0.9-1.bbappend index 03a8f3df1ce..640221a615f 100644 --- a/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers_1.0.9-1.bbappend +++ b/meta-ros2-humble/recipes-bbappends/aerostack2/as2-motion-reference-handlers_1.0.9-1.bbappend @@ -7,5 +7,5 @@ ROS_BUILDTOOL_DEPENDS += " \ # ld: cannot find -lGeographicLib: No such file or directory DEPENDS += "geographiclib" -FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" -SRC_URI += "file://add-geographiclib-find-package.patch" +# FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +# SRC_URI += "file://add_geographiclib.patch" diff --git a/meta-ros2-humble/recipes-bbappends/flir-camera-driver/spinnaker-camera-driver_2.1.15-1.bbappend b/meta-ros2-humble/recipes-bbappends/flir-camera-driver/spinnaker-camera-driver_2.1.15-1.bbappend new file mode 100644 index 00000000000..b4af7f30b45 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/flir-camera-driver/spinnaker-camera-driver_2.1.15-1.bbappend @@ -0,0 +1,9 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +ROS_BUILDTOOL_DEPENDS += " \ + ament-cmake-ros \ + ament-cmake-gmock \ + ament-cmake-gtest \ + ament-cmake-pytest \ + rosidl-default-generators-native \ +" diff --git a/meta-ros2-humble/recipes-bbappends/ignition-cmake2-vendor/ignition-cmake2-vendor_0.0.2-2.bbappend b/meta-ros2-humble/recipes-bbappends/ignition-cmake2-vendor/ignition-cmake2-vendor_0.0.2-2.bbappend new file mode 100644 index 00000000000..1666f7c6725 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/ignition-cmake2-vendor/ignition-cmake2-vendor_0.0.2-2.bbappend @@ -0,0 +1,18 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +inherit python3native + +ROS_BUILDTOOL_DEPENDS = " \ + ament-copyright-native \ + ament-lint-cmake-native \ + ament-package-native \ + ament-xmllint-native \ +" + +ROS_BUILD_DEPENDS = " \ + ament-cmake-lint-cmake \ + ament-cmake-copyright \ + ament-cmake-core \ + ament-cmake-test \ + ament-cmake-xmllint \ +" diff --git a/meta-ros2-humble/recipes-bbappends/ignition-math6-vendor/ignition-math6-vendor_0.0.2-2.bbappend b/meta-ros2-humble/recipes-bbappends/ignition-math6-vendor/ignition-math6-vendor_0.0.2-2.bbappend new file mode 100644 index 00000000000..4e75d2679bb --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/ignition-math6-vendor/ignition-math6-vendor_0.0.2-2.bbappend @@ -0,0 +1,10 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +inherit python3native + +ROS_BUILDTOOL_DEPENDS += " \ + ament-copyright-native \ + ament-lint-cmake-native \ + ament-package-native \ + ament-xmllint-native \ +" diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0001-mrpt2-gui-pthread.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0001-mrpt2-gui-pthread.patch new file mode 100644 index 00000000000..365efea7f7d --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0001-mrpt2-gui-pthread.patch @@ -0,0 +1,11 @@ +Index: git/libs/gui/CMakeLists.txt +=================================================================== +--- git.orig/libs/gui/CMakeLists.txt ++++ git/libs/gui/CMakeLists.txt +@@ -68,4 +68,6 @@ if(BUILD_mrpt-gui) + if (MRPT_OPENGL_PROFILER) + target_compile_definitions(gui PRIVATE MRPT_OPENGL_PROFILER) + endif() ++ ++ target_link_libraries(gui PRIVATE Threads::Threads) + endif() diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0002-fix-debian-bug-unambiguous-tracking.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0002-fix-debian-bug-unambiguous-tracking.patch new file mode 100644 index 00000000000..78844e32ac3 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/0002-fix-debian-bug-unambiguous-tracking.patch @@ -0,0 +1,53 @@ +Index: git/apps/benchmarking-image-features/src/mainwindow.h +=================================================================== +--- git.orig/apps/benchmarking-image-features/src/mainwindow.h ++++ git/apps/benchmarking-image-features/src/mainwindow.h +@@ -217,7 +217,7 @@ class MainWindow : public QMainWindow + int tracking_image_counter; //!< counter for moving forward in the dataset + + /** tracker oject which calls the tracking method to perform tracking */ +- ::Tracker tracker_obj; ++ tracker::Tracker tracker_obj; + + /// tracker parameter variables + QCheckBox* tracker_param1; //! Checkbox for tracking parameter 1 +Index: git/apps/benchmarking-image-features/src/tracker.cpp +=================================================================== +--- git.orig/apps/benchmarking-image-features/src/tracker.cpp ++++ git/apps/benchmarking-image-features/src/tracker.cpp +@@ -24,7 +24,7 @@ using namespace mrpt::img; + /************************************************************************************************ + * Tracker Constructor * + ************************************************************************************************/ +-Tracker::Tracker() ++tracker::Tracker::Tracker() + { + hasResolution = false; + step_num = 0; +@@ -43,7 +43,7 @@ Tracker::Tracker() + /************************************************************************************************ + * Track Them All tracker * + ************************************************************************************************/ +-cv::Mat Tracker::trackThemAll( ++cv::Mat tracker::Tracker::trackThemAll( + std::vector files_fullpath_tracking, + int tracking_image_counter, int remove_lost_feats, int add_new_feats, + int max_feats, int patch_size, int window_width, int window_height) +Index: git/apps/benchmarking-image-features/src/tracker.h +=================================================================== +--- git.orig/apps/benchmarking-image-features/src/tracker.h ++++ git/apps/benchmarking-image-features/src/tracker.h +@@ -48,6 +48,8 @@ + #include + #include + ++namespace tracker ++{ + class Tracker + { + public: +@@ -103,3 +105,4 @@ class Tracker + int tracking_image_counter, int remove_lost_feats, int add_new_feats, + int max_feats, int patch_size, int window_width, int window_height); + }; ++} diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/add-cmake-toolchain-file-to-nanoflann.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/add-cmake-toolchain-file-to-nanoflann.patch new file mode 100644 index 00000000000..de0cea99a47 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/add-cmake-toolchain-file-to-nanoflann.patch @@ -0,0 +1,12 @@ +diff --git a/cmakemodules/script_nanoflann.cmake b/cmakemodules/script_nanoflann.cmake +index 82a07cae..8e1d2298 100644 +--- a/cmakemodules/script_nanoflann.cmake ++++ b/cmakemodules/script_nanoflann.cmake +@@ -19,6 +19,7 @@ if (NOT nanoflann_FOUND) + -DNANOFLANN_BUILD_EXAMPLES=OFF + -DNANOFLANN_BUILD_TESTS=OFF + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ++ -DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE} + RESULT_VARIABLE result + WORKING_DIRECTORY "${nanoflann_EMBEDDED_BUILD_DIR}" + ${echo_flag} diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/disable-host-system-dirs.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/disable-host-system-dirs.patch new file mode 100644 index 00000000000..cba04daa630 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/disable-host-system-dirs.patch @@ -0,0 +1,41 @@ +diff --git a/libs/hwdrivers/CMakeLists.txt b/libs/hwdrivers/CMakeLists.txt +index c45fc79..600a298 100644 +--- a/libs/hwdrivers/CMakeLists.txt ++++ b/libs/hwdrivers/CMakeLists.txt +@@ -207,20 +207,22 @@ endif() + # have some errors: + if(CMAKE_COMPILER_IS_GNUCXX AND CMAKE_MRPT_HAS_FFMPEG_SYSTEM) + set(EXTRA_ISYSTEMS "") +- if(EXISTS "${LIBAVCODEC_INCLUDEDIR}") +- set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR} ") +- endif() +- +- if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/ffmpeg") +- set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/ffmpeg ") +- endif() +- +- if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/libavcodec") +- set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/libavcodec ") +- endif() +- +- if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/libavformat") +- set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/libavformat ") ++ if (NOT "${LIBAVCODEC_INCLUDEDIR}" STREQUAL "/usr/include") ++ if(EXISTS "${LIBAVCODEC_INCLUDEDIR}") ++ set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR} ") ++ endif() ++ ++ if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/ffmpeg") ++ set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/ffmpeg ") ++ endif() ++ ++ if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/libavcodec") ++ set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/libavcodec ") ++ endif() ++ ++ if(EXISTS "${LIBAVCODEC_INCLUDEDIR}/libavformat") ++ set(EXTRA_ISYSTEMS "-isystem ${LIBAVCODEC_INCLUDEDIR}/libavformat ") ++ endif() + endif() + + if (NOT "${EXTRA_ISYSTEMS}" STREQUAL "") diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/enable-linking-octomap.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/enable-linking-octomap.patch new file mode 100644 index 00000000000..73120bd6cdb --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/enable-linking-octomap.patch @@ -0,0 +1,34 @@ +diff --git a/libs/maps/CMakeLists.txt b/libs/maps/CMakeLists.txt +index 55139c9..27bdee2 100644 +--- a/libs/maps/CMakeLists.txt ++++ b/libs/maps/CMakeLists.txt +@@ -40,7 +40,7 @@ if(BUILD_mrpt-maps) + if(TARGET "EP_octomap") + add_dependencies(maps EP_octomap) + endif() +- target_link_libraries(maps PRIVATE ${OCTOMAP_LIBRARIES}) ++ target_link_libraries(maps PUBLIC ${OCTOMAP_LIBRARIES}) + endif() + + target_link_libraries(maps PRIVATE ${MRPT_OPENGL_LIBS}) +diff --git a/libs/nav/CMakeLists.txt b/libs/nav/CMakeLists.txt +index c6459bd..8a2c319 100644 +--- a/libs/nav/CMakeLists.txt ++++ b/libs/nav/CMakeLists.txt +@@ -25,3 +25,16 @@ define_mrpt_lib( + mrpt-maps + mrpt-kinematics + ) ++ ++if(BUILD_mrpt-nav) ++ if (CMAKE_MRPT_HAS_OCTOMAP) ++ if (NOT "${OCTOMAP_LIBRARY_DIRS}" STREQUAL "") ++ link_directories("${OCTOMAP_LIBRARY_DIRS}") ++ endif() ++ if(TARGET "EP_octomap") ++ add_dependencies(nav EP_octomap) ++ endif() ++ target_link_libraries(nav PUBLIC ${OCTOMAP_LIBRARIES}) ++ endif() ++ ++endif() diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/fix-nanogui-cmakelist.patch b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/fix-nanogui-cmakelist.patch new file mode 100644 index 00000000000..f108539c180 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2/fix-nanogui-cmakelist.patch @@ -0,0 +1,89 @@ +diff --git a/3rdparty/nanogui/CMakeLists.txt b/3rdparty/nanogui/CMakeLists.txt +index fb22011d..1f0a2dbf 100644 +--- a/3rdparty/nanogui/CMakeLists.txt ++++ b/3rdparty/nanogui/CMakeLists.txt +@@ -6,7 +6,7 @@ if (POLICY CMP0058) + cmake_policy(SET CMP0058 NEW) + endif() + +-if (NOT IS_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/ext/nanovg/src") ++if (NOT IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/ext/nanovg/src") + message(FATAL_ERROR "The NanoGUI dependency repositories (NANOVG, etc.) are missing! " + "You probably did not clone the project with --recursive. It is possible to recover " + "by calling \"git submodule update --init --recursive\"") +@@ -93,7 +93,7 @@ else() + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/lib/") + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin/") + +- add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/ext/glfw" "ext_build/glfw") ++ add_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ext/glfw" "ext_build/glfw") + # Two targets have now been defined: `glfw_objects`, which will be merged into + # NanoGUI at the end, and `glfw`. The `glfw` target is the library itself + # (e.g., libglfw.so), but can be skipped as we do not need to link against it +@@ -234,11 +234,11 @@ endif() + if (NANOGUI_USE_GLAD) + # Build and include GLAD on Windows + list(APPEND LIBNANOGUI_EXTRA_SOURCE +- "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/src/glad.c" +- "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/include/glad/glad.h" +- "${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/include/KHR/khrplatform.h") ++ "${CMAKE_CURRENT_LIST_DIR}/ext/glad/src/glad.c" ++ "${CMAKE_CURRENT_LIST_DIR}/ext/glad/include/glad/glad.h" ++ "${CMAKE_CURRENT_LIST_DIR}/ext/glad/include/KHR/khrplatform.h") + if (MSVC) +- set_source_files_properties("${CMAKE_CURRENT_SOURCE_DIR}/ext/glad/src/glad.c" ++ set_source_files_properties("${CMAKE_CURRENT_LIST_DIR}/ext/glad/src/glad.c" + PROPERTIES COMPILE_FLAGS "/wd4055 ") + endif() + endif() +@@ -260,9 +260,9 @@ endif() + # * Roboto-Bold.ttf, Roboto-Regular.ttf => apt install fonts-roboto-fontface + # * entypo+ is a custom font from: https://github.com/svenevs/nanogui-entypo + # (it is NOT the same one as provided by the entypo debian package) +-find_file(ENTYPO_TTF_FILE entypo.ttf PATHS "${CMAKE_CURRENT_SOURCE_DIR}/resources" REQUIRED) +-find_file(ROBOTO_BOLD_TTF_FILE Roboto-Bold.ttf PATHS /usr/share/fonts/truetype/roboto-fontface/roboto/ "${CMAKE_CURRENT_SOURCE_DIR}/resources" REQUIRED) +-find_file(ROBOTO_REGULAR_TTF_FILE Roboto-Regular.ttf PATHS /usr/share/fonts/truetype/roboto-fontface/roboto/ "${CMAKE_CURRENT_SOURCE_DIR}/resources" REQUIRED) ++find_file(ENTYPO_TTF_FILE entypo.ttf PATHS "${CMAKE_CURRENT_LIST_DIR}/resources" REQUIRED) ++find_file(ROBOTO_BOLD_TTF_FILE Roboto-Bold.ttf PATHS "${CMAKE_CURRENT_LIST_DIR}/resources" REQUIRED) ++find_file(ROBOTO_REGULAR_TTF_FILE Roboto-Regular.ttf PATHS "${CMAKE_CURRENT_LIST_DIR}/resources" REQUIRED) + + # Glob up resource files + set(resources ${ENTYPO_TTF_FILE} ${ROBOTO_BOLD_TTF_FILE} ${ROBOTO_REGULAR_TTF_FILE}) +@@ -277,7 +277,7 @@ set(bin2c_cmdline + -DOUTPUT_C=nanogui_resources.cpp + -DOUTPUT_H=nanogui_resources.h + "-DINPUT_FILES=${resources_string}" +- -P "${CMAKE_CURRENT_SOURCE_DIR}/resources/bin2c.cmake") ++ -P "${CMAKE_CURRENT_LIST_DIR}/resources/bin2c.cmake") + + # Run bin2c on resource files + add_custom_command( +@@ -649,7 +649,7 @@ if (NANOGUI_BUILD_PYTHON) + # Detect Python + + # Try to autodetect Python (can be overridden manually if needed) +- list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/ext/pybind11/tools") ++ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/ext/pybind11/tools") + set(Python_ADDITIONAL_VERSIONS 3.7 3.6 3.5 3.4) + find_package(PythonLibsNew ${NANOGUI_PYTHON_VERSION}) + if (NOT PYTHONLIBS_FOUND) +@@ -762,8 +762,8 @@ else() + # Create documentation for python plugin (optional target for developers) + + string(REPLACE " " ";" MKDOC_CXX_FLAGS_LIST ${CMAKE_CXX_FLAGS}) +- get_property(MKDOC_INCLUDE_DIRECTORIES DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES) +- get_property(MKDOC_COMPILE_DEFINITIONS DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY COMPILE_DEFINITIONS) ++ get_property(MKDOC_INCLUDE_DIRECTORIES DIRECTORY ${CMAKE_CURRENT_LIST_DIR} PROPERTY INCLUDE_DIRECTORIES) ++ get_property(MKDOC_COMPILE_DEFINITIONS DIRECTORY ${CMAKE_CURRENT_LIST_DIR} PROPERTY COMPILE_DEFINITIONS) + + foreach (value ${MKDOC_INCLUDE_DIRECTORIES}) + list(APPEND MKDOC_CXX_FLAGS_LIST -I${value}) +@@ -779,7 +779,7 @@ else() + python3 ${PROJECT_SOURCE_DIR}/docs/mkdoc_rst.py + ${MKDOC_CXX_FLAGS_LIST} + ${PROJECT_SOURCE_DIR}/include/nanogui/*.h +- > ${CMAKE_CURRENT_SOURCE_DIR}/python/py_doc.h) ++ > ${CMAKE_CURRENT_LIST_DIR}/python/py_doc.h) + + endif() + diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2_2.12.1-1.bbappend b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2_2.12.1-1.bbappend new file mode 100644 index 00000000000..cfabe62036a --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/mrpt2_2.12.1-1.bbappend @@ -0,0 +1,64 @@ +FILESEXTRAPATHS:prepend := "${THISDIR}/${PN}:" + +SRC_URI += "file://disable-host-system-dirs.patch \ + file://enable-linking-octomap.patch \ + file://0001-mrpt2-gui-pthread.patch \ + file://0002-fix-debian-bug-unambiguous-tracking.patch \ + file://add-cmake-toolchain-file-to-nanoflann.patch \ +" + +LICENSE = "BSD-3-Clause" + +inherit pkgconfig + +FILES_${PN} += "${datadir}/mrpt* ${datadir}/metainfo/* ${datadir}/mime/packages/*" + +EXTRA_OECMAKE += "-DCMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES:PATH='${STAGING_INCDIR}'" + +# Copyright (c) 2020 LG Electronics, Inc. + +# Make this conditional on meta-qt5, because otherwise builds without +# meta-qt5 give the error "Could not inherit file classes/cmake_qt5.bbclass" +inherit ${@bb.utils.contains('BBFILE_COLLECTIONS', 'qt5-layer', 'cmake_qt5', '', d)} + +# CMake Error: TRY_RUN() invoked in cross-compiling mode, please set the following cache variables appropriately: +# HAS_LTO_EXITCODE (advanced) +# HAS_LTO_EXITCODE__TRYRUN_OUTPUT (advanced) +EXTRA_OECMAKE += "-DHAS_LTO_EXITCODE=1 -DHAS_LTO_EXITCODE__TRYRUN_OUTPUT=0" + +# Otherwise it tries to build own version with ExternalProject_Add and fails +# ninja: error: 'lib/liboctomath.a', needed by 'lib/libmrpt-maps.so.2.0.4', missing and no known rule to make it +ROS_BUILD_DEPENDS += " \ + octomap \ +" + +inherit ros_ament_cmake + +ROS_BUILDTOOL_DEPENDS += " \ + ament-package-native \ +" + +ROS_BUILD_DEPENDS += " \ + ament-cmake-libraries \ + ament-cmake-export-definitions \ + ament-cmake-export-include-directories \ + ament-cmake-export-interfaces \ + ament-cmake-export-libraries \ + ament-cmake-export-link-flags \ + ament-cmake-export-targets \ + ament-cmake-gen-version-h \ + ament-cmake-python \ + ament-cmake-target-dependencies \ + ament-cmake-include-directories \ + ament-cmake-test \ + ament-cmake-version \ + nanogui \ + rosidl-adapter \ +" + +# # Without the target rosidl-typesupport-{c,cpp}, ament finds the native packages and then fails to link (error: incompatible +# # target). +# ROS_BUILD_DEPENDS += " \ +# rosidl-typesupport-c \ +# rosidl-typesupport-cpp \ +# " diff --git a/meta-ros2-humble/recipes-bbappends/mrpt2/source.md b/meta-ros2-humble/recipes-bbappends/mrpt2/source.md new file mode 100644 index 00000000000..612d3a50b40 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrpt2/source.md @@ -0,0 +1,2 @@ +# https://raw.githubusercontent.com/ros/meta-ros/master/meta-ros2-foxy/recipes-bbappends/mrpt2/mrpt2_2.1.3-1.bbappend +c1be6a77acfe5851105666ffe3ee9034 mrpt2_2.%.bbappend diff --git a/meta-ros2-humble/recipes-bbappends/mrt-cmake-modules/mrt-cmake-modules/add-lanelet2-core.patch b/meta-ros2-humble/recipes-bbappends/mrt-cmake-modules/mrt-cmake-modules/add-lanelet2-core.patch new file mode 100644 index 00000000000..fb394e1ed1d --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/mrt-cmake-modules/mrt-cmake-modules/add-lanelet2-core.patch @@ -0,0 +1,17 @@ +diff --git a/yaml/cmake.yaml b/yaml/cmake.yaml +index 9e3516e..3cac390 100644 +--- a/yaml/cmake.yaml ++++ b/yaml/cmake.yaml +@@ -79,6 +79,12 @@ gtest: + include_dirs: [gtest_INCLUDE_DIRS] + libraries: [gtest_LIBRARIES] + name: gtest ++lanelet2_core: ++ components: [] ++ include_dirs: [lanelet2_core_INCLUDE_DIRS] ++ libraries: [lanelet2_core_LIBRARIES] ++ library_dirs: [] ++ name: lanelet2_core + libann-dev: + components: [] + include_dirs: [ANN_INCLUDE_DIR] diff --git a/meta-ros2-humble/recipes-bbappends/pangolin/pangolin_0.9.1-1.bbappend b/meta-ros2-humble/recipes-bbappends/pangolin/pangolin_0.9.1-1.bbappend new file mode 100644 index 00000000000..9d0f9bc9d5e --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/pangolin/pangolin_0.9.1-1.bbappend @@ -0,0 +1,3 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +DEPENDS += "zstd" diff --git a/meta-ros2-humble/recipes-bbappends/rmf-traffic-editor/rmf-traffic-editor-test-maps_1.6.2-1.bbappend b/meta-ros2-humble/recipes-bbappends/rmf-traffic-editor/rmf-traffic-editor-test-maps_1.6.2-1.bbappend new file mode 100644 index 00000000000..fde20021619 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/rmf-traffic-editor/rmf-traffic-editor-test-maps_1.6.2-1.bbappend @@ -0,0 +1,6 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +ROS_BUILDTOOL_DEPENDS:remove = "rmf-building-map-tools-native" +ROS_BUILDTOOL_DEPENDS:remove = "ros2run-native" +ROS_BUILDTOOL_DEPENDS:append = " rmf-building-map-tools" +ROS_BUILDTOOL_DEPENDS:append = " ros2run" diff --git a/meta-ros2-humble/recipes-bbappends/ros-gz/ros-gz-bridge_0.244.14-1.bbappend b/meta-ros2-humble/recipes-bbappends/ros-gz/ros-gz-bridge_0.244.14-1.bbappend new file mode 100644 index 00000000000..b51de7f85e0 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/ros-gz/ros-gz-bridge_0.244.14-1.bbappend @@ -0,0 +1,5 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +ROS_BUILDTOOL_DEPENDS += " \ + rosidl-cmake-native \ +" diff --git a/meta-ros2-humble/recipes-bbappends/rviz/rviz-rendering_%.bbappend b/meta-ros2-humble/recipes-bbappends/rviz/rviz-rendering_%.bbappend new file mode 100644 index 00000000000..9f7468bc212 --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/rviz/rviz-rendering_%.bbappend @@ -0,0 +1,8 @@ +# Copyright (c) 2021 LG Electronics, Inc. + +# CMake Warning at /jenkins/mjansa/build/ros/ros2-foxy-dunfell/tmp-glibc/work/core2-64-oe-linux/rviz-rendering/8.2.0-1-r0/recipe-sysroot/usr/lib/cmake/Qt5/Qt5Config.cmake:7 (message): +# SkippingbecauseOE_QMAKE_PATH_EXTERNAL_HOST_BINSisnotdefined +# ... +# CMake Error at CMakeLists.txt:65 (qt5_wrap_cpp): +# Unknown CMake command "qt5_wrap_cpp". +inherit ${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], '', 'cmake_qt5', d)} diff --git a/meta-ros2-humble/recipes-bbappends/rviz/rviz2_11.2.12-1.bbappend b/meta-ros2-humble/recipes-bbappends/rviz/rviz2_11.2.12-1.bbappend index d0f80942740..58939e9402c 100644 --- a/meta-ros2-humble/recipes-bbappends/rviz/rviz2_11.2.12-1.bbappend +++ b/meta-ros2-humble/recipes-bbappends/rviz/rviz2_11.2.12-1.bbappend @@ -8,7 +8,3 @@ ROS_BUILDTOOL_DEPENDS += " \ ament-package-native \ rosidl-default-generators-native \ " - -# ERROR: QA Issue: package rviz2 contains bad RPATH .../assimp/5.2.5-r0/recipe-sysroot/usr/lib -# in file .../rviz2/11.2.8-1-r0/packages-split/rviz2/usr/bin/rviz2 -EXTRA_OECMAKE += "-DCMAKE_SKIP_RPATH=ON" diff --git a/meta-ros2-humble/recipes-bbappends/turtlebot4-simulator/turtlebot4-ignition-gui-plugins_1.0.2-1.bbappend b/meta-ros2-humble/recipes-bbappends/turtlebot4-simulator/turtlebot4-ignition-gui-plugins_1.0.2-1.bbappend new file mode 100644 index 00000000000..0ffbfb5b3ef --- /dev/null +++ b/meta-ros2-humble/recipes-bbappends/turtlebot4-simulator/turtlebot4-ignition-gui-plugins_1.0.2-1.bbappend @@ -0,0 +1,4 @@ +# Copyright (c) 2023 Wind River Systems, Inc. + +ROS_BUILDTOOL_DEPENDS:remove = "ignition-gui6-native" +ROS_BUILD_DEPENDS:append = "ignition-gui6" diff --git a/meta-ros2-humble/recipes-support/ignition-fortress/ignition-fortress_1.0.3.bb b/meta-ros2-humble/recipes-support/ignition-fortress/ignition-fortress_1.0.3.bb new file mode 100644 index 00000000000..14e5f20eb46 --- /dev/null +++ b/meta-ros2-humble/recipes-support/ignition-fortress/ignition-fortress_1.0.3.bb @@ -0,0 +1,43 @@ +# Recipe created by recipetool +# This is the basis of a recipe and may need further editing in order to be fully functional. +# (Feel free to remove these comments when editing.) + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +# +# The following license files were not able to be identified and are +# represented as "Unknown" below, you will need to check them yourself: +# LICENSE +LICENSE = "Unknown" +LIC_FILES_CHKSUM = "file://LICENSE;md5=7eb60e29c1b7d33cea477b84618c2f4d" + +SRC_URI = "git://github.com/gazebosim/gz-fortress.git;protocol=https;branch=main" + +# Modify these as desired +PV = "1.0.3+git${SRCPV}" +SRCREV = "a8b194cb334944458b698f6d4d01b13b63c25f1d" + +S = "${WORKDIR}/git" + +inherit cmake + +DEPENDS = " \ + ignition-cmake2 \ + ignition-common4 \ + ignition-fuel-tools7 \ + ignition-gazebo6 \ + ignition-gui6 \ + ignition-launch5 \ + ignition-math6 \ + ignition-msgs8 \ + ignition-physics5 \ + ignition-plugin \ + ignition-rendering6 \ + ignition-sensors6 \ + ignition-transport11 \ + ignition-utils1 \ + sdformat \ +" +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + diff --git a/meta-ros2-humble/recipes-support/sdformat/sdformat_12.0.0.bb b/meta-ros2-humble/recipes-support/sdformat/sdformat_12.0.0.bb new file mode 100644 index 00000000000..94830ce65e1 --- /dev/null +++ b/meta-ros2-humble/recipes-support/sdformat/sdformat_12.0.0.bb @@ -0,0 +1,29 @@ +LICENSE = "Apache-2.0" +LIC_FILES_CHKSUM = "file://COPYING;md5=2a461be67a1edf991251f85f3aadd1d0 \ + file://LICENSE;md5=881ceadb4a5b6db70a8a48a5f5f0050f" + +SRC_URI = "git://github.com/gazebosim/sdformat.git;protocol=https;branch=main" + +PV = "12.0.0+git${SRCPV}" +SRCREV = "c9494fbeaa36f45f085921f2b509a4074f3984ca" + +S = "${WORKDIR}/git" + +inherit cmake pkgconfig + +DEPENDS = " \ + ignition-cmake2 \ + ignition-math6 \ + ignition-tools1 \ + ignition-utils1 \ + libtinyxml2 \ + urdfdom \ + python3-psutil-native \ + ruby-native \ +" + +FILES:${PN} += " \ + ${libdir}/ruby/ignition/cmdsdformat12.rb \ + ${datadir}/ignition/sdformat12.yaml \ + ${datadir}/sdformat12/* \ +" diff --git a/meta-ros2-humble/recipes-support/warehouse-ros-mongo/warehouse-ros-mongo_2.0.3.bb b/meta-ros2-humble/recipes-support/warehouse-ros-mongo/warehouse-ros-mongo_2.0.3.bb new file mode 100644 index 00000000000..e04c919f977 --- /dev/null +++ b/meta-ros2-humble/recipes-support/warehouse-ros-mongo/warehouse-ros-mongo_2.0.3.bb @@ -0,0 +1,29 @@ +# Recipe created by recipetool +# This is the basis of a recipe and may need further editing in order to be fully functional. +# (Feel free to remove these comments when editing.) + +# WARNING: the following LICENSE and LIC_FILES_CHKSUM values are best guesses - it is +# your responsibility to verify that the values are complete and correct. +# +# The following license files were not able to be identified and are +# represented as "Unknown" below, you will need to check them yourself: +# LICENSE +LICENSE = "Unknown" +LIC_FILES_CHKSUM = "file://LICENSE;md5=2711a5d3f3f7dac3923e893f23bf6df3" + +SRC_URI = "git://github.com/ros-planning/warehouse_ros_mongo.git;protocol=https;branch=ros2" + +# Modify these as desired +PV = "2.0.3+git${SRCPV}" +SRCREV = "55f7e9f8d1893abb566275f8dc609785684407e5" + +S = "${WORKDIR}/git" + +# NOTE: unable to map the following CMake package dependencies: MONGODB rclcpp ament_lint_auto std_msgs warehouse_ros class_loader launch_testing_ament_cmake rclpy ament_cmake_gtest ament_cmake_python ament_cmake +DEPENDS = "boost" + +inherit cmake + +# Specify any options you want to pass to cmake using EXTRA_OECMAKE: +EXTRA_OECMAKE = "" + diff --git a/meta-ros2-rolling/conf/ros-distro/include/rolling/generated/superflore-ros-distro.inc b/meta-ros2-rolling/conf/ros-distro/include/rolling/generated/superflore-ros-distro.inc index 9aeed8848ae..890d610ba2f 100644 --- a/meta-ros2-rolling/conf/ros-distro/include/rolling/generated/superflore-ros-distro.inc +++ b/meta-ros2-rolling/conf/ros-distro/include/rolling/generated/superflore-ros-distro.inc @@ -4370,7 +4370,6 @@ ROS_UNRESOLVED_DEP-cwiid-dev = "ROS_UNRESOLVED_DEP-cwiid-dev" ROS_UNRESOLVED_DEP-docker.io = "ROS_UNRESOLVED_DEP-docker.io" ROS_UNRESOLVED_DEP-gazebo-msgs = "ROS_UNRESOLVED_DEP-gazebo-msgs" ROS_UNRESOLVED_DEP-gazebo-ros = "ROS_UNRESOLVED_DEP-gazebo-ros" -ROS_UNRESOLVED_DEP-gazebo-ros-pkgs = "ROS_UNRESOLVED_DEP-gazebo-ros-pkgs" ROS_UNRESOLVED_DEP-gazebo-rosdev = "ROS_UNRESOLVED_DEP-gazebo-rosdev" ROS_UNRESOLVED_DEP-geos = "ROS_UNRESOLVED_DEP-geos" ROS_UNRESOLVED_DEP-glslang-dev = "ROS_UNRESOLVED_DEP-glslang-dev" diff --git a/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro-recipe-blacklist.inc b/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro-recipe-blacklist.inc index ec7ba1709cd..e0e5098a23c 100644 --- a/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro-recipe-blacklist.inc +++ b/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro-recipe-blacklist.inc @@ -12,9 +12,6 @@ SKIP_RECIPE[ament-cmake-clang-tidy] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GRO SKIP_RECIPE[aws-sdk-cpp-vendor] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'aws', 'aws: depends on recipes provided by meta-aws, but not yet tested with meta-ros', '', d)}" SKIP_RECIPE[aws-robomaker-small-warehouse-world] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-plugins and gazebo-ros->gazebo-rosdev->gazebo which is not available', '', d)}" SKIP_RECIPE[cartographer] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'cartographer', 'cartographer: depends on ROS_UNRESOLVED_DEP-libabsl-dev', '', d)}" -SKIP_RECIPE[clearpath-gz] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-gz which depends on ros-gz-sim and ros-gz-sim-demos which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[clearpath-simulator] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on clearpath-gz which depends on ros-gz which depends on ros-gz-sim and ros-gz-sim-demos which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[clearpath-viz] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-gz which depends on ros-gz-sim and ros-gz-sim-demos which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" SKIP_RECIPE[color-names] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on rviz2 which depends on qtbase; opengl: depends on rviz2 which depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz2 which depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[connext-cmake-module] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'connext', 'connext: depends on rti-connext-dds which is not available', '', d)}" SKIP_RECIPE[connext-cmake-module-native] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'connext', 'connext: depends on rti-connext-dds-native which is not available', '', d)}" @@ -25,9 +22,8 @@ SKIP_RECIPE[depthai-examples] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', SKIP_RECIPE[depthai-ros] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'hunter', 'Depends on hunter', '', d)}" SKIP_RECIPE[depthai-ros-msgs] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'hunter', 'Depends on hunter', '', d)}" SKIP_RECIPE[desktop] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5', 'opengl', 'x11'], 'qt5: rdepends on rviz2, rviz-default-plugins, rqt-common-plugins which rdepends on rqt-image-view which depends on qt-gui-cpp, rqt-gui, rqt-gui-cpp which depend on qtbase; pyqt5: rdepends on rqt-common-plugins which rdepends on rqt-image-view which depends on qt-gui-cpp, rqt-gui, rqt-gui-cpp which depend on python3-pyqt5 which requires pyqt5; opengl: rdepends on rviz2, rviz-default-plugins which depend on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: rdepends on rviz2, rviz-default-plugins which depend on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" -SKIP_RECIPE[dolly] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['ignition', 'gazebo', 'qt5', 'opengl', 'x11'], 'ignition: depends on dolly-ignition which depends on ros-ign-bridge and ros-ign-gazebo which depend on unavailable ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-msgs5, ROS_UNRESOLVED_DEP-ignition-transport8; gazebo: depends on dolly-gazebo which depends on gazebo-ros-pkgs which depends on gazebo-rosdev->gazebo which is not available; qt5: depends on dolly-gazebo which depends on rviz2 which depends on qtbase; opengl: depends on dolly-gazebo which depends on rviz2 which depends on depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on dolly-gazebo which depends on rviz2 which depends on depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" +SKIP_RECIPE[dolly] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['gazebo', 'qt5', 'opengl', 'x11'], 'gazebo: depends on dolly-gazebo which depends on gazebo-ros-pkgs which depends on gazebo-rosdev->gazebo which is not available; qt5: depends on dolly-gazebo which depends on rviz2 which depends on qtbase; opengl: depends on dolly-gazebo which depends on rviz2 which depends on depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on dolly-gazebo which depends on rviz2 which depends on depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[dolly-gazebo] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['gazebo', 'qt5', 'opengl', 'x11'], 'gazebo: depends on gazebo-ros-pkgs which depends on gazebo-rosdev->gazebo which is not available; qt5: depends on rviz2 which depends on qtbase; opengl: depends on rviz2 which depends on depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz2 which depends on depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" -SKIP_RECIPE[dolly-ignition] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-ign-bridge and ros-ign-gazebo which depend on unavailable ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-msgs5, ROS_UNRESOLVED_DEP-ignition-transport8', '', d)}" SKIP_RECIPE[gazebo-plugins] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-rosdev->gazebo which is not available', '', d)}" SKIP_RECIPE[gazebo-ros2-control] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-rosdev->gazebo which is not available', '', d)}" SKIP_RECIPE[gazebo-ros2-control-demos] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-ros2-control which depends on gazebo-rosdev->gazebo which is not available', '', d)}" @@ -35,11 +31,6 @@ SKIP_RECIPE[gazebo-ros] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazeb SKIP_RECIPE[gazebo-rosdev] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo11', 'gazebo: depends on gazebo11 which is not available', '', d)}" SKIP_RECIPE[gazebo-ros-pkgs] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gazebo', 'gazebo: depends on gazebo-rosdev->gazebo which is not available', '', d)}" SKIP_RECIPE[gurumdds-cmake-module] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'gurumdds', 'gurumdds: depends on gurumdds-2.6 which is not available', '', d)}" -SKIP_RECIPE[ignition-cmake2-vendor] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-cmake2', '', d)}" -SKIP_RECIPE[ignition-math6-vendor] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[ign-rviz] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-common4, ROS_UNRESOLVED_DEP-ignition-gui5', '', d)}" -SKIP_RECIPE[ign-rviz-common] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-gui5', '', d)}" -SKIP_RECIPE[ign-rviz-plugins] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-rendering5, ROS_UNRESOLVED_DEP-ignition-common4, ROS_UNRESOLVED_DEP-ignition-gui5', '', d)}" SKIP_RECIPE[joint-state-publisher-gui] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], 'qt5: depends on python-qt-binding which depends on qtbase; pyqt5: depends on python-qt-binding which depends on python3-pyqt5 which requires pyqt5', '', d)}" SKIP_RECIPE[libg2o] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['opengl', 'x11'], 'opengl: depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on libglu which requires x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[librealsense2] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['opengl', 'glfw'], 'opengl: depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; glfw: depends on librealsense2 which depends on glfw which is available only in dunfell and requires x11 in DISTRO_FEATURES', '', d)}" @@ -112,13 +103,6 @@ SKIP_RECIPE[rosbag2-bag-v2-plugins] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GRO SKIP_RECIPE[rosidl-typesupport-connext-c] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'connext', 'connext: depends on (rosidl-typesupport-connext-cpp-native,connext-cmake-module-native)->rti-connext-dds-native which is not available', '', d)}" SKIP_RECIPE[rosidl-typesupport-connext-cpp] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'connext', 'connext: depends on rti-connext-dds-native which is not available', '', d)}" SKIP_RECIPE[rosidl-typesupport-connext-cpp-native] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'connext', 'connext: depends on rti-connext-dds-native which is not available', '', d)}" -SKIP_RECIPE[ros-gz] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-gz-sim and ros-gz-sim-demos which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[ros-gz-sim-demos] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on ros-gz-sim which depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs8, ROS_UNRESOLVED_DEP-ignition-transport11, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[ros-ign] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: rdepends on ros-ign-image, ros-ign-bridge, ros-ign-gazebo which depend on unavailable ROS_UNRESOLVED_DEP-ignition-gazebo5, ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-msgs7, ROS_UNRESOLVED_DEP-ignition-transport10', '', d)}" -SKIP_RECIPE[ros-ign-bridge] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs7, ROS_UNRESOLVED_DEP-ignition-transport10', '', d)}" -SKIP_RECIPE[ros-ign-gazebo] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-gazebo5, ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[ros-ign-gazebo-demos] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-gazebo5', '', d)}" -SKIP_RECIPE[ros-ign-image] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'ignition', 'ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-msgs7, ROS_UNRESOLVED_DEP-ignition-transport10', '', d)}" SKIP_RECIPE[ros-image-turtlebot3-all] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'turtlebot3', 'turtlebot3: Rdepends on packagegroup-ros-turtlebot3-core, packagegroup-ros-turtlebot3-extended which rdepend turtlebot3-bringup,hls-lfcd-lds-driver,turtlebot3-msgs,ros-base,slam-karto, compressed-image-transport, depthimage-to-laserscan turtlebot3-applications-msgs, turtlebot3-autorace, cartographer-ros, turtlebot3, turtlebot3-applications which were not ported to foxy yet', '', d)}" SKIP_RECIPE[ros-image-turtlebot3-core] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'turtlebot3', 'turtlebot3: Rdepends on packagegroup-ros-turtlebot3-core, packagegroup-ros-turtlebot3-extended which rdepend turtlebot3-bringup,hls-lfcd-lds-driver,turtlebot3-msgs,ros-base,slam-karto, compressed-image-transport, depthimage-to-laserscan turtlebot3-applications-msgs, turtlebot3-autorace, cartographer-ros, turtlebot3, turtlebot3-applications which were not ported to foxy yet', '', d)}" SKIP_RECIPE[rqt-action] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], 'qt5: rdepends on rqt-gui-py which depends qt-gui which depends on qtbase; pyqt5: rdepends on rqt-gui-py which depends on qt-gui which depends on python3-pyqt5 which requires pyqt5', '', d)}" @@ -153,10 +137,10 @@ SKIP_RECIPE[rti-connext-dds-cmake-module] ?= "${@bb.utils.contains('ROS_WORLD_SK SKIP_RECIPE[run-move-group] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5', 'opengl', 'x11'], 'qt5: rdepends on moveit-resources-panda-moveit-config which rdepends on joint-state-publisher-gui which depends on python-qt-binding which depends on qtbase; pyqt5: rdepends on moveit-resources-panda-moveit-config which rdepends on joint-state-publisher-gui which depends on python-qt-binding which depends on python3-pyqt5 which requires pyqt5; opengl: depends on rviz2 which depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz2 which depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[run-moveit-cpp] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5', 'opengl', 'x11'], 'qt5: rdepends on moveit-resources-panda-moveit-config which rdepends on joint-state-publisher-gui which depends on python-qt-binding which depends on qtbase; pyqt5: rdepends on moveit-resources-panda-moveit-config which rdepends on joint-state-publisher-gui which depends on python-qt-binding which depends on python3-pyqt5 which requires pyqt5; opengl: depends on rviz2 which depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz2 which depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[run-ompl-constrained-planning] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['mongodb', 'mongodb-legacy-cxx-driver'], 'mongodb: rdepends on warehouse-ros-mongo which requires mongodb; mongodb-legacy-cxx-driver: rdepends on warehouse-ros-mongo which requires unavailable mongo-cxx-driver-legacy', '', d)}" -SKIP_RECIPE[rviz2] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11', 'ignition'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES; ignition: depends on rviz-default-plugins which depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" +SKIP_RECIPE[rviz2] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[rviz-common] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[rviz-ogre-vendor] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['opengl', 'x11'], 'opengl: depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" -SKIP_RECIPE[rviz-default-plugins] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11', 'ignition'], 'qt5: depends on qtbase; opengl: depends on rviz-common which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES; ignition: depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" +SKIP_RECIPE[rviz-default-plugins] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-common which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[rviz-imu-plugin] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5'], 'qt5: depends on qtbase', '', d)}" SKIP_RECIPE[rviz-rendering] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[rviz-rendering-tests] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" @@ -173,8 +157,8 @@ SKIP_RECIPE[turtlebot3-simulations] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP SKIP_RECIPE[turtlesim] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'qt5-widgets'], 'qt5: depends on qtbase; qt5-widgets: needs widgets enabled in qtbase PACKAGECONFIG', '', d)}" SKIP_RECIPE[turtle-tf2-cpp] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'qt5-widgets'], 'Requires turtlesim->qtbase which requires meta-qt5 to be included; qt5-widgets: needs widgets enabled in qtbase PACKAGECONFIG', '', d)}" SKIP_RECIPE[turtle-tf2-py] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'qt5-widgets'], 'Requires turtlesim->qtbase which requires meta-qt5 to be included; qt5-widgets: needs widgets enabled in qtbase PACKAGECONFIG', '', d)}" -SKIP_RECIPE[ur-description] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11', 'ignition'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES; ignition: depends on rviz2 which depends on rviz-default-plugins which depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" -SKIP_RECIPE[ur-robot-driver] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11', 'ignition'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES; ignition: depends on rviz2 which depends on rviz-default-plugins which depends on unavailable ROS_UNRESOLVED_DEP-ignition-math6', '', d)}" +SKIP_RECIPE[ur-description] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" +SKIP_RECIPE[ur-robot-driver] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'opengl', 'x11'], 'qt5: depends on qtbase; opengl: depends on rviz-ogre-vendor which depends on mesa which is not available because of missing opengl or vulkan in DISTRO_FEATURES; x11: depends on rviz-rendering which depends on rviz-ogre-vendor which depends on libx11,libxrandr,libxaw which require x11 in DISTRO_FEATURES', '', d)}" SKIP_RECIPE[usb-cam] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['ffmpeg', 'x264'], 'ffmpeg: Depends on ffmpeg which requires commercial license; x264: Depends on ffmpeg which depends on x264 which requires commercial license', '', d)}" SKIP_RECIPE[warehouse-ros-mongo] ?= "${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['mongodb', 'mongodb-legacy-cxx-driver'], 'Requires mongodb; mongodb-legacy-cxx-driver: requires unavailable mongo-cxx-driver-legacy', '', d)}" SKIP_RECIPE[webots-ros2-abb] ?= "${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', 'webots-python-modules', 'webots-python-modules: rdepends on webots-ros2-core which requires python-transforms3d-pip which is not available in OE yet', '', d)}" diff --git a/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro.inc b/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro.inc index 09c17f20059..7251323bb99 100644 --- a/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro.inc +++ b/meta-ros2-rolling/conf/ros-distro/include/rolling/ros-distro.inc @@ -140,13 +140,13 @@ ROS_WORLD_SKIP_GROUPS += "${@bb.utils.contains('DISTRO_FEATURES', 'x11', '', 'gl ROS_WORLD_SKIP_GROUPS += "webots-python-modules" # recipes depending on gazebo-rosdev -ROS_WORLD_SKIP_GROUPS += "gazebo" +# ROS_WORLD_SKIP_GROUPS += "gazebo" # recipes depending on libqglviewer (https://packages.debian.org/source/stretch/libqglviewer https://packages.debian.org/stretch/libqglviewer2-qt5) ROS_WORLD_SKIP_GROUPS += "libqglviewer" # recipes depending on ignition-* (ROS_UNRESOLVED_DEP-ignition-gazebo5, ROS_UNRESOLVED_DEP-ignition-math6, ROS_UNRESOLVED_DEP-ignition-msgs7, ROS_UNRESOLVED_DEP-ignition-transport10, ROS_UNRESOLVED_DEP-ignition-rendering5, ROS_UNRESOLVED_DEP-ignition-common4, ROS_UNRESOLVED_DEP-ignition-gui5) -ROS_WORLD_SKIP_GROUPS += "ignition" +# ROS_WORLD_SKIP_GROUPS += "ignition" # recipes depending on legacy mongo-cxx-driver (https://packages.debian.org/source/stretch/mongo-cxx-driver-legacy) # the mongodb recipe in meta-oe installs just the binaries mongoc, mongos, install_compass @@ -348,7 +348,6 @@ ROS_UNRESOLVED_DEP-ignition-gui6-native = "ignition-gui6-native" ROS_UNRESOLVED_DEP-libqt5-qml = "qtbase" ROS_UNRESOLVED_DEP-libqt5-quick = "qtbase" -ROS_UNRESOLVED_DEP-qml-module-qtquick-extras = "qtquickcontrols2" ROS_UNRESOLVED_DEP-range-v3 = "range-v3" ROS_UNRESOLVED_DEP-simde = "simde" @@ -386,3 +385,42 @@ ROS_UNRESOLVED_DEP-libgdal-dev = "gdal" ROS_UNRESOLVED_DEP-python3-smbus = "python3-smbus" ROS_UNRESOLVED_DEP-libxkbcommon-dev = "libxkbcommon" ROS_UNRESOLVED_DEP-libavdevice-dev = "ffmpeg" + +ROS_UNRESOLVED_DEP-glslc = "shaderc" +ROS_UNRESOLVED_DEP-libshaderc-dev = "shaderc" +ROS_UNRESOLVED_DEP-libgts = "gts" +ROS_UNRESOLVED_DEP-liblz4 = "lz4" +ROS_UNRESOLVED_DEP-liblz4-dev = "lz4" +ROS_UNRESOLVED_DEP-qml-module-qtquick-extras = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtcharts = "qtcharts" +ROS_UNRESOLVED_DEP-qml-module-qtgraphicaleffects = "qtgraphicaleffects" +ROS_UNRESOLVED_DEP-qml-module-qt-labs-folderlistmodel = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qt-labs-platform = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qt-labs-settings = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtlocation = "qtlocation" +ROS_UNRESOLVED_DEP-qml-module-qtpositioning = "qtlocation" +ROS_UNRESOLVED_DEP-qml-module-qtquick2 = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtquick-controls = "qtquickcontrols" +ROS_UNRESOLVED_DEP-qml-module-qtquick-controls2 = "qtquickcontrols2" +ROS_UNRESOLVED_DEP-qml-module-qtquick-dialogs = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtquick-layouts = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtquick-templates2 = "qtdeclarative" +ROS_UNRESOLVED_DEP-qml-module-qtquick-window2 = "qtdeclarative" +ROS_UNRESOLVED_DEP-ruby = "ruby" +ROS_UNRESOLVED_DEP-zziplib = "zziplib" +ROS_UNRESOLVED_DEP-libnlopt-dev = "nlopt" +ROS_UNRESOLVED_DEP-libnlopt-cxx-dev = "nlopt" +ROS_UNRESOLVED_DEP-rapidjson-dev = "rapidjson" +ROS_UNRESOLVED_DEP-libwebsockets = "libwebsockets" +ROS_UNRESOLVED_DEP-qtquickcontrols2-5-dev = "qtquickcontrols2" +ROS_UNRESOLVED_DEP-qtquickcontrols2-5 = "qtquickcontrols2" +ROS_UNRESOLVED_DEP-libfreeimage = "freeimage" +ROS_UNRESOLVED_DEP-libfreeimage-dev = "freeimage" + +ROS_UNRESOLVED_DEP-libxcb-randr0-dev = "libxcb" +ROS_UNRESOLVED_DEP-glslang-dev = "glslang" +ROS_UNRESOLVED_DEP-libx11-xcb-dev = "libxcb" +ROS_UNRESOLVED_DEP-libwebsockets-dev = "libwebsockets" +ROS_UNRESOLVED_DEP-libcurl-dev = "curl" +ROS_UNRESOLVED_DEP-libzip-dev = "libzip" +ROS_UNRESOLVED_DEP-ignition-math6 = "ignition-math6" diff --git a/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python/use-DESTDIR-for-install.patch b/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python/use-DESTDIR-for-install.patch new file mode 100644 index 00000000000..96bc63c6221 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python/use-DESTDIR-for-install.patch @@ -0,0 +1,26 @@ +Index: git/cmake/ament_python_install_module.cmake +=================================================================== +--- git.orig/cmake/ament_python_install_module.cmake ++++ git/cmake/ament_python_install_module.cmake +@@ -65,7 +65,7 @@ function(_ament_cmake_python_install_mod + "execute_process( + COMMAND + \"${python_interpreter}\" \"-m\" \"compileall\" +- \"${CMAKE_INSTALL_PREFIX}/${destination}/${module_file}\" ++ \"\$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/${destination}/${module_file}\" + )" + ) + endif() +Index: git/cmake/ament_python_install_package.cmake +=================================================================== +--- git.orig/cmake/ament_python_install_package.cmake ++++ git/cmake/ament_python_install_package.cmake +@@ -195,7 +195,7 @@ setup( + "execute_process( + COMMAND + \"${python_interpreter_config}\" \"-m\" \"compileall\" +- \"${CMAKE_INSTALL_PREFIX}/${ARG_DESTINATION}/${package_name}\" ++ \"\$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/${ARG_DESTINATION}/${package_name}\" + )" + ) + endif() diff --git a/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python_2.5.0-1.bbappend b/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python_2.5.0-1.bbappend new file mode 100644 index 00000000000..61d5fbfe327 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ament-cmake/ament-cmake-python_2.5.0-1.bbappend @@ -0,0 +1,4 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +SRC_URI += "file://use-DESTDIR-for-install.patch" diff --git a/meta-ros2-rolling/recipes-bbappends/cpp-polyfills/tl-expected_1.0.2-4.bbappend b/meta-ros2-rolling/recipes-bbappends/cpp-polyfills/tl-expected_1.0.2-4.bbappend new file mode 100644 index 00000000000..856b7216a48 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/cpp-polyfills/tl-expected_1.0.2-4.bbappend @@ -0,0 +1,2 @@ +# Converting from Creative-Commons-Zero-v1.0-Universal to SPDX conform CC0-1.0 +LICENSE = "CC0-1.0" diff --git a/meta-ros2-rolling/recipes-bbappends/demos/action-tutorials-interfaces_0.33.2-1.bbappend b/meta-ros2-rolling/recipes-bbappends/demos/action-tutorials-interfaces_0.33.2-1.bbappend index 7a3f2da3644..790b2528552 100644 --- a/meta-ros2-rolling/recipes-bbappends/demos/action-tutorials-interfaces_0.33.2-1.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/demos/action-tutorials-interfaces_0.33.2-1.bbappend @@ -12,15 +12,15 @@ ROS_BUILDTOOL_DEPENDS += " \ # Without the target rosidl-typesupport-{c,cpp}, ament finds the native packages and then fails to link (error: incompatible # target). ROS_BUILD_DEPENDS += " \ + action-msgs \ rosidl-typesupport-c \ rosidl-typesupport-cpp \ + service-msgs \ " ROS_EXEC_DEPENDS += " \ - action-msgs \ builtin-interfaces \ fastcdr \ - service-msgs \ unique-identifier-msgs \ rosidl-typesupport-fastrtps-c \ rosidl-typesupport-fastrtps-cpp \ diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-command-line_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-command-line_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-command-line_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-concepts_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-concepts_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-concepts_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-containers_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-containers_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-containers_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-converters_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-converters_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-converters_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core-apps_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core-apps_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core-apps_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-core_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-devices_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-devices_1.2.1-4.bbappend index 11df3a70faf..96b8e8f71f2 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-devices_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-devices_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_devices.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-eigen_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-eigen_1.2.1-4.bbappend index 9a153810c57..8af8ad055a5 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-eigen_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-eigen_1.2.1-4.bbappend @@ -1,3 +1,6 @@ # Copyright (c) 2020 LG Electronics, Inc. FILES:${PN}-doc:prepend = "${datadir}/licenses " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-exceptions_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-exceptions_1.2.1-4.bbappend index 6a1784e7dd7..e06bd2adb73 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-exceptions_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-exceptions_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_exceptions.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-filesystem_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-filesystem_1.2.1-4.bbappend index f04a32e868f..e8bb4fa7ae7 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-filesystem_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-filesystem_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_filesystem.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-formatters_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-formatters_1.2.1-4.bbappend index 086a969e588..cda9f783671 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-formatters_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-formatters_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_formatters.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-geometry_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-geometry_1.2.1-4.bbappend index e8169ad2b85..6c34b6aa7f0 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-geometry_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-geometry_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_geometry.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-ipc_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-ipc_1.2.1-4.bbappend index bb8d6bedd21..b01c57b3bb8 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-ipc_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-ipc_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_ipc.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-linear-algebra_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-linear-algebra_1.2.1-4.bbappend index b1868b4d7c5..289ba82d996 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-linear-algebra_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-linear-algebra_1.2.1-4.bbappend @@ -7,3 +7,6 @@ FILES:${PN}-dev += " \ # sophus provides headers and does not have a runtime package ROS_EXEC_DEPENDS:remove = "sophus" + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-manipulators_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-manipulators_1.2.1-4.bbappend index bc2f89f6f27..06b11c8fcdb 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-manipulators_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-manipulators_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_manipulators.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-math_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-math_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-math_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mobile-robot_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mobile-robot_1.2.1-4.bbappend index ac0a5db1671..fcda4464917 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mobile-robot_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mobile-robot_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_mobile_robot.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mpl_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mpl_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-mpl_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-sigslots_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-sigslots_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-sigslots_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-statistics_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-statistics_1.2.1-4.bbappend index 1f5212a0ad4..d7bc48355af 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-statistics_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-statistics_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_statistics.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-streams_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-streams_1.2.1-4.bbappend index 91a467f76df..290fd12ef2b 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-streams_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-streams_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_streams.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-threads_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-threads_1.2.1-4.bbappend index 2952381f9f0..8776a7f4cb1 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-threads_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-threads_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_threads.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-time_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-time_1.2.1-4.bbappend index 97211ad3f3b..3bb5417ee6b 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-time_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-time_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_time.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-type-traits_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-type-traits_1.2.1-4.bbappend index 7d09c357b31..bfcb0bafad5 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-type-traits_1.2.1-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-type-traits_1.2.1-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_type_traits.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-utilities_1.2.1-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-utilities_1.2.1-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-core/ecl-utilities_1.2.1-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-config_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-config_1.2.0-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-config_1.2.0-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-console_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-console_1.2.0-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-console_1.2.0-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-converters-lite_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-converters-lite_1.2.0-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-converters-lite_1.2.0-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-errors_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-errors_1.2.0-4.bbappend index 48022603c27..3ef4467598b 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-errors_1.2.0-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-errors_1.2.0-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_errors.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-io_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-io_1.2.0-4.bbappend index b470b7420d5..177dbfa5815 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-io_1.2.0-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-io_1.2.0-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_io.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-lite_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-lite_1.2.0-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-lite_1.2.0-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-sigslots-lite_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-sigslots-lite_1.2.0-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-sigslots-lite_1.2.0-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-time-lite_1.2.0-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-time-lite_1.2.0-4.bbappend index e5dd9092999..c86416f0036 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-time-lite_1.2.0-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-lite/ecl-time-lite_1.2.0-4.bbappend @@ -4,3 +4,6 @@ FILES:${PN}-dev += " \ ${libdir}/libecl_time_lite.so \ " + +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-build_1.0.3-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-build_1.0.3-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-build_1.0.3-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-license_1.0.3-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-license_1.0.3-4.bbappend index bd21e66300d..73db8a07367 100644 --- a/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-license_1.0.3-4.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-license_1.0.3-4.bbappend @@ -1,5 +1,3 @@ -# Copyright (c) 2022 Wind River Systems, Inc. - # ERROR: QA Issue: ecl-license: Files/directories were installed but not shipped in any package: # /usr/share/licenses # /usr/share/licenses/COPYING @@ -7,6 +5,19 @@ # /usr/share/licenses/COPYING-PLAIN # Please set FILES such that these items are packaged. Alternatively if they are unneeded, avoid installing them or delete them within do_install. # ecl-license: 4 installed and not shipped files. [installed-vs-shipped] -FILES:${PN} += "${datadir}/licenses/COPYING \ - ${datadir}/licenses/AUTHORS \ - ${datadir}/licenses/COPYING-PLAIN" + +# To fix this: If we are not caring for the license package, discard (delete) +# the files. If we are creating a -lic package, move it to the right +# location. + +do_install:append () { + if [ "${LICENSE_CREATE_PACKAGE}" == "0" ]; then + rm ${D}/usr/share/licenses -Rf + else + install -m 755 -d ${D}${datadir}/licenses/${PN} + mv ${D}${datadir}/licenses/* ${D}${datadir}/licenses/${PN}/ + fi +} + +## overwriting "BSD" to proper SPDX +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-tools_1.0.3-4.bbappend b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-tools_1.0.3-4.bbappend new file mode 100644 index 00000000000..f2ad92a0513 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/ecl-tools/ecl-tools_1.0.3-4.bbappend @@ -0,0 +1,2 @@ +# Setting LICENSE from BSD to BSD-3-Clause to be SPDX compliant +LICENSE = "BSD-3-Clause" diff --git a/meta-ros2-rolling/recipes-bbappends/example-interfaces/example-interfaces_0.12.0-2.bbappend b/meta-ros2-rolling/recipes-bbappends/example-interfaces/example-interfaces_0.12.0-2.bbappend index c169329a667..053db079ad4 100644 --- a/meta-ros2-rolling/recipes-bbappends/example-interfaces/example-interfaces_0.12.0-2.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/example-interfaces/example-interfaces_0.12.0-2.bbappend @@ -12,16 +12,16 @@ ROS_BUILDTOOL_DEPENDS += " \ # Without the target rosidl-typesupport-{c,cpp}, ament finds the native packages and then fails to link (error: incompatible # target). ROS_BUILD_DEPENDS += " \ + action-msgs \ rosidl-typesupport-c \ rosidl-typesupport-cpp \ + service-msgs \ " ROS_EXEC_DEPENDS += " \ - action-msgs \ builtin-interfaces \ fastcdr \ rosidl-typesupport-fastrtps-c \ rosidl-typesupport-fastrtps-cpp \ - service-msgs \ unique-identifier-msgs \ " diff --git a/meta-ros2-rolling/recipes-bbappends/google-benchmark-vendor/google-benchmark-vendor/0001-CMakeLists.txt-prevent-building-google-benchmark-wit.patch b/meta-ros2-rolling/recipes-bbappends/google-benchmark-vendor/google-benchmark-vendor/0001-CMakeLists.txt-prevent-building-google-benchmark-wit.patch index 782e64c397b..51423cab9c6 100644 --- a/meta-ros2-rolling/recipes-bbappends/google-benchmark-vendor/google-benchmark-vendor/0001-CMakeLists.txt-prevent-building-google-benchmark-wit.patch +++ b/meta-ros2-rolling/recipes-bbappends/google-benchmark-vendor/google-benchmark-vendor/0001-CMakeLists.txt-prevent-building-google-benchmark-wit.patch @@ -18,9 +18,9 @@ Index: git/CMakeLists.txt @@ -81,15 +81,15 @@ macro(build_benchmark) endmacro() - if(NOT benchmark_FOUND OR "${benchmark_VERSION}" VERSION_LESS 1.6.1) + if(NOT benchmark_FOUND OR "${benchmark_VERSION}" VERSION_LESS 1.8.3) - build_benchmark() -+ message(FATAL_ERROR "benchmark not found, missing dependency on google-benchmark or version less than 1.6.1, found ${benchmark_VERSION}") ++ message(FATAL_ERROR "benchmark not found, missing dependency on google-benchmark or version less than 1.8.3, found ${benchmark_VERSION}") elseif(benchmark_FOUND) # Ubuntu Focal and Jammy have a packaging bug where libbenchmark_main has no symbols, # causing linker failures. I'm pretty sure it shouldn't be a static library. diff --git a/meta-ros2-rolling/recipes-bbappends/gz-cmake-vendor/gz-cmake-vendor_0.0.6-1.bbappend b/meta-ros2-rolling/recipes-bbappends/gz-cmake-vendor/gz-cmake-vendor_0.0.6-1.bbappend new file mode 100644 index 00000000000..24c68134554 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/gz-cmake-vendor/gz-cmake-vendor_0.0.6-1.bbappend @@ -0,0 +1,9 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +export GZ_RELAX_VERSION_MATCH="1" + +DEPENDS += "gz-cmake3" + +# See CMakeLists.txt for details on why /usr/opt/gz_cmake_vendor/ is used +FILES:${PN} += "${datadir}/gz/gz-cmake3/* \ + ${prefix}/opt/gz_cmake_vendor/extra_cmake/lib/cmake/gz-cmake/*" diff --git a/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor/use-system-ogre-next.patch b/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor/use-system-ogre-next.patch new file mode 100644 index 00000000000..f415acdccba --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor/use-system-ogre-next.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index d66ac69..c52cf49 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -4,7 +4,10 @@ project(gz_ogre_next_vendor) + find_package(ament_cmake REQUIRED) + find_package(ament_cmake_vendor_package REQUIRED) + ++find_package(OGRE-Next) ++ + ament_vendor(${PROJECT_NAME} ++ SATISFIED OGRE-Next_FOUND + VCS_URL https://github.com/OGRECave/ogre-next.git + VCS_VERSION v2.3.3 + CMAKE_ARGS diff --git a/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor_0.0.2-1.bbappend b/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor_0.0.2-1.bbappend new file mode 100644 index 00000000000..dff28bc884f --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/gz-ogre-next-vendor/gz-ogre-next-vendor_0.0.2-1.bbappend @@ -0,0 +1,4 @@ +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +SRC_URI += "file://use-system-ogre-next.patch" + +DEPENDS += "ogre-next" diff --git a/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor/use-system-backwardcpp.patch b/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor/use-system-backwardcpp.patch new file mode 100644 index 00000000000..a4549751f5c --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor/use-system-backwardcpp.patch @@ -0,0 +1,12 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index b30781b..f872685 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -34,6 +34,7 @@ ament_vendor(${LIB_NAME_UNDERSCORE}_vendor + VCS_VERSION ${GITHUB_NAME}${LIB_VER_MAJOR}_${LIB_VER} + CMAKE_ARGS + -DBUILD_DOCS:BOOL=OFF ++ -DUSE_SYSTEM_BACKWARDCPP=ON + GLOBAL_HOOK + ) + diff --git a/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor_0.0.3-1.bbappend b/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor_0.0.3-1.bbappend new file mode 100644 index 00000000000..ea0586cc8cc --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/gz-tools-vendor/gz-tools-vendor_0.0.3-1.bbappend @@ -0,0 +1,9 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +DEPENDS += " gz-tools2 gz-tools2-native" + +# See CMakeLists.txt for details on why /usr/opt/gz_tools_vendor/ is used +FILES:${PN} += " \ + ${prefix}/opt/gz_tools_vendor/extra_cmake/lib/cmake/gz-tools/gz-tools-config-version.cmake \ + ${prefix}/opt/gz_tools_vendor/extra_cmake/lib/cmake/gz-tools/gz-tools-config.cmake \ +" diff --git a/meta-ros2-rolling/recipes-bbappends/mqtt-client/mqtt-client-interfaces_2.2.1-1.bbappend b/meta-ros2-rolling/recipes-bbappends/mqtt-client/mqtt-client-interfaces_2.2.1-1.bbappend new file mode 100644 index 00000000000..40594c6f69a --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/mqtt-client/mqtt-client-interfaces_2.2.1-1.bbappend @@ -0,0 +1,5 @@ +# Copyright (c) 2024 Wind River Systems, Inc. + +ROS_BUILDTOOL_DEPENDS += " \ + rosidl-default-runtime-native \ +" diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-fetch-orocos-kdl-with-bitbake-fetcher.patch b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-fetch-orocos-kdl-with-bitbake-fetcher.patch deleted file mode 100644 index 398091562bb..00000000000 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-fetch-orocos-kdl-with-bitbake-fetcher.patch +++ /dev/null @@ -1,16 +0,0 @@ -Index: git/CMakeLists.txt -=================================================================== ---- git.orig/CMakeLists.txt -+++ git/CMakeLists.txt -@@ -9,9 +9,8 @@ find_package(orocos_kdl 1.5.1 QUIET) - - ament_vendor(orocos_kdl_vendor - SATISFIED ${orocos_kdl_FOUND} -- VCS_URL https://github.com/orocos/orocos_kinematics_dynamics.git -- VCS_VERSION 507de66205e14b12c8c65f25eafc05c4dc66e21e -- SOURCE_SUBDIR orocos_kdl -+ VCS_URL orocos-kdl/orocos_kdl -+ VCS_TYPE path - GLOBAL_HOOK - CMAKE_ARGS - -DENABLE_TESTS:BOOL=OFF diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-use-system-orocos-kdl.patch b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-use-system-orocos-kdl.patch deleted file mode 100644 index 1a07d934b65..00000000000 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor/0001-CMakeLists.txt-use-system-orocos-kdl.patch +++ /dev/null @@ -1,101 +0,0 @@ -diff --git a/CMakeLists.txt b/CMakeLists.txt -index 655e562..c083241 100644 ---- a/CMakeLists.txt -+++ b/CMakeLists.txt -@@ -4,90 +4,13 @@ project(orocos_kdl_vendor) - - find_package(ament_cmake REQUIRED) - --option(FORCE_BUILD_VENDOR_PKG -- "Build orocos_kdl from source, even if system-installed package is available" -- OFF) -+# Set minimum version to find matching what would be built because PyKDL vendor will require it -+find_package(orocos_kdl 1.5.1 QUIET) - --if(NOT FORCE_BUILD_VENDOR_PKG) -- # Set minimum version to find matching what would be built because PyKDL vendor will require it -- find_package(orocos_kdl 1.5.1 QUIET) --endif() -- --macro(build_orocos_kdl) -- set(extra_cmake_args) -- if(DEFINED CMAKE_BUILD_TYPE) -- list(APPEND extra_cmake_args -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}) -- endif() -- if(DEFINED CMAKE_TOOLCHAIN_FILE) -- list(APPEND extra_cmake_args "-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}") -- if(ANDROID) -- if(DEFINED ANDROID_ABI) -- list(APPEND extra_cmake_args "-DANDROID_ABI=${ANDROID_ABI}") -- endif() -- if(DEFINED ANDROID_CPP_FEATURES) -- list(APPEND extra_cmake_args "-DANDROID_CPP_FEATURES=${ANDROID_CPP_FEATURES}") -- endif() -- if(DEFINED ANDROID_FUNCTION_LEVEL_LINKING) -- list(APPEND extra_cmake_args "-DANDROID_FUNCTION_LEVEL_LINKING=${ANDROID_FUNCTION_LEVEL_LINKING}") -- endif() -- if(DEFINED ANDROID_NATIVE_API_LEVEL) -- list(APPEND extra_cmake_args "-DANDROID_NATIVE_API_LEVEL=${ANDROID_NATIVE_API_LEVEL}") -- endif() -- if(DEFINED ANDROID_NDK) -- list(APPEND extra_cmake_args "-DANDROID_NDK=${ANDROID_NDK}") -- endif() -- if(DEFINED ANDROID_STL) -- list(APPEND extra_cmake_args "-DANDROID_STL=${ANDROID_STL}") -- endif() -- if(DEFINED ANDROID_TOOLCHAIN_NAME) -- list(APPEND extra_cmake_args "-DANDROID_TOOLCHAIN_NAME=${ANDROID_TOOLCHAIN_NAME}") -- endif() -- endif() -- else() -- list(APPEND extra_cmake_args "-DCMAKE_CXX_COMPILER=${CMAKE_CXX_COMPILER}") -- endif() -- list(APPEND extra_cmake_args "-DCMAKE_CXX_FLAGS=${CMAKE_CXX_FLAGS}") -- list(APPEND extra_cmake_args "-DENABLE_TESTS=OFF") -- list(APPEND extra_cmake_args "-DENABLE_EXAMPLES=OFF") -- -- include(ExternalProject) -- -- # Build orocos_kdl -- externalproject_add(orocos_kdl-507de66 -- GIT_REPOSITORY https://github.com/orocos/orocos_kinematics_dynamics.git -- GIT_TAG 507de66205e14b12c8c65f25eafc05c4dc66e21e # 1.5.1 + yet-to-be-released commits -- GIT_CONFIG advice.detachedHead=false -- # Suppress git update due to https://gitlab.kitware.com/cmake/cmake/-/issues/16419 -- # See https://github.com/ament/uncrustify_vendor/pull/22 for details -- UPDATE_COMMAND "" -- TIMEOUT 600 -- SOURCE_SUBDIR orocos_kdl -- CMAKE_ARGS -- -DCMAKE_INSTALL_PREFIX=${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}_install -- ${extra_cmake_args} -- PATCH_COMMAND -- ${CMAKE_COMMAND} -E chdir git apply -p1 --ignore-space-change --whitespace=nowarn -- ${CMAKE_CURRENT_SOURCE_DIR}/0001-include_project_name.patch -- ) -- -- # The external project will install to the build folder, but we'll install that on make install. -- install( -- DIRECTORY -- ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}_install/ -- DESTINATION -- ${CMAKE_INSTALL_PREFIX} -- USE_SOURCE_PERMISSIONS -- ) --endmacro() -- --if(NOT orocos_kdl_FOUND) -- message(STATUS "Did not find orocos-kdl installation, building from source") -- build_orocos_kdl() --endif() -- --if(BUILD_TESTING) -- find_package(ament_lint_auto REQUIRED) -- ament_lint_auto_find_test_dependencies() -+if(orocos_kdl_FOUND) -+ message(STATUS "Found orocos-kdl ${KDL_VERSION}") -+else() -+ message(FATAL_ERROR "orocos-kdl not found -- missing from DEPENDS?") - endif() - - ament_package(CONFIG_EXTRAS "orocos_kdl_vendor-extras.cmake") diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor_0.5.0-2.bbappend b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor_0.5.0-2.bbappend deleted file mode 100644 index e51d929b242..00000000000 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl-vendor_0.5.0-2.bbappend +++ /dev/null @@ -1,20 +0,0 @@ -# Copyright (c) 2020 LG Electronics, Inc. -# Copyright (c) 2022 Wind River Systems, Inc. - -require orocos-kdl.inc - -# orocos-kdl appears in both ROS_BUILD_DEPENDS and ROS_EXPORT_DEPENDS, so it's easier to remove it from DEPENDS. -DEPENDS:remove = "orocos-kdl" -ROS_EXEC_DEPENDS:remove = "orocos-kdl" - -# Instead of fetching a tarball -# during do_compile -FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" -SRC_URI += "file://0001-CMakeLists.txt-fetch-orocos-kdl-with-bitbake-fetcher.patch" - -SRC_URI[patch.md5sum] = "0208162d10526b13e62a6cdef2dadc84" -SRC_URI[patch.sha256sum] = "bed98c6c2a0261488d522b80fc792fd3ad817b01d7344342f28a470bd140c481" - -FILES:${PN}-dev += "${datadir}/orocos_kdl/cmake/*.cmake" - -inherit ros_insane_dev_so diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl.inc b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl.inc deleted file mode 100644 index 802549f8800..00000000000 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/orocos-kdl.inc +++ /dev/null @@ -1,12 +0,0 @@ -# Copyright (c) 2022 Wind River Systems, Inc. - -HOMEPAGE = "https://orocos.org/kdl.html" - -SRC_URI = " \ - git://github.com/ros2-gbp/orocos_kdl_vendor-release;name=release;${ROS_BRANCH};protocol=https \ - git://github.com/orocos/orocos_kinematics_dynamics.git;protocol=https;name=orocos-kdl;destsuffix=git/orocos-kdl;branch=master \ - " - -SRCREV_release = "f1bbaed1b5190dbfefd08ca445e53d20d1a0066e" -SRCREV_orocos-kdl = "507de66205e14b12c8c65f25eafc05c4dc66e21e" -SRCREV_FORMAT = "release_orocos-kdl" diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor/0001-use-system-pykdl.patch b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor/0001-use-system-pykdl.patch new file mode 100644 index 00000000000..ea1683e5b6e --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor/0001-use-system-pykdl.patch @@ -0,0 +1,40 @@ +Set pykdl_FOUND if PyKDL.so exists + +There is no pkgconfig for PyKDL and the Python site-packages directory +is not in the find_library() search path. + +Therefore simply, set pykdl_FOUND if PyKDL.so exists. + +Signed-off-by: Matthias Schoepfer +Signed-off-by: Rob Woolley + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index bd493da..aece216 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -14,23 +14,8 @@ if(POLICY CMP0135) + endif() + + if(NOT FORCE_BUILD_VENDOR_PKG) +- # Check if Python bindings are installed by trying to import from interpreter +- # Figure out Python3 debug/release before anything else can find_package it +- if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug") +- find_package(python_cmake_module REQUIRED) +- find_package(PythonExtra REQUIRED) +- +- # Force FindPython3 to use the debug interpreter where ROS 2 expects it +- set(Python3_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}") +- endif() +- find_package(Python3 REQUIRED COMPONENTS Interpreter Development) +- execute_process( +- COMMAND ${Python3_EXECUTABLE} -c "import PyKDL" +- RESULT_VARIABLE pykdl_import_exit_code +- OUTPUT_QUIET +- ERROR_QUIET +- ) +- if(pykdl_import_exit_code EQUAL 0) ++ # Check if Python bindings are installed by searching for them ++ if(EXISTS $ENV{STAGING_LIBDIR}/$ENV{PYTHON_DIR}/site-packages/PyKDL.so) + set(pykdl_FOUND 1) + endif() + endif() diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor_0.5.0-2.bbappend b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor_0.5.0-2.bbappend index 6c5cbc5ce63..0738dcbde05 100644 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor_0.5.0-2.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/orocos-kdl-vendor/python-orocos-kdl-vendor_0.5.0-2.bbappend @@ -1,20 +1,5 @@ -# Copyright (c) 2020 LG Electronics, Inc. -# Copyright (c) 2022 Wind River Systems, Inc. +FILESEXTRAPATHS:prepend := "${THISDIR}/${PN}:" -require orocos-kdl.inc - -LICENSE = "LGPL-2.1-or-later" -LIC_FILES_CHKSUM = "file://package.xml;beginline=15;endline=15;md5=d94c5c8f30151b2fe7d07ba53ed6444b" - -# orocos-kdl appears in both ROS_BUILD_DEPENDS and ROS_EXPORT_DEPENDS, so it's easier to remove it from DEPENDS. -DEPENDS:remove = "python3-pykdl" -ROS_EXEC_DEPENDS:remove = "python3-pykdl" - -S = "${WORKDIR}/git/orocos-kdl/python_orocos_kdl" - -SRC_URI[patch.md5sum] = "0208162d10526b13e62a6cdef2dadc84" -SRC_URI[patch.sha256sum] = "bed98c6c2a0261488d522b80fc792fd3ad817b01d7344342f28a470bd140c481" - -FILES:${PN}-dev += "${datadir}/orocos_kdl/cmake/*.cmake" - -inherit ros_insane_dev_so +SRC_URI:append = " \ + file://0001-use-system-pykdl.patch \ +" diff --git a/meta-ros2-rolling/recipes-bbappends/orocos-kinematics-dynamics/orocos-kdl-vendor_%.bbappend b/meta-ros2-rolling/recipes-bbappends/orocos-kinematics-dynamics/orocos-kdl-vendor_%.bbappend deleted file mode 100644 index 3779fbf8996..00000000000 --- a/meta-ros2-rolling/recipes-bbappends/orocos-kinematics-dynamics/orocos-kdl-vendor_%.bbappend +++ /dev/null @@ -1,3 +0,0 @@ -# Missing license version in package.xml -# https://github.com/ros2-gbp/orocos_kinematics_dynamics-release/issues/2 -LICENSE = "LGPL-2.1-only" diff --git a/meta-ros2-rolling/recipes-bbappends/phidgets-drivers/libphidget22/0001-Use-libphidget22-from-libphidget22-upstream-and-norm.patch b/meta-ros2-rolling/recipes-bbappends/phidgets-drivers/libphidget22/0001-Use-libphidget22-from-libphidget22-upstream-and-norm.patch index c148d9f334f..7dd98d5729c 100644 --- a/meta-ros2-rolling/recipes-bbappends/phidgets-drivers/libphidget22/0001-Use-libphidget22-from-libphidget22-upstream-and-norm.patch +++ b/meta-ros2-rolling/recipes-bbappends/phidgets-drivers/libphidget22/0001-Use-libphidget22-from-libphidget22-upstream-and-norm.patch @@ -13,7 +13,7 @@ Index: git/CMakeLists.txt =================================================================== --- git.orig/CMakeLists.txt +++ git/CMakeLists.txt -@@ -3,44 +3,6 @@ project(libphidget22) +@@ -3,43 +3,6 @@ project(libphidget22) find_package(ament_cmake REQUIRED) @@ -21,10 +21,9 @@ Index: git/CMakeLists.txt - -include(ExternalProject) -ExternalProject_Add(EP_${PROJECT_NAME} -- URL https://www.phidgets.com/downloads/phidget22/libraries/linux/libphidget22/libphidget22-1.13.20230224.tar.gz -- URL_MD5 e34f6bf266562d1950a82067ab5beaa9 +- URL https://www.phidgets.com/downloads/phidget22/libraries/linux/libphidget22/libphidget22-1.19.20240304.tar.gz +- URL_MD5 9b059eaef8cb8ce70b8abd7e4d309d1d - -- PATCH_COMMAND patch -p1 < ${CMAKE_CURRENT_SOURCE_DIR}/patch/libphidget22-1.13.20230224-fix-warnings.patch - SOURCE_DIR ${PROJECT_BINARY_DIR}/${PROJECT_NAME}-src - CONFIGURE_COMMAND - /configure diff --git a/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding/adding-sip5-integration.patch b/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding/adding-sip5-integration.patch new file mode 100644 index 00000000000..d47e0dab145 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding/adding-sip5-integration.patch @@ -0,0 +1,236 @@ +Based on work done by Sean Yen and Jochen Sprickerhof. + +Signed-off-by: Rob Woolley + +https://github.com/ros-o/python_qt_binding/pull/1 + +From 04d693309c473bcfa32094651c66254799b48eaf Mon Sep 17 00:00:00 2001 +From: Jochen Sprickerhof +Date: Mon, 28 Sep 2020 18:26:33 +0200 +Subject: [PATCH 1/8] workaround for new path sip dir in pyqt5 >= + 5.15.0+dfsg-1+exp1 + +--- + cmake/sip_configure.py | 5 +++++ + 1 file changed, 5 insertions(+) + + +https://github.com/ros-visualization/python_qt_binding/pull/94 + +From f639d5ea3218dd48dcfe5e16d4d36300ee963f84 Mon Sep 17 00:00:00 2001 +From: seanyen +Date: Fri, 7 Aug 2020 14:30:18 -0700 +Subject: [PATCH] Adding SIP 5 integration. + +--- + CMakeLists.txt | 1 + + cmake/pyproject.toml.in | 26 ++++++++++ + cmake/sip_helper.cmake | 107 ++++++++++++++++++++++++++++++++-------- + 3 files changed, 113 insertions(+), 21 deletions(-) + create mode 100644 cmake/pyproject.toml.in + +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -11,6 +11,7 @@ install(FILES + cmake/shiboken_helper.cmake + cmake/sip_configure.py + cmake/sip_helper.cmake ++ cmake/pyproject.toml.in + DESTINATION share/${PROJECT_NAME}/cmake) + + if(BUILD_TESTING) +Index: git/cmake/pyproject.toml.in +=================================================================== +--- /dev/null ++++ git/cmake/pyproject.toml.in +@@ -0,0 +1,30 @@ ++# Specify sip v5 as the build system for the package. ++[build-system] ++requires = ["PyQt-builder >=1, <2"] ++build-backend = "sipbuild.api" ++ ++[tool.sip] ++project-factory = "pyqtbuild:PyQtProject" ++ ++[tool.sip.builder] ++qmake = "@QMAKE_EXECUTABLE@" ++ ++[tool.sip.project] ++sip-files-dir = "@SIP_FILES_DIR@" ++build-dir = "@SIP_BUILD_DIR@" ++sip-include-dirs = ["@SIP_PROJECT_INCLUDE_DIRS@"] ++ ++# Specify the PEP 566 metadata for the project. ++[project] ++name = "lib@PROJECT_NAME@" ++ ++[tool.sip.bindings.libqt_gui_cpp_sip] ++sip-file = "@SIP_FILE@" ++include-dirs = [@SIP_INCLUDE_DIRS@] ++libraries = [@SIP_LIBRARIES@] ++library-dirs = [@SIP_LIBRARY_DIRS@] ++# this should be extra-objects, but these break inside pybuild with sip modules ++extra-link-args = [@SIP_ABS_LIBRARIES@] ++qmake-QT = ["widgets"] ++define-macros = [@SIP_EXTRA_DEFINES@] ++exceptions = true +Index: git/cmake/sip_helper.cmake +=================================================================== +--- git.orig/cmake/sip_helper.cmake ++++ git/cmake/sip_helper.cmake +@@ -31,9 +31,11 @@ execute_process( + if(PYTHON_SIP_EXECUTABLE) + string(STRIP ${PYTHON_SIP_EXECUTABLE} SIP_EXECUTABLE) + else() +- find_program(SIP_EXECUTABLE sip) ++ find_program(SIP_EXECUTABLE NAMES sip sip-build) + endif() + ++set(SIP_PROJECT_INCLUDE_DIRS "$ENV{SIP_PROJECT_INCLUDE_DIRS}") ++ + if(SIP_EXECUTABLE) + message(STATUS "SIP binding generator available at: ${SIP_EXECUTABLE}") + set(sip_helper_FOUND TRUE) +@@ -42,6 +42,20 @@ else() + set(sip_helper_NOTFOUND TRUE) + endif() + ++if(sip_helper_FOUND) ++ execute_process( ++ COMMAND ${SIP_EXECUTABLE} -V ++ OUTPUT_VARIABLE SIP_VERSION ++ ERROR_QUIET) ++ string(STRIP ${SIP_VERSION} SIP_VERSION) ++ message(STATUS "SIP binding generator version: ${SIP_VERSION}") ++endif() ++ ++execute_process( ++ COMMAND ${Python3_EXECUTABLE} -c "import sysconfig as c; print(c.get_config_var('EXT_SUFFIX'), end='')" ++ OUTPUT_VARIABLE PYTHON_EXTENSION_MODULE_SUFFIX ++ ERROR_QUIET) ++ + # + # Run the SIP generator and compile the generated code into a library. + # +@@ -93,37 +107,95 @@ function(build_sip_binding PROJECT_NAME + set(LIBRARY_DIRS ${${PROJECT_NAME}_LIBRARY_DIRS}) + set(LDFLAGS_OTHER ${${PROJECT_NAME}_LDFLAGS_OTHER}) + +- add_custom_command( +- OUTPUT ${SIP_BUILD_DIR}/Makefile +- COMMAND ${Python3_EXECUTABLE} ${sip_SIP_CONFIGURE} ${SIP_BUILD_DIR} ${SIP_FILE} ${sip_LIBRARY_DIR} +- \"${INCLUDE_DIRS}\" \"${LIBRARIES}\" \"${LIBRARY_DIRS}\" \"${LDFLAGS_OTHER}\" +- DEPENDS ${sip_SIP_CONFIGURE} ${SIP_FILE} ${sip_DEPENDS} +- WORKING_DIRECTORY ${sip_SOURCE_DIR} +- COMMENT "Running SIP generator for ${PROJECT_NAME} Python bindings..." +- ) ++ if(${SIP_VERSION} VERSION_GREATER_EQUAL "5.0.0") ++ # Since v5, SIP implements the backend per PEP 517, PEP 518 ++ # Here we synthesize `pyproject.toml` and run `pip install` + +- if(NOT EXISTS "${sip_LIBRARY_DIR}") ++ find_program(QMAKE_EXECUTABLE NAMES qmake REQUIRED) ++ ++ file(REMOVE_RECURSE ${SIP_BUILD_DIR}) + file(MAKE_DIRECTORY ${sip_LIBRARY_DIR}) +- endif() ++ set(SIP_FILES_DIR ${sip_SOURCE_DIR}) + +- if(WIN32) +- set(MAKE_EXECUTABLE NMake.exe) ++ set(SIP_INCLUDE_DIRS "") ++ foreach(_x ${INCLUDE_DIRS}) ++ set(SIP_INCLUDE_DIRS "${SIP_INCLUDE_DIRS},\"${_x}\"") ++ endforeach() ++ string(REGEX REPLACE "^," "" SIP_INCLUDE_DIRS "${SIP_INCLUDE_DIRS}") ++ ++ # pyproject.toml expects libraries listed as such to be added to the linker command ++ # via `-l`, but this does not work for libraries with absolute paths ++ # instead we have to pass them to the linker via a different parameter ++ set(_SIP_REL_LIBRARIES "") ++ set(_SIP_ABS_LIBRARIES "") ++ foreach(_x ${LIBRARIES} ${Python3_LIBRARIES}) ++ cmake_path(IS_ABSOLUTE _x is_abs) ++ if(is_abs) ++ list(APPEND _SIP_ABS_LIBRARIES "\"${_x}\"") ++ else() ++ list(APPEND _SIP_REL_LIBRARIES "\"${_x}\"") ++ endif() ++ endforeach() ++ list(JOIN _SIP_REL_LIBRARIES "," SIP_LIBRARIES) ++ list(JOIN _SIP_ABS_LIBRARIES "," SIP_ABS_LIBRARIES) ++ ++ set(SIP_LIBRARY_DIRS "") ++ foreach(_x ${LIBRARY_DIRS}) ++ set(SIP_LIBRARY_DIRS "${SIP_LIBRARY_DIRS},\"${_x}\"") ++ endforeach() ++ string(REGEX REPLACE "^," "" SIP_LIBRARY_DIRS "${SIP_LIBRARY_DIRS}") ++ ++ set(SIP_EXTRA_DEFINES "") ++ foreach(_x ${EXTRA_DEFINES}) ++ set(SIP_EXTRA_DEFINES "${SIP_EXTRA_DEFINES},\"${_x}\"") ++ endforeach() ++ string(REGEX REPLACE "^," "" SIP_EXTRA_DEFINES "${SIP_EXTRA_DEFINES}") ++ ++ # TODO: ++ # I don't know what to do about LDFLAGS_OTHER ++ # what's the equivalent construct in sip5? ++ ++ configure_file( ++ ${__PYTHON_QT_BINDING_SIP_HELPER_DIR}/pyproject.toml.in ++ ${sip_BINARY_DIR}/sip/pyproject.toml ++ ) ++ add_custom_command( ++ OUTPUT ${sip_LIBRARY_DIR}/lib${PROJECT_NAME}${PYTHON_EXTENSION_MODULE_SUFFIX} ++ COMMAND ${Python3_EXECUTABLE} -m pip install . --target ${sip_LIBRARY_DIR} --no-deps --no-build-isolation ++ DEPENDS ${sip_SIP_CONFIGURE} ${SIP_FILE} ${sip_DEPENDS} ++ WORKING_DIRECTORY ${sip_BINARY_DIR}/sip ++ COMMENT "Running SIP-build generator for ${PROJECT_NAME} Python bindings..." ++ ) + else() +- find_program(MAKE_PROGRAM NAMES make) +- message(STATUS "Found required make: ${MAKE_PROGRAM}") +- set(MAKE_EXECUTABLE ${MAKE_PROGRAM}) ++ add_custom_command( ++ OUTPUT ${SIP_BUILD_DIR}/Makefile ++ COMMAND ${Python3_EXECUTABLE} ${sip_SIP_CONFIGURE} ${SIP_BUILD_DIR} ${SIP_FILE} ${sip_LIBRARY_DIR} \"${INCLUDE_DIRS}\" \"${LIBRARIES}\" \"${LIBRARY_DIRS}\" \"${LDFLAGS_OTHER}\" \"${EXTRA_DEFINES}\" ++ DEPENDS ${sip_SIP_CONFIGURE} ${SIP_FILE} ${sip_DEPENDS} ++ WORKING_DIRECTORY ${sip_SOURCE_DIR} ++ COMMENT "Running SIP generator for ${PROJECT_NAME} Python bindings..." ++ ) ++ ++ if(NOT EXISTS "${sip_LIBRARY_DIR}") ++ file(MAKE_DIRECTORY ${sip_LIBRARY_DIR}) ++ endif() ++ ++ if(WIN32) ++ set(MAKE_EXECUTABLE NMake.exe) ++ else() ++ set(MAKE_EXECUTABLE "\$(MAKE)") ++ endif() ++ ++ add_custom_command( ++ OUTPUT ${sip_LIBRARY_DIR}/lib${PROJECT_NAME}${PYTHON_EXTENSION_MODULE_SUFFIX} ++ COMMAND ${MAKE_EXECUTABLE} ++ DEPENDS ${SIP_BUILD_DIR}/Makefile ++ WORKING_DIRECTORY ${SIP_BUILD_DIR} ++ COMMENT "Compiling generated code for ${PROJECT_NAME} Python bindings..." ++ ) + endif() + +- add_custom_command( +- OUTPUT ${sip_LIBRARY_DIR}/lib${PROJECT_NAME}${CMAKE_SHARED_LIBRARY_SUFFIX} +- COMMAND ${MAKE_EXECUTABLE} +- DEPENDS ${SIP_BUILD_DIR}/Makefile +- WORKING_DIRECTORY ${SIP_BUILD_DIR} +- COMMENT "Compiling generated code for ${PROJECT_NAME} Python bindings..." +- ) +- + add_custom_target(lib${PROJECT_NAME} ALL +- DEPENDS ${sip_LIBRARY_DIR}/lib${PROJECT_NAME}${CMAKE_SHARED_LIBRARY_SUFFIX} ++ DEPENDS ${sip_LIBRARY_DIR}/lib${PROJECT_NAME}${PYTHON_EXTENSION_MODULE_SUFFIX} + COMMENT "Meta target for ${PROJECT_NAME} Python bindings..." + ) + add_dependencies(lib${PROJECT_NAME} ${sip_DEPENDENCIES}) diff --git a/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding_%.bbappend b/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding_%.bbappend index 3c4e43e1cda..05e4952a64b 100644 --- a/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding_%.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/python-qt-binding/python-qt-binding_%.bbappend @@ -1,3 +1,8 @@ -# Copyright (c) 2023 Wind River Systems, Inc. +# Copyright (c) 2023-2024 Wind River Systems, Inc. -DEPENDS += "sip3-native python3-pyqt5-native" +SRC_URI += "file://adding-sip5-integration.patch" + +inherit python3targetconfig + +DEPENDS += "sip-native python3-pyqt5-native" +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" diff --git a/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp/use-cmake-target-libraries.patch b/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp/use-cmake-target-libraries.patch new file mode 100644 index 00000000000..9eaffd1d838 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp/use-cmake-target-libraries.patch @@ -0,0 +1,48 @@ +This uses the CMake target variables for libraries instead of the generator. + +The generator approach was resulting in TARGET_FILE:Python3::Python appearing +directly in the generated pyproject.toml and libqt_gui_cpp_sip.pro files. + +Eventually, pip install was invoked which called QMake then Make. The linker +did not like it and would fail. + +This resulted in pip reporting "error: subprocess-exited-with-error" + +Signed-off-by: Rob Woolley + +Upstream-status: Pending + +Index: git/src/qt_gui_cpp_sip/CMakeLists.txt +=================================================================== +--- git.orig/src/qt_gui_cpp_sip/CMakeLists.txt ++++ git/src/qt_gui_cpp_sip/CMakeLists.txt +@@ -55,8 +55,8 @@ find_package(Python3 REQUIRED COMPONENTS + + set(_qt_gui_cpp_sip_LIBRARIES + ${deps_libraries} +- Python3::Python +- qt_gui_cpp ++ ${Python3_LIBRARIES} ++ ${qt_gui_cpp_LIBRARIES} + ) + + # sip needs libraries to have resolved paths and cannot link to cmake targets +@@ -90,12 +90,17 @@ if(sip_helper_FOUND) + DEPENDENCIES qt_gui_cpp + ) + ++ execute_process( ++ COMMAND ${Python3_EXECUTABLE} -c "import sysconfig as c; print(c.get_config_var('EXT_SUFFIX'), end='')" ++ OUTPUT_VARIABLE PYTHON_EXTENSION_MODULE_SUFFIX ++ ERROR_QUIET) ++ + if(APPLE) + set(LIBQT_GUI_CPP_SIP_SUFFIX .so) + elseif(WIN32) + set(LIBQT_GUI_CPP_SIP_SUFFIX .pyd) + else() +- set(LIBQT_GUI_CPP_SIP_SUFFIX ${CMAKE_SHARED_LIBRARY_SUFFIX}) ++ set(LIBQT_GUI_CPP_SIP_SUFFIX ${PYTHON_EXTENSION_MODULE_SUFFIX}) + endif() + + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/libqt_gui_cpp_sip${LIBQT_GUI_CPP_SIP_SUFFIX} diff --git a/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp_2.7.4-1.bbappend b/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp_2.7.4-1.bbappend index df8ec276cda..8452c389f63 100644 --- a/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp_2.7.4-1.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/qt-gui-core/qt-gui-cpp_2.7.4-1.bbappend @@ -3,9 +3,14 @@ LICENSE = "BSD-3-Clause" -inherit ${@bb.utils.contains('BBFILE_COLLECTIONS', 'qt5-layer', 'cmake_qt5', '', d)} +inherit python3targetconfig + +inherit qmake5_base + +export SIP_PROJECT_INCLUDE_DIRS="${STAGING_DIR_TARGET}/${PYTHON_SITEPACKAGES_DIR}/PyQt5/bindings" -inherit python3native +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +SRC_URI += "file://use-cmake-target-libraries.patch" # This is needed to set OE_QMAKE_PATH_EXTERNAL_HOST_BINS to resolve: # | -- Found PythonLibs: ros2-foxy-dunfell/tmp-glibc/work/core2-64-oe-linux/qt-gui-cpp/1.0.8-1-r0/recipe-sysroot/usr/lib/libpython3.8.so (found suitable version "3.8.2", minimum required is "3.8") @@ -17,11 +22,11 @@ inherit python3native # | # | CMake Error at src/qt_gui_cpp/CMakeLists.txt:35 (qt5_wrap_cpp): # | Unknown CMake command "qt5_wrap_cpp". -inherit ${@bb.utils.contains_any('ROS_WORLD_SKIP_GROUPS', ['qt5', 'pyqt5'], '', 'cmake_qt5', d)} +inherit ${@bb.utils.contains('BBFILE_COLLECTIONS', 'qt5-layer', 'cmake_qt5', '', d)} # | CMake Warning at ros2-foxy-dunfell/tmp-glibc/work/core2-64-oe-linux/qt-gui-cpp/1.0.8-1-r0/recipe-sysroot/usr/share/python_qt_binding/cmake/sip_helper.cmake:27 (message): # | SIP binding generator NOT available. -DEPENDS += "python3-pyqt5-native sip3-native" +DEPENDS += "python3-pyqt5-native python3-pyqt5-sip-native sip-native python3" # | CMake Error: # | Running @@ -32,15 +37,3 @@ DEPENDS += "python3-pyqt5-native sip3-native" # This is caused by sip_helper.cmake from python_qt_binding containing a # hard-coded command that violates ninja syntax: cd && $(MAKE) OECMAKE_GENERATOR = "Unix Makefiles" - -do_compile:prepend () { - cp ${STAGING_LIBDIR}/${PYTHON_DIR}${PYTHON_ABI}/site-packages/sipconfig.py ${STAGING_DATADIR}/python_qt_binding/cmake/ - sed -i -e "s|--sysroot |--sysroot ${STAGING_DIR_TARGET}|g" ${STAGING_DATADIR}/python_qt_binding/cmake/sipconfig.py - sed -i -e "s|--sysroot=[^ ']*|--sysroot=${STAGING_DIR_TARGET}|g" ${STAGING_DATADIR}/python_qt_binding/cmake/sipconfig.py - sed -i -e "s|\('[a-z_]*_dir': *'\)\([^']*',\)|\1${STAGING_DIR_TARGET}\2|g" ${STAGING_DATADIR}/python_qt_binding/cmake/sipconfig.py - sed -i -e "s|\('sip_bin': *'\)\(/usr/bin/sip',\)|\1${STAGING_DIR_NATIVE}\2|" ${STAGING_DATADIR}/python_qt_binding/cmake/sipconfig.py -} - -do_install:append () { - chrpath --delete ${D}${libdir}/${PYTHON_DIR}/site-packages/qt_gui_cpp/libqt_gui_cpp_sip.so -} diff --git a/meta-ros2-rolling/recipes-bbappends/ros2-canopen/canopen-interfaces_0.2.9-1.bbappend b/meta-ros2-rolling/recipes-bbappends/ros2-canopen/canopen-interfaces_0.2.9-1.bbappend index ca1e8ce7382..59364420eab 100644 --- a/meta-ros2-rolling/recipes-bbappends/ros2-canopen/canopen-interfaces_0.2.9-1.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/ros2-canopen/canopen-interfaces_0.2.9-1.bbappend @@ -25,5 +25,8 @@ ROS_EXEC_DEPENDS += " \ rosidl-typesupport-fastrtps-cpp \ rosidl-typesupport-introspection-c \ rosidl-typesupport-introspection-cpp \ +" + +ROS_BUILD_DEPENDS += " \ service-msgs \ " diff --git a/meta-ros2-rolling/recipes-bbappends/ros2-canopen/lely-core-libraries/repackage-lely-core.patch b/meta-ros2-rolling/recipes-bbappends/ros2-canopen/lely-core-libraries/repackage-lely-core.patch index 33e30500c24..c13ffb6d573 100644 --- a/meta-ros2-rolling/recipes-bbappends/ros2-canopen/lely-core-libraries/repackage-lely-core.patch +++ b/meta-ros2-rolling/recipes-bbappends/ros2-canopen/lely-core-libraries/repackage-lely-core.patch @@ -13,7 +13,7 @@ Index: git/CMakeLists.txt - INSTALL_DIR "${CMAKE_INSTALL_PREFIX}" # Installation prefix - BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/build - GIT_REPOSITORY https://gitlab.com/lely_industries/lely-core.git -- GIT_TAG 7824cbb2ac08d091c4fa2fb397669b938de9e3f5 +- GIT_TAG b63a0b6f79d3ea91dc221724b42dae49894449fc - TIMEOUT 60 - #UPDATE step apply patch to fix dcf-tools install - UPDATE_COMMAND diff --git a/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue-and-concurren.patch b/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue.patch similarity index 53% rename from meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue-and-concurren.patch rename to meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue.patch index 5254ae444b4..1465d12f936 100644 --- a/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue-and-concurren.patch +++ b/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor/0001-CMakeLists.txt-fetch-readerwriterqueue.patch @@ -1,7 +1,9 @@ +Signed-off-by: Rob Woolley + From 10a0f06654b5db1dca9521a97128d3f375a4b283 Mon Sep 17 00:00:00 2001 From: Martin Jansa Date: Fri, 27 Nov 2020 09:12:58 -0800 -Subject: [PATCH] CMakeLists.txt: fetch readerwriterqueue and concurrentqueue +Subject: [PATCH] CMakeLists.txt: fetch readerwriterqueue with bitbake fetcher Upstream-Status: Pending @@ -11,11 +13,11 @@ Signed-off-by: Martin Jansa CMakeLists.txt | 20 ++++++-------------- 1 file changed, 6 insertions(+), 14 deletions(-) -diff --git a/CMakeLists.txt b/CMakeLists.txt -index 0daf4672..465367f2 100644 ---- a/CMakeLists.txt -+++ b/CMakeLists.txt -@@ -6,11 +6,7 @@ find_package(ament_cmake REQUIRED) +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -11,11 +11,7 @@ endif() include(ExternalProject) # Single producer single consumer queue by moodycamel - header only, don't build, install ExternalProject_Add(ext-singleproducerconsumer @@ -28,31 +30,14 @@ index 0daf4672..465367f2 100644 INSTALL_DIR ${CMAKE_CURRENT_BINARY_DIR} CONFIGURE_COMMAND "" BUILD_COMMAND "" -@@ -19,11 +15,7 @@ ExternalProject_Add(ext-singleproducerconsumer - - # Concurrent and blocking concurrent queue by moodycamel - header only, don't build, install - ExternalProject_Add(ext-concurrentqueue -- PREFIX concurrentqueue -- DOWNLOAD_DIR ${CMAKE_CURRENT_BINARY_DIR}/download -- URL https://github.com/cameron314/concurrentqueue/archive/8f65a8734d77c3cc00d74c0532efca872931d3ce.zip -- URL_MD5 71a0d932cc89150c2ade85f0d9cac9dc -- TIMEOUT 60 -+ SOURCE_DIR ${PROJECT_SOURCE_DIR}/concurrentqueue-upstream - INSTALL_DIR ${CMAKE_CURRENT_BINARY_DIR} - CONFIGURE_COMMAND "" - BUILD_COMMAND "" -@@ -45,10 +37,10 @@ install( +@@ -34,8 +30,8 @@ install( # Install headers install( FILES - "${CMAKE_CURRENT_BINARY_DIR}/singleproducerconsumer/src/ext-singleproducerconsumer/atomicops.h" - "${CMAKE_CURRENT_BINARY_DIR}/singleproducerconsumer/src/ext-singleproducerconsumer/readerwriterqueue.h" -- "${CMAKE_CURRENT_BINARY_DIR}/concurrentqueue/src/ext-concurrentqueue/concurrentqueue.h" -- "${CMAKE_CURRENT_BINARY_DIR}/concurrentqueue/src/ext-concurrentqueue/blockingconcurrentqueue.h" + "${PROJECT_SOURCE_DIR}/singleproducerconsumer-upstream/atomicops.h" + "${PROJECT_SOURCE_DIR}/singleproducerconsumer-upstream/readerwriterqueue.h" -+ "${PROJECT_SOURCE_DIR}/concurrentqueue-upstream/concurrentqueue.h" -+ "${PROJECT_SOURCE_DIR}/concurrentqueue-upstream/blockingconcurrentqueue.h" DESTINATION ${CMAKE_INSTALL_PREFIX}/include/moodycamel ) diff --git a/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor_0.26.1-1.bbappend b/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor_0.26.1-1.bbappend index 6a9c78fa9a7..6f7d5f874c2 100644 --- a/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor_0.26.1-1.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/rosbag2/shared-queues-vendor_0.26.1-1.bbappend @@ -2,17 +2,14 @@ # Instead of fetching # https://github.com/cameron314/readerwriterqueue/archive/ef7dfbf553288064347d51b8ac335f1ca489032a.zip -# https://github.com/cameron314/concurrentqueue/archive/8f65a8734d77c3cc00d74c0532efca872931d3ce.zip # with curl during do_compile use bitbake git fetcher FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" SRC_URI = " \ git://github.com/ros2-gbp/rosbag2-release;name=release;${ROS_BRANCH};protocol=https \ - file://0001-CMakeLists.txt-fetch-readerwriterqueue-and-concurren.patch \ + file://0001-CMakeLists.txt-fetch-readerwriterqueue.patch \ git://github.com/cameron314/readerwriterqueue.git;protocol=https;name=singleproducerconsumer-upstream;destsuffix=git/singleproducerconsumer-upstream;branch=master \ - git://github.com/cameron314/concurrentqueue.git;protocol=https;name=concurrentqueue-upstream;destsuffix=git/concurrentqueue-upstream;branch=master \ " -SRCREV_release = "dc17fed08353f30a7e20676df7c8fc5e842ed011" +SRCREV_release = "2d211121749c26978f1957f8fa0351c243bb2347" SRCREV_singleproducerconsumer-upstream = "ef7dfbf553288064347d51b8ac335f1ca489032a" -SRCREV_concurrentqueue-upstream = "8f65a8734d77c3cc00d74c0532efca872931d3ce" -SRCREV_FORMAT = "release_singleproducerconsumer-upstream_concurrentqueue-upstream" +SRCREV_FORMAT = "release_singleproducerconsumer-upstream" diff --git a/meta-ros2-rolling/recipes-bbappends/rqt/rqt-gui_%.bbappend b/meta-ros2-rolling/recipes-bbappends/rqt/rqt-gui_%.bbappend index 5c360dbe24b..fa306126f7f 100644 --- a/meta-ros2-rolling/recipes-bbappends/rqt/rqt-gui_%.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/rqt/rqt-gui_%.bbappend @@ -1 +1,3 @@ LICENSE = "BSD-3-Clause" + +FILES:${PN} += "${datadir}/lib/rqt_gui/rqt_gui" diff --git a/meta-ros2-rolling/recipes-bbappends/rsl/rsl/Disable-compiler-warnings-by-default.patch b/meta-ros2-rolling/recipes-bbappends/rsl/rsl/Disable-compiler-warnings-by-default.patch new file mode 100644 index 00000000000..13514ebf718 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/rsl/rsl/Disable-compiler-warnings-by-default.patch @@ -0,0 +1,43 @@ +From a6803dc717c40978607484e0ab4cda4a7aa2e5f7 Mon Sep 17 00:00:00 2001 +From: Chris Thrasher +Date: Thu, 15 Feb 2024 11:40:21 -0700 +Subject: [PATCH] Disable compiler warnings by default + +Unconditionally enabling -Werror is a heavy-handed approach and not +ideal when shipping code to be used by many third parties. In fact +it's even better to disable warnings by default since compiler +warnings are not hard requirements. They're merely a development +tool that developers should opt into. +--- + CMakeLists.txt | 3 ++- + CMakePresets.json | 3 ++- + 2 files changed, 4 insertions(+), 2 deletions(-) + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 6d47b08..b800e66 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -9,7 +9,8 @@ find_package(rclcpp REQUIRED) + find_package(tcb_span REQUIRED) + find_package(tl_expected REQUIRED) + +-if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") ++option(RSL_ENABLE_WARNINGS "Enable compiler warnings" OFF) ++if(RSL_ENABLE_WARNINGS AND CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Werror -Wall -Wextra -Wpedantic -Wshadow -Wconversion -Wsign-conversion -Wold-style-cast) + endif() + +diff --git a/CMakePresets.json b/CMakePresets.json +index c7565ae..2d35c1f 100644 +--- a/CMakePresets.json ++++ b/CMakePresets.json +@@ -18,7 +18,8 @@ + "CMAKE_EXE_LINKER_FLAGS": "-fuse-ld=lld", + "CMAKE_MODULE_LINKER_FLAGS": "-fuse-ld=lld", + "CMAKE_SHARED_LINKER_FLAGS": "-fuse-ld=lld", +- "RSL_BUILD_TESTING": "ON" ++ "RSL_BUILD_TESTING": "ON", ++ "RSL_ENABLE_WARNINGS": "ON" + }, + "warnings": { + "unusedCli": false diff --git a/meta-ros2-rolling/recipes-bbappends/rsl/rsl_1.1.0-2.bbappend b/meta-ros2-rolling/recipes-bbappends/rsl/rsl_1.1.0-2.bbappend index f56f6f5397e..25a25439955 100644 --- a/meta-ros2-rolling/recipes-bbappends/rsl/rsl_1.1.0-2.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/rsl/rsl_1.1.0-2.bbappend @@ -1,34 +1,8 @@ -# Copyright (c) 2022 Wind River Systems, Inc. +# Copyright (c) 2024 Wind River Systems, Inc. -# error: conversion to 'int' from 'unsigned int' may change the sign of the result [-Werror=sign-conversion] -# error: conversion to 'long long int' from 'uint64_t' {aka 'long unsigned int'} may change the sign of the result [-Werror=sign-conversion] -# error: conversion to 'long unsigned int' from 'int' may change the sign of the result [-Werror=sign-conversion] -# error: conversion to 'std::__cxx11::basic_string::size_type' {aka 'long unsigned int'} from 'int' may change the sign of the result [-Werror=sign-conversion] -# error: conversion to 'unsigned int' from 'int' may change the sign of the result [-Werror=sign-conversion] -# error: signed conversion from 'unsigned int' to 'int' changes value from '2147483648' to '-2147483648' [-Werror=sign-conversion] -# error: signed conversion from 'unsigned int' to 'int' changes value from '4294967295' to '-1' [-Werror=sign-conversion] -# error: use of old-style cast to 'const double*' [-Werror=old-style-cast] -# error: use of old-style cast to 'const Scalar*' [-Werror=old-style-cast] -#error: use of old-style cast to 'const typename Eigen::internal::unpacket_traits::type*' [-Werror=old-style-cast] -# error: use of old-style cast to 'const typename Eigen::internal::unpacket_traits, std::complex<_Tp>, _ConjLhs, _ConjRhs, Arch, _PacketSize>::Vectorizable, typename Eigen::internal::packet_conditional<_PacketSize, typename Eigen::internal::packet_traits::type, typename Eigen::internal::packet_traits::half, typename Eigen::internal::unpacket_traits::half>::half>::type, std::complex<_Tp> >::type>::type*' [-Werror=old-style-cast] -# error: use of old-style cast to 'double*' [-Werror=old-style-cast] -# error: use of old-style cast to 'Eigen::internal::SsePrefetchPtrType' {aka 'const char*'} [-Werror=old-style-cast] -# error: use of old-style cast to 'enum Eigen::TransformTraits' [-Werror=old-style-cast] -# error: use of old-style cast to 'int' [-Werror=old-style-cast] -# error: use of old-style cast to 'LinearMatrixType*' [-Werror=old-style-cast] -# error: use of old-style cast to '__m64*' [-Werror=old-style-cast] -# error: use of old-style cast to 'Scalar*' [-Werror=old-style-cast] -# error: use of old-style cast to 'unsigned int' [-Werror=old-style-cast] -CFLAGS += "-Wno-error=sign-conversion -Wno-error=old-style-cast" -CXXFLAGS += "-Wno-error=sign-conversion -Wno-error=old-style-cast" +ROS_BUILDTOOL_DEPENDS += " \ + rosidl-default-runtime-native \ +" -# error declaration of 'error_msg' shadows a member of 'rclcpp::exceptions::InvalidNodeNameError' [-Werror=shadow] -# error declaration of 'invalid_index' shadows a member of 'rclcpp::exceptions::InvalidNodeNameError' [-Werror=shadow] -# error declaration of 'error_msg' shadows a member of 'rclcpp::exceptions::InvalidNamespaceError' [-Werror=shadow] -# error declaration of 'invalid_index' shadows a member of 'rclcpp::exceptions::InvalidNamespaceError' [-Werror=shadow] -# error declaration of 'error_msg' shadows a member of 'rclcpp::exceptions::InvalidTopicNameError' [-Werror=shadow] -# error declaration of 'invalid_index' shadows a member of 'rclcpp::exceptions::InvalidTopicNameError' [-Werror=shadow] -# error declaration of 'error_msg' shadows a member of 'rclcpp::exceptions::InvalidServiceNameError' [-Werror=shadow] -# error declaration of 'invalid_index' shadows a member of 'rclcpp::exceptions::InvalidServiceNameError' [-Werror=shadow] -CFLAGS += "-Wno-error=shadow" -CXXFLAGS += "-Wno-error=shadow" +FILESEXTRAPATHS:prepend := "${THISDIR}/${BPN}:" +SRC_URI += "file://Disable-compiler-warnings-by-default.patch" diff --git a/meta-ros2-rolling/recipes-bbappends/rviz/rviz-ogre-vendor/0001-CMakeLists-remove-all-ament_vendor-calls.patch b/meta-ros2-rolling/recipes-bbappends/rviz/rviz-ogre-vendor/0001-CMakeLists-remove-all-ament_vendor-calls.patch index 39eba151cb0..6fcee07b027 100644 --- a/meta-ros2-rolling/recipes-bbappends/rviz/rviz-ogre-vendor/0001-CMakeLists-remove-all-ament_vendor-calls.patch +++ b/meta-ros2-rolling/recipes-bbappends/rviz/rviz-ogre-vendor/0001-CMakeLists-remove-all-ament_vendor-calls.patch @@ -7,7 +7,7 @@ Index: git/CMakeLists.txt =================================================================== --- git.orig/CMakeLists.txt +++ git/CMakeLists.txt -@@ -4,115 +4,12 @@ project(rviz_ogre_vendor) +@@ -4,122 +4,12 @@ project(rviz_ogre_vendor) find_package(ament_cmake REQUIRED) find_package(ament_cmake_vendor_package REQUIRED) @@ -66,6 +66,8 @@ Index: git/CMakeLists.txt - set(OGRE_CXX_FLAGS "-Wno-mismatched-new-delete ${OGRE_CXX_FLAGS}") - set(OGRE_CXX_FLAGS "-Wno-range-loop-construct ${OGRE_CXX_FLAGS}") - set(OGRE_CXX_FLAGS "-Wno-undef ${OGRE_CXX_FLAGS}") +- set(OGRE_CXX_FLAGS "-Wno-misleading-indentation ${OGRE_CXX_FLAGS}") +- set(OGRE_CXX_FLAGS "-Wno-implicit-const-int-float-conversion ${OGRE_CXX_FLAGS}") - - if(NOT CMAKE_CXX_COMPILER_ID MATCHES "Clang") - set(OGRE_CXX_FLAGS "-Wno-maybe-uninitialized ${OGRE_CXX_FLAGS}") @@ -80,6 +82,11 @@ Index: git/CMakeLists.txt - list(APPEND OGRE_CMAKE_ARGS -DCMAKE_SKIP_INSTALL_RPATH:BOOL=ON) -endif() - +-if(APPLE) +- list(APPEND OGRE_CMAKE_ARGS -DOGRE_ENABLE_PRECOMPILED_HEADERS:BOOL=OFF) +- list(APPEND OGRE_CMAKE_ARGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64) +-endif() +- -ament_vendor(ogre_vendor - VCS_URL https://github.com/OGRECave/ogre.git - VCS_VERSION v1.12.10 diff --git a/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor/0001-Use-platform-yaml-cpp.patch b/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor/0001-Use-platform-yaml-cpp.patch new file mode 100644 index 00000000000..bc5dd9d2330 --- /dev/null +++ b/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor/0001-Use-platform-yaml-cpp.patch @@ -0,0 +1,104 @@ +From da4fad4eca3ecd54d3cf02e47168791651df439f Mon Sep 17 00:00:00 2001 +From: Herb Kuta +Date: Tue, 31 Dec 2019 10:17:22 -0800 +Subject: [PATCH] Use platform yaml-cpp + +Upstream-Status: Pending + +--- + CMakeLists.txt | 79 ++++---------------------------------------------- + 1 file changed, 6 insertions(+), 73 deletions(-) + +Index: git/CMakeLists.txt +=================================================================== +--- git.orig/CMakeLists.txt ++++ git/CMakeLists.txt +@@ -14,82 +14,13 @@ if (POLICY CMP0135) + cmake_policy(SET CMP0135 NEW) + endif() + +-macro(build_yaml_cpp) +- set(extra_cmake_args) +- +- if(DEFINED CMAKE_BUILD_TYPE) +- list(APPEND extra_cmake_args -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}) +- endif() +- if(NOT WIN32) +- set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -w") +- set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -w") +- endif() +- +- list(APPEND extra_cmake_args "-DYAML_CPP_BUILD_TESTS=OFF") +- list(APPEND extra_cmake_args "-DYAML_CPP_BUILD_TOOLS=OFF") +- list(APPEND extra_cmake_args "-DYAML_CPP_BUILD_CONTRIB=OFF") +- if(BUILD_SHARED_LIBS) +- list(APPEND extra_cmake_args "-DYAML_BUILD_SHARED_LIBS=ON") +- endif() +- list(APPEND extra_cmake_args "-DCMAKE_CXX_COMPILER=${CMAKE_CXX_COMPILER}") +- list(APPEND extra_cmake_args "-DCMAKE_CXX_FLAGS=${CMAKE_CXX_FLAGS}") +- +- if(WIN32 AND NOT ${CMAKE_VERBOSE_MAKEFILE}) +- set(should_log ON) # prevent warnings in Windows CI +- else() +- set(should_log OFF) +- endif() +- +- if(DEFINED CMAKE_TOOLCHAIN_FILE) +- list(APPEND extra_cmake_args "-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}") +- endif() +- +- include(ExternalProject) +- ExternalProject_Add(yaml_cpp-0.7.0 +- URL https://github.com/jbeder/yaml-cpp/archive/yaml-cpp-0.7.0.tar.gz +- URL_MD5 74d646a3cc1b5d519829441db96744f0 +- TIMEOUT 600 +- LOG_CONFIGURE ${should_log} +- LOG_BUILD ${should_log} +- CMAKE_ARGS +- -DCMAKE_INSTALL_PREFIX=${CMAKE_CURRENT_BINARY_DIR}/yaml_cpp_install +- ${extra_cmake_args} +- -Wno-dev +- ) +- +- # The external project will install to the build folder, but we'll install that on make install. +- install( +- DIRECTORY +- ${CMAKE_CURRENT_BINARY_DIR}/yaml_cpp_install/ +- DESTINATION +- ${CMAKE_INSTALL_PREFIX}/opt/yaml_cpp_vendor +- USE_SOURCE_PERMISSIONS +- ) +-endmacro() +- +-# NO_CMAKE_PACKAGE_REGISTRY used to avoid finding the library downloaded in WORKSPACE B +-# when building workspace A. +-# This should only find a system installed yaml-cpp and thus the environment hook isn't needed. +-find_package(yaml-cpp QUIET NO_CMAKE_PACKAGE_REGISTRY) +-if(FORCE_BUILD_VENDOR_PKG OR NOT yaml-cpp_FOUND) +- build_yaml_cpp() +- +- if(WIN32) +- ament_environment_hooks(env_hook/yaml_cpp_vendor_library_path.bat) +- set(ENV_VAR_NAME "PATH") +- set(ENV_VAR_VALUE "opt\\yaml_cpp_vendor\\bin") +- else() +- ament_environment_hooks(env_hook/yaml_cpp_vendor_library_path.sh) +- if(APPLE) +- set(ENV_VAR_NAME "DYLD_LIBRARY_PATH") +- else() +- set(ENV_VAR_NAME "LD_LIBRARY_PATH") +- endif() +- set(ENV_VAR_VALUE "opt/yaml_cpp_vendor/lib") +- endif() +- ament_environment_hooks(env_hook/yaml_cpp_vendor_library_path.dsv.in) ++# We arrange for the platform yaml-cpp to be built from the same commit as that from which the ExternalProject is built => no ++# invocation of ament_environment_hooks(). ++find_package(yaml-cpp) ++if(yaml-cpp_FOUND) ++ message(STATUS "Found yaml-cpp ${yaml-cpp_VERSION}") + else() +- message(STATUS "Found yaml-cpp ${yaml-cpp_VERSION} in path ${yaml-cpp_CONFIG}") ++ message(FATAL_ERROR "yaml-cpp not found -- missing from DEPENDS?") + endif() + + ament_package( diff --git a/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor_%.bbappend b/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor_%.bbappend index 3d06757d62a..99719c427e2 100644 --- a/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor_%.bbappend +++ b/meta-ros2-rolling/recipes-bbappends/yaml-cpp-vendor/yaml-cpp-vendor_%.bbappend @@ -1,3 +1,7 @@ # Copyright (c) 2019-2020 LG Electronics, Inc. DESCRIPTION = "Wrapper around yaml-cpp, it provides a fixed CMake module." + +# We arrange for the platform yaml-cpp to be built from the same commit as that from which the ExternalProject is built. If the +# commit changes, the patch will not apply cleanly and we'll know we need to update the .bbappend for yaml-cpp. +DEPENDS += "yaml-cpp" diff --git a/meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.13.20230224.bb b/meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.19.20240304.bb similarity index 76% rename from meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.13.20230224.bb rename to meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.19.20240304.bb index e9b32749d10..a81f9ff6901 100644 --- a/meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.13.20230224.bb +++ b/meta-ros2-rolling/recipes-devtools/libphidget22/libphidget22-upstream_1.19.20240304.bb @@ -12,13 +12,10 @@ DEPENDS = "libusb1" SRCNAME = "libphidget22" -SRC_URI = "https://www.phidgets.com/downloads/phidget22/libraries/linux/${SRCNAME}/${SRCNAME}-${PV}.tar.gz \ - https://raw.githubusercontent.com/ros-drivers/phidgets_drivers/rolling/libphidget22/patch/libphidget22-1.13.20230224-fix-warnings.patch;name=patch \ -" +SRC_URI = "https://www.phidgets.com/downloads/phidget22/libraries/linux/${SRCNAME}/${SRCNAME}-${PV}.tar.gz" S = "${WORKDIR}/${SRCNAME}-${PV}" -SRC_URI[sha256sum] = "1d0795110517eb18c806472887cafc861dd0b6a1c1045246c555bc47f6bd77e3" -SRC_URI[patch.sha256sum] = "f72814e010526ec8affaff2886dc69f4d5dad4f34e562ff01ddcd69e44987081" +SRC_URI[sha256sum] = "1a9cc6329434dacfd7fd711c1a8a33ccc8e282b6eabc0bbcd5b71bed01bedfa1" inherit autotools diff --git a/meta-ros2-rolling/recipes-support/lely-core/lely-core_2.3.2.bb b/meta-ros2-rolling/recipes-support/lely-core/lely-core_2.3.2.bb index 878ce540a3d..c8ff8be6237 100644 --- a/meta-ros2-rolling/recipes-support/lely-core/lely-core_2.3.2.bb +++ b/meta-ros2-rolling/recipes-support/lely-core/lely-core_2.3.2.bb @@ -17,6 +17,10 @@ DEPENDS += "python3-setuptools-native python3-wheel-native" EXTRA_OECONF += " --disable-cython --disable-tests --disable-python2" +# include/lely/coapp/device.hpp:1003:3: error: 'virtual void lely::canopen::Device::OnWrite(uint16_t, uint8_t)' was hidden [-Werror=overloaded-virtual=] +CXXFLAGS += "-Wno-error=overloaded-virtual" + + PACKAGES =+ " \ liblely-can \ liblely-can1 \ diff --git a/meta-ros2/recipes-benchmark/google-benchmark/google-benchmark_git.bb b/meta-ros2/recipes-benchmark/google-benchmark/google-benchmark_git.bb index 54d4cd063d9..2463446919d 100644 --- a/meta-ros2/recipes-benchmark/google-benchmark/google-benchmark_git.bb +++ b/meta-ros2/recipes-benchmark/google-benchmark/google-benchmark_git.bb @@ -6,10 +6,10 @@ SECTION = "devel" LICENSE = "Apache-2.0" LIC_FILES_CHKSUM = "file://LICENSE;md5=3b83ef96387f14655fc854ddc3c6bd57" -PV = "1.7.0+git${SRCPV}" +PV = "1.8.3" -# matches with tag 1.7.0 -SRCREV = "361e8d1cfe0c6c36d30b39f1b61302ece5507320" +# matches with tag 1.8.3 +SRCREV = "344117638c8ff7e239044fd0fa7085839fc03021" SRC_URI = "git://github.com/google/benchmark;branch=main;protocol=https" S = "${WORKDIR}/git" diff --git a/meta-ros2/recipes-devtools/python/python3-flask-cors_4.0.0.bb b/meta-ros2/recipes-devtools/python/python3-flask-cors_4.0.0.bb new file mode 100644 index 00000000000..ddac48930a0 --- /dev/null +++ b/meta-ros2/recipes-devtools/python/python3-flask-cors_4.0.0.bb @@ -0,0 +1,29 @@ +SUMMARY = "Cross Origin Resource Sharing ( CORS ) support for Flask" +HOMEPAGE = "https://github.com/corydolphin/flask-cors" +DESCRIPTION = "Cross Origin Resource Sharing ( CORS ) support for Flask" +SECTION = "devel/python" +LICENSE = "MIT" +LIC_FILES_CHKSUM = "file://LICENSE;md5=118fecaa576ab51c1520f95e98db61ce" + +SRC_URI[sha256sum] = "f268522fcb2f73e2ecdde1ef45e2fd5c71cc48fe03cffb4b441c6d1b40684eb0" + +PYPI_PACKAGE = "Flask-Cors" + +inherit pypi +inherit setuptools3 + +S = "${WORKDIR}/Flask-Cors-${PV}" + +do_configure:prepend() { +cat > ${S}/setup.py <<-EOF +from setuptools import setup + +setup( + name="${PYPI_PACKAGE}", + version="${PV}", + license="${LICENSE}", +) +EOF +} + +BBCLASSEXTEND = "native nativesdk" diff --git a/meta-ros2/recipes-graphics/nanogui/nanogui/0001-set-nanobind-dir.patch b/meta-ros2/recipes-graphics/nanogui/nanogui/0001-set-nanobind-dir.patch new file mode 100644 index 00000000000..6270b3fe9ce --- /dev/null +++ b/meta-ros2/recipes-graphics/nanogui/nanogui/0001-set-nanobind-dir.patch @@ -0,0 +1,10 @@ +--- a/ext/nanobind/CMakeLists.txt ++++ b/ext/nanobind/CMakeLists.txt +@@ -129,6 +129,7 @@ + # Include nanobind cmake functionality + # --------------------------------------------------------------------------- + ++set(nanobind_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") + find_package(nanobind + PATHS ${CMAKE_CURRENT_SOURCE_DIR}/cmake + NO_DEFAULT_PATH) diff --git a/meta-ros2/recipes-graphics/nanogui/nanogui_git.bb b/meta-ros2/recipes-graphics/nanogui/nanogui_git.bb new file mode 100644 index 00000000000..25c81d011a9 --- /dev/null +++ b/meta-ros2/recipes-graphics/nanogui/nanogui_git.bb @@ -0,0 +1,46 @@ +DESCRIPTION = "Minimalistic C++/Python GUI library for OpenGL, GLES2/3, Metal, and WebAssembly/WebGL" +HOMEPAGE = "https://github.com/mitsuba-renderer/nanogui" +LICENSE = "BSD-3-Clause" +LIC_FILES_CHKSUM = "file://LICENSE.txt;md5=cea9322f8f8f3489fa38b53cf3c03983" + +DEPENDS = "glfw python3" + +S = "${WORKDIR}/git" + +SRC_URI = " \ + git://github.com/mitsuba-renderer/nanogui.git;name=nanogui;protocol=https;branch=master \ + git://github.com/wjakob/nanovg.git;name=nanovg;protocol=https;branch=master;destsuffix=git/ext/nanovg \ + git://github.com/wjakob/nanovg_metal.git;name=nanovg-metal;protocol=https;branch=master;destsuffix=git/ext/nanovg_metal \ + git://github.com/wjakob/nanobind.git;name=nanobind;protocol=https;branch=master;destsuffix=git/ext/nanobind \ + git://github.com/wjakob/glfw.git;name=glfw;protocol=https;branch=master;destsuffix=git/ext/glfw \ + git://github.com/Tessil/robin-map.git;name=robin-map;protocol=https;branch=master;destsuffix=git/ext/nanobind/ext/robin_map \ + file://0001-set-nanobind-dir.patch \ +" +SRCREV_nanogui = "2ee903c96480d4aee54542ea3c340c13cc06dc32" +SRCREV_nanovg = "7acc5d509f70e038d9229753d4b0f20e77e7f279" +SRCREV_nanovg-metal = "075b04f16c579728c693b46a2ce408f2325968cf" +SRCREV_nanobind = "ea2569f705b9d12185eea67db399a373d37c75aa" +SRCREV_glfw = "e130e55a990998c78fd323f21076e798e0efe8a4" +SRCREV_robin-map = "5eace6f74c9edff8e264c2d26a85365ad9ea149c" +SRCREV_FORMAT = "nanogui-nanvg-nanovg-metal-nanobind-glfw_robin-map" + +FILES:${PN} += " \ + ${libdir}/nanogui_ext.cpython-310-x86_64-linux-gnu.so \ + ${libdir}/libnanogui.so \ + ${datadir}/fonts/truetype/fonts-entypo/entypo.ttf \ +" +FILES:${PN}-dev = "${includedir} ${datadir}/cmake" + +do_install:append () { + rm ${D}${includedir}/GLFW/* + + install -d ${D}${datadir}/fonts/truetype/fonts-entypo + install -m 0600 ${S}/docs/_static/entypo.ttf ${D}${datadir}/fonts/truetype/fonts-entypo +#./git/resources/Roboto-Regular.ttf +#./git/resources/FontAwesome-Solid.ttf +#./git/resources/Roboto-Bold.ttf +#./git/resources/Inconsolata-Regular.ttf +} + +INSANE_SKIP:${PN} += "already-stripped" +inherit cmake python3native diff --git a/meta-ros2/recipes-python/pyqt5/python3-pyqt5-sip_%.bbappend b/meta-ros2/recipes-python/pyqt5/python3-pyqt5-sip_%.bbappend new file mode 100644 index 00000000000..03ff91738f8 --- /dev/null +++ b/meta-ros2/recipes-python/pyqt5/python3-pyqt5-sip_%.bbappend @@ -0,0 +1 @@ +BBCLASSEXTEND="native nativesdk" diff --git a/meta-ros2/recipes-python/pyqt5/python3-pyqt5_%.bbappend b/meta-ros2/recipes-python/pyqt5/python3-pyqt5_%.bbappend new file mode 100644 index 00000000000..03ff91738f8 --- /dev/null +++ b/meta-ros2/recipes-python/pyqt5/python3-pyqt5_%.bbappend @@ -0,0 +1 @@ +BBCLASSEXTEND="native nativesdk" diff --git a/meta-ros2/recipes-support/libfyaml/libfyaml_0.9.bb b/meta-ros2/recipes-support/libfyaml/libfyaml_0.9.bb new file mode 100644 index 00000000000..e3433ff69e2 --- /dev/null +++ b/meta-ros2/recipes-support/libfyaml/libfyaml_0.9.bb @@ -0,0 +1,12 @@ +DESCRIPTION = "Fully feature complete YAML parser and emitter, supporting the latest YAML spec and passing the full YAML testsuite." +HOMEPAGE = "https://github.com/pantoniou/libfyaml" +LICENSE = "MIT" +LIC_FILES_CHKSUM = "file://LICENSE;md5=6399094fbc639a289cfca2d660c010aa" + +SRC_URI = "git://github.com/pantoniou/libfyaml.git;protocol=https;branch=master" +SRCREV = "8054c66e0454a09a810f756996d1b280738594e5" + +S = "${WORKDIR}/git" + +inherit autotools pkgconfig + diff --git a/meta-ros2/recipes-support/openni2/openni2/glx-remove-dead-declarations.patch b/meta-ros2/recipes-support/openni2/openni2/glx-remove-dead-declarations.patch new file mode 100644 index 00000000000..03d884c19bb --- /dev/null +++ b/meta-ros2/recipes-support/openni2/openni2/glx-remove-dead-declarations.patch @@ -0,0 +1,66 @@ +This corresponds to changes done in Mesa: + +glx: Remove dead declarations from + +https://gitlab.freedesktop.org/mesa/mesa/-/commit/cc93f08f1e3e84f09cb2bb587d6de702dc836478.patch + +Signed-off-by: Rob Woolley + +diff --git a/ThirdParty/GL/glh/glh_genext.h b/ThirdParty/GL/glh/glh_genext.h +index 275c61d..cddc40d 100644 +--- a/ThirdParty/GL/glh/glh_genext.h ++++ b/ThirdParty/GL/glh/glh_genext.h +@@ -843,15 +843,9 @@ extern "C" { + # ifdef _WIN32 + GLH_EXTERN PFNWGLALLOCATEMEMORYNVPROC GLH_EXT_NAME(wglAllocateMemoryNV) GLH_INITIALIZER; + # endif +-# ifdef GLX_VERSION_1_3 +- GLH_EXTERN PFNGLXALLOCATEMEMORYNVPROC GLH_EXT_NAME(glXAllocateMemoryNV) GLH_INITIALIZER; +-# endif + # ifdef _WIN32 + GLH_EXTERN PFNWGLFREEMEMORYNVPROC GLH_EXT_NAME(wglFreeMemoryNV) GLH_INITIALIZER; + # endif +-# ifdef GLX_VERSION_1_3 +- GLH_EXTERN PFNGLXFREEMEMORYNVPROC GLH_EXT_NAME(glXFreeMemoryNV) GLH_INITIALIZER; +-# endif + #endif + + #ifdef GL_NV_vertex_array_range2 +@@ -3775,21 +3769,11 @@ int glh_init_extension(const char* extension) + if (NULL == GLH_EXT_NAME(wglAllocateMemoryNV)) + return GL_FALSE; + # endif +-# ifdef GLX_VERSION_1_3 +- GLH_EXT_NAME(glXAllocateMemoryNV) = (PFNGLXALLOCATEMEMORYNVPROC)GLH_EXT_GET_PROC_ADDRESS("glXAllocateMemoryNV"); +- if (NULL == GLH_EXT_NAME(glXAllocateMemoryNV)) +- return GL_FALSE; +-# endif + # ifdef _WIN32 + GLH_EXT_NAME(wglFreeMemoryNV) = (PFNWGLFREEMEMORYNVPROC)GLH_EXT_GET_PROC_ADDRESS("wglFreeMemoryNV"); + if (NULL == GLH_EXT_NAME(wglFreeMemoryNV)) + return GL_FALSE; + # endif +-# ifdef GLX_VERSION_1_3 +- GLH_EXT_NAME(glXFreeMemoryNV) = (PFNGLXFREEMEMORYNVPROC)GLH_EXT_GET_PROC_ADDRESS("glXFreeMemoryNV"); +- if (NULL == GLH_EXT_NAME(glXFreeMemoryNV)) +- return GL_FALSE; +-# endif + + return GL_TRUE; + } +@@ -5130,15 +5114,9 @@ int glh_init_extension(const char* extension) + # ifdef _WIN32 + #define wglAllocateMemoryNV GLH_EXT_NAME(wglAllocateMemoryNV) + # endif +-# ifdef GLX_VERSION_1_3 +-#define glXAllocateMemoryNV GLH_EXT_NAME(glXAllocateMemoryNV) +-# endif + # ifdef _WIN32 + #define wglFreeMemoryNV GLH_EXT_NAME(wglFreeMemoryNV) + # endif +-# ifdef GLX_VERSION_1_3 +-#define glXFreeMemoryNV GLH_EXT_NAME(glXFreeMemoryNV) +-# endif + #endif + + #ifdef GL_NV_vertex_array_range2 diff --git a/meta-ros2/recipes-support/openni2/openni2_2.2.0.bb b/meta-ros2/recipes-support/openni2/openni2_2.2.0.bb index 5cf1f9f8843..b500858d4bd 100644 --- a/meta-ros2/recipes-support/openni2/openni2_2.2.0.bb +++ b/meta-ros2/recipes-support/openni2/openni2_2.2.0.bb @@ -28,6 +28,7 @@ SRC_URI = " \ file://0018-Don-t-allocate-m_errorBuffer-on-TLS.patch \ file://0018-Fix-javadoc-with-Java-17.patch \ file://0019-fix-stringop-overflow.patch \ + file://glx-remove-dead-declarations.patch \ " SRC_URI[sha256sum] = "abc17f5e30d6799200c69a52d34aefaef4fd567be7921e0cb68cae353ac4495a" diff --git a/scripts/generate-skip-groups.py b/scripts/generate-skip-groups.py new file mode 100755 index 00000000000..bbb2d6cb888 --- /dev/null +++ b/scripts/generate-skip-groups.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 + +import sys +import ast +import pprint + +MISSING_STR = "Missing or unbuildable dependency chain was:" +DEV_SUFFIX = "-dev" +RDEPENDS_STR = "RDEPENDS:${PN}:remove = \"${@bb.utils.contains('ROS_WORLD_SKIP_GROUPS', '%s', '${ROS_SUPERFLORE_GENERATED_WORLD_PACKAGES_DEPENDING_ON_%s}', '', d)}\"" +DEPENDING_ON_STR = "ROS_SUPERFLORE_GENERATED_WORLD_PACKAGES_DEPENDING_ON_%s = \" \\" +UNRESOLVED_STR = "ROS_UNRESOLVED_DEP-" + +def usage(): + print("generate-skip-groups.py ") + +def main(): + if (len(sys.argv) != 2): + usage() + + skip_groups = {} + unresolved = [] + with open(sys.argv[1]) as cooker_log_file: + for line in cooker_log_file: + if line.startswith(MISSING_STR): + chain = line.split(':', 2)[1].rstrip() + x = ast.literal_eval(chain) + + # print(" -> ".join(x)) + # print(x[0], " : ", x[-1]) + + # if either the dependendee or depender is a dev package + if x[0].endswith(DEV_SUFFIX) or x[-1].endswith(DEV_SUFFIX): + continue + + if x[-1] in skip_groups: + # if the missing recipe has been seen already + if x[0] not in skip_groups[x[-1]]: + # add the new depender to the list + skip_groups[x[-1]].append(x[0]) + else: + # if the missing recipe is new + # print("DEBUG: x[0]:%s,x[-1]:%s" % (x[0],x[-1])) + if x[0].startswith(UNRESOLVED_STR): + # print("ERROR: The ROS package could not be resolved %s" % x[0]) + unresolved.append(x[0]) + else: + skip_groups[x[-1]] = [x[0]] + + if (len(unresolved) > 0): + print("ERROR: The following ROS packages could not be resolved in OpenEmbedded:") + for i in unresolved: + print(" ",i.removeprefix(UNRESOLVED_STR)) + exit(-1) + + for dependee, dependers in skip_groups.items(): + print(RDEPENDS_STR % (dependee, dependee.upper())) + print(DEPENDING_ON_STR % dependee.upper()) + dependers.sort() + for depender in dependers: + print(f" %s \\" % depender) + print("\"") + +if __name__ == "__main__": + main()