Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 1 addition & 6 deletions cv_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,7 @@ cmake_minimum_required(VERSION 3.14)
project(cv_bridge)

find_package(ament_cmake_ros REQUIRED)

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
find_package(ament_cmake_ros_core REQUIRED)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra)
Expand Down Expand Up @@ -40,7 +36,6 @@ else()
endif()

find_package(rclcpp REQUIRED)
find_package(rcpputils REQUIRED)
find_package(sensor_msgs REQUIRED)

find_package(OpenCV 4 QUIET
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef CV_BRIDGE__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
#define CV_BRIDGE__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_

#include <bit>
#include <cstddef>
#include <memory>
#include <variant>
Expand All @@ -30,26 +31,6 @@

namespace cv_bridge
{
namespace detail
{
// TODO(audrow): Replace with std::endian when C++ 20 is available
// https://en.cppreference.com/w/cpp/types/endian
enum class endian
{
#ifdef _WIN32
little = 0,
big = 1,
native = little
#else
little = __ORDER_LITTLE_ENDIAN__,
big = __ORDER_BIG_ENDIAN__,
native = __BYTE_ORDER__
#endif
};

} // namespace detail


/// A potentially owning, potentially non-owning, container of a cv::Mat and ROS header.
/**
* The two main use cases for this are publishing user controlled data, and
Expand Down Expand Up @@ -85,7 +66,7 @@ enum class endian
*/
class ROSCvMatContainer
{
static constexpr bool is_bigendian_system = detail::endian::native == detail::endian::big;
static constexpr bool is_bigendian_system = std::endian::native == std::endian::big;

public:
using SensorMsgsImageStorageType = std::variant<
Expand Down
2 changes: 1 addition & 1 deletion cv_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,14 @@

<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>python_cmake_module</buildtool_depend>
<buildtool_depend>ament_cmake_ros_core</buildtool_depend>

<build_depend>libboost-dev</build_depend>
<build_depend>libboost-python-dev</build_depend>

<depend>libopencv-dev</depend>
<depend>python3-numpy</depend>
<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>sensor_msgs</depend>
<depend>python3-opencv</depend>

Expand Down
7 changes: 4 additions & 3 deletions cv_bridge/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
opencv_imgproc
opencv_imgcodecs
rclcpp::rclcpp
ament_cmake_ros_core::ament_ros_defaults
)
target_link_libraries(${PROJECT_NAME} PRIVATE
Boost::headers
rcpputils::rcpputils)
Boost::headers)

install(TARGETS ${PROJECT_NAME} EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
Expand All @@ -36,7 +36,8 @@ if(NOT CV_BRIDGE_DISABLE_PYTHON)
target_link_libraries(${PROJECT_NAME}_boost PRIVATE
${PROJECT_NAME}
${boost_python_target}
Python3::NumPy)
Python3::NumPy
ament_cmake_ros_core::ament_ros_defaults)
target_compile_definitions(${PROJECT_NAME}_boost PRIVATE PYTHON3)

if(OpenCV_VERSION_MAJOR VERSION_EQUAL 4)
Expand Down
10 changes: 5 additions & 5 deletions cv_bridge/src/cv_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include "rcpputils/endian.hpp"

#include <bit>
#include <map>
#include <memory>
#include <regex>
Expand Down Expand Up @@ -299,8 +299,8 @@ cv::Mat matFromImage(const sensor_msgs::msg::Image & source)
cv::Mat mat(source.height, source.width, source_type, const_cast<uchar *>(&source.data[0]),
source.step);

if ((rcpputils::endian::native == rcpputils::endian::big && source.is_bigendian) ||
(rcpputils::endian::native == rcpputils::endian::little && !source.is_bigendian) ||
if ((std::endian::native == std::endian::big && source.is_bigendian) ||
(std::endian::native == std::endian::little && !source.is_bigendian) ||
byte_depth == 1)
{
return mat;
Expand Down Expand Up @@ -392,7 +392,7 @@ void CvImage::toImageMsg(sensor_msgs::msg::Image & ros_image) const
ros_image.height = image.rows;
ros_image.width = image.cols;
ros_image.encoding = encoding;
ros_image.is_bigendian = (rcpputils::endian::native == rcpputils::endian::big);
ros_image.is_bigendian = (std::endian::native == std::endian::big);
ros_image.step = image.cols * image.elemSize();
size_t size = ros_image.step * image.rows;
ros_image.data.resize(size);
Expand Down Expand Up @@ -442,7 +442,7 @@ CvImageConstPtr toCvShare(
{
// If the encoding different or the endianness different, you have to copy
if ((!encoding.empty() && source.encoding != encoding) || (!source.is_bigendian !=
(rcpputils::endian::native != rcpputils::endian::big)))
(std::endian::native != std::endian::big)))
{
return toCvCopy(source, encoding);
}
Expand Down
30 changes: 21 additions & 9 deletions cv_bridge/test/test_endian.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,10 @@
#include <boost/endian/conversion.hpp>
#include <bit>
#include <cv_bridge/cv_bridge.hpp>
#include <gtest/gtest.h>
#include <memory>

TEST(CvBridgeTest, endianness)
{
using namespace boost::endian;

// Create an image of the type opposite to the platform
sensor_msgs::msg::Image msg;
msg.height = 1;
Expand All @@ -15,17 +13,31 @@ TEST(CvBridgeTest, endianness)
msg.step = 8;

msg.data.resize(msg.step);
int32_t * data = reinterpret_cast<int32_t *>(&msg.data[0]);
uint8_t * raw = msg.data.data();

// Write 1 and 2 in order, but with an endianness opposite to the platform
if (order::native == order::little) {
if (std::endian::native == std::endian::little) {
msg.is_bigendian = true;
*(data++) = native_to_big(static_cast<int32_t>(1));
*data = native_to_big(static_cast<int32_t>(2));
raw[0] = 0x00;
raw[1] = 0x00;
raw[2] = 0x00;
raw[3] = 0x01;

raw[4] = 0x00;
raw[5] = 0x00;
raw[6] = 0x00;
raw[7] = 0x02;
} else {
msg.is_bigendian = false;
*(data++) = native_to_little(static_cast<int32_t>(1));
*data = native_to_little(static_cast<int32_t>(2));
raw[0] = 0x01;
raw[1] = 0x00;
raw[2] = 0x00;
raw[3] = 0x00;

raw[4] = 0x02;
raw[5] = 0x00;
raw[6] = 0x00;
raw[7] = 0x00;
}

// Make sure the values are still the same
Expand Down
9 changes: 3 additions & 6 deletions image_geometry/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,10 @@ project(image_geometry)

find_package(ament_cmake_python REQUIRED)
find_package(ament_cmake_ros REQUIRED)
find_package(ament_cmake_ros_core REQUIRED)

ament_python_install_package(${PROJECT_NAME})

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra)
endif()
Expand All @@ -30,7 +26,8 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
opencv_core
opencv_highgui
opencv_imgproc
${sensor_msgs_TARGETS})
${sensor_msgs_TARGETS}
ament_cmake_ros_core::ament_ros_defaults)

install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})

Expand Down
1 change: 1 addition & 0 deletions image_geometry/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<buildtool_depend>ament_cmake_python</buildtool_depend>
<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>ament_cmake_ros_core</buildtool_depend>

<depend>libopencv-dev</depend>
<depend>sensor_msgs</depend>
Expand Down