Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

enable ament_lint_auto in cv_bridge and image_geometry #542

Open
wants to merge 1 commit into
base: rolling
Choose a base branch
from
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
4 changes: 4 additions & 0 deletions cv_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,10 @@ set(cv_bridge_lib_dir "$<TARGET_FILE_DIR:${PROJECT_NAME}>")

if(BUILD_TESTING)
add_subdirectory(test)

find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE) # Setting this flag disables the copyright check
ament_lint_auto_find_test_dependencies()
endif()

ament_export_dependencies(
Expand Down
13 changes: 7 additions & 6 deletions cv_bridge/include/cv_bridge/cv_bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,19 +37,20 @@
#ifndef CV_BRIDGE__CV_BRIDGE_HPP_
#define CV_BRIDGE__CV_BRIDGE_HPP_

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/imgproc/types_c.h>
#include <cv_bridge/cv_bridge_export.h>
#include <opencv2/imgproc/types_c.h>

#include <memory>
#include <ostream>
#include <stdexcept>
#include <string>

#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include <sensor_msgs/msg/image.hpp>

namespace cv_bridge
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <cstddef>
#include <memory>
#include <optional>
#include <string>
#include <variant>

#include "opencv2/core/mat.hpp"
Expand All @@ -26,7 +28,6 @@

#include "cv_bridge/visibility_control.h"

#include <optional>

namespace cv_bridge
{
Expand Down Expand Up @@ -213,7 +214,7 @@ class ROSCvMatContainer
CV_BRIDGE_PUBLIC
bool
is_bigendian() const;

/// Return the encoding override if provided.
CV_BRIDGE_PUBLIC
std::optional<std::string>
Expand Down Expand Up @@ -244,29 +245,26 @@ struct rclcpp::TypeAdapter<cv_bridge::ROSCvMatContainer, sensor_msgs::msg::Image
{
destination.height = source.cv_mat().rows;
destination.width = source.cv_mat().cols;
const auto& encoding_override = source.encoding_override();
if (encoding_override.has_value() && !encoding_override.value().empty())
{
const auto & encoding_override = source.encoding_override();
if (encoding_override.has_value() && !encoding_override.value().empty()) {
destination.encoding = encoding_override.value();
}
else
{
} else {
switch (source.cv_mat().type()) {
case CV_8UC1:
destination.encoding = "mono8";
break;
case CV_8UC3:
destination.encoding = "bgr8";
break;
case CV_16SC1:
destination.encoding = "mono16";
break;
case CV_8UC4:
destination.encoding = "rgba8";
break;
default:
throw std::runtime_error("unsupported encoding type");
}
case CV_8UC1:
destination.encoding = "mono8";
break;
case CV_8UC3:
destination.encoding = "bgr8";
break;
case CV_16SC1:
destination.encoding = "mono16";
break;
case CV_8UC4:
destination.encoding = "rgba8";
break;
default:
throw std::runtime_error("unsupported encoding type");
}
}
destination.step = static_cast<sensor_msgs::msg::Image::_step_type>(source.cv_mat().step);
size_t size = source.cv_mat().step * source.cv_mat().rows;
Expand Down
3 changes: 1 addition & 2 deletions cv_bridge/include/cv_bridge/rgb_colors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,8 @@
#ifndef CV_BRIDGE__RGB_COLORS_HPP_
#define CV_BRIDGE__RGB_COLORS_HPP_

#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge_export.h>

#include <opencv2/opencv.hpp>

namespace cv_bridge
{
Expand Down
4 changes: 2 additions & 2 deletions cv_bridge/python/cv_bridge/__init__.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
from .core import CvBridge, CvBridgeError
from .core import CvBridge, CvBridgeError # noqa: F401

# python bindings
# This try is just to satisfy doc jobs that are built differently.
try:
from cv_bridge.boost.cv_bridge_boost import cvtColorForDisplay, getCvType
from cv_bridge.boost.cv_bridge_boost import cvtColorForDisplay, getCvType # noqa: F401
except ImportError:
pass
10 changes: 6 additions & 4 deletions cv_bridge/python/cv_bridge/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ def __init__(self):
self.numpy_type_to_cvtype = {'uint8': '8U', 'int8': '8S', 'uint16': '16U',
'int16': '16S', 'int32': '32S', 'float32': '32F',
'float64': '64F'}
self.numpy_type_to_cvtype.update(dict((v, k) for (k, v) in self.numpy_type_to_cvtype.items()))
self.numpy_type_to_cvtype.update({v: k for k, v in self.numpy_type_to_cvtype.items()})

def dtype_with_channels_to_cvtype2(self, dtype, n_channels):
return '%sC%d' % (self.numpy_type_to_cvtype[dtype.name], n_channels)
Expand Down Expand Up @@ -170,14 +170,16 @@ def imgmsg_to_cv2(self, img_msg, desired_encoding='passthrough'):
dtype = np.dtype(dtype)
dtype = dtype.newbyteorder('>' if img_msg.is_bigendian else '<')

img_buf = np.asarray(img_msg.data, dtype=dtype) if isinstance(img_msg.data, list) else img_msg.data
img_buf = np.asarray(img_msg.data, dtype=dtype) if isinstance(
img_msg.data, list) else img_msg.data

if n_channels == 1:
im = np.ndarray(shape=(img_msg.height, int(img_msg.step/dtype.itemsize)),
dtype=dtype, buffer=img_buf)
im = np.ascontiguousarray(im[:img_msg.height, :img_msg.width])
else:
im = np.ndarray(shape=(img_msg.height, int(img_msg.step/dtype.itemsize/n_channels), n_channels),
im = np.ndarray(shape=(img_msg.height, int(img_msg.step/dtype.itemsize/n_channels),
n_channels),
dtype=dtype, buffer=img_buf)
im = np.ascontiguousarray(im[:img_msg.height, :img_msg.width, :])

Expand Down Expand Up @@ -236,7 +238,7 @@ def cv2_to_compressed_imgmsg(self, cvim, dst_format='jpg'):

return cmprs_img_msg

def cv2_to_imgmsg(self, cvim, encoding='passthrough', header = None):
def cv2_to_imgmsg(self, cvim, encoding='passthrough', header=None):
"""
Convert an OpenCV :cpp:type:`cv::Mat` type to a ROS sensor_msgs::Image message.

Expand Down
2 changes: 1 addition & 1 deletion cv_bridge/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ install(FILES
DESTINATION include/${PROJECT_NAME}/${PROJECT_NAME})

if(NOT CV_BRIDGE_DISABLE_PYTHON)
Python3_add_library(${PROJECT_NAME}_boost MODULE module.cpp module_opencv4.cpp)
python3_add_library(${PROJECT_NAME}_boost MODULE module.cpp module_opencv4.cpp)
target_link_libraries(${PROJECT_NAME}_boost PRIVATE
${PROJECT_NAME}
${boost_python_target}
Expand Down
60 changes: 38 additions & 22 deletions cv_bridge/src/cv_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,6 @@
*********************************************************************/

#include <cv_bridge/cv_bridge.hpp>
#include <cv_bridge/rgb_colors.hpp>
#include <boost/endian/conversion.hpp>
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include "rcpputils/endian.hpp"

#include <map>
#include <memory>
Expand All @@ -49,6 +43,14 @@
#include <utility>
#include <vector>

#include <boost/endian/conversion.hpp>
#include <cv_bridge/rgb_colors.hpp>
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <rcpputils/endian.hpp>
#include <sensor_msgs/image_encodings.hpp>


namespace enc = sensor_msgs::image_encodings;

namespace cv_bridge
Expand Down Expand Up @@ -120,8 +122,21 @@ int getCvType(const std::string & encoding)

/// @cond DOXYGEN_IGNORE

enum Encoding { INVALID = -1, GRAY = 0, RGB, BGR, RGBA, BGRA, YUV422, YUV422_YUY2, BAYER_RGGB, BAYER_BGGR,
BAYER_GBRG, BAYER_GRBG};
enum Encoding
{
INVALID = -1,
GRAY = 0,
RGB,
BGR,
RGBA,
BGRA,
YUV422,
YUV422_YUY2,
BAYER_RGGB,
BAYER_BGGR,
BAYER_GBRG,
BAYER_GRBG
};

Encoding getEncoding(const std::string & encoding)
{
Expand Down Expand Up @@ -217,9 +232,11 @@ const std::vector<int> getConversionCode(std::string src_encoding, std::string d
Encoding src_encod = getEncoding(src_encoding);
Encoding dst_encod = getEncoding(dst_encoding);
bool is_src_color_format = enc::isColor(src_encoding) || enc::isMono(src_encoding) ||
enc::isBayer(src_encoding) || (src_encoding == enc::YUV422) || (src_encoding == enc::YUV422_YUY2);
enc::isBayer(src_encoding) || (src_encoding == enc::YUV422) ||
(src_encoding == enc::YUV422_YUY2);
bool is_dst_color_format = enc::isColor(dst_encoding) || enc::isMono(dst_encoding) ||
enc::isBayer(dst_encoding) || (dst_encoding == enc::YUV422) || (dst_encoding == enc::YUV422_YUY2);
enc::isBayer(dst_encoding) || (dst_encoding == enc::YUV422) ||
(dst_encoding == enc::YUV422_YUY2);
bool is_num_channels_the_same =
(enc::numChannels(src_encoding) == enc::numChannels(dst_encoding));

Expand Down Expand Up @@ -299,7 +316,7 @@ 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) ||
if ((rcpputils::endian::native == rcpputils::endian::big && source.is_bigendian) ||
(rcpputils::endian::native == rcpputils::endian::little && !source.is_bigendian) ||
byte_depth == 1)
{
Expand Down Expand Up @@ -515,7 +532,8 @@ void CvImage::toCompressedImageMsg(
{
ros_image.header = header;
cv::Mat image;
if (encoding == enc::BGR8 || encoding == enc::BGRA8 || encoding == enc::MONO8 || encoding == enc::MONO16)
if (encoding == enc::BGR8 || encoding == enc::BGRA8 || encoding == enc::MONO8 ||
encoding == enc::MONO16)
{
image = this->image;
} else {
Expand Down Expand Up @@ -550,8 +568,7 @@ CvImagePtr toCvCopy(const sensor_msgs::msg::CompressedImage & source, const std:
const cv::Mat rgb_a = cv::imdecode(in, cv::IMREAD_UNCHANGED);

if (encoding != enc::MONO16) {
switch (rgb_a.channels())
{
switch (rgb_a.channels()) {
case 4:
return toCvCopyImpl(rgb_a, source.header, enc::BGRA8, encoding);
break;
Expand All @@ -564,8 +581,7 @@ CvImagePtr toCvCopy(const sensor_msgs::msg::CompressedImage & source, const std:
default:
return CvImagePtr();
}
}
else {
} else {
return toCvCopyImpl(rgb_a, source.header, enc::MONO16, encoding);
}
}
Expand Down Expand Up @@ -599,7 +615,7 @@ CvImageConstPtr cvtColorForDisplay(
} else {
// We choose BGR by default here as we assume people will use OpenCV
if ((enc::bitDepth(source->encoding) == 8) ||
(enc::bitDepth(source->encoding) == 16) ||
(enc::bitDepth(source->encoding) == 16) ||
(enc::bitDepth(source->encoding) == 32))
{
encoding = enc::BGR8;
Expand All @@ -619,8 +635,8 @@ CvImageConstPtr cvtColorForDisplay(
(enc::bitDepth(encoding) != 8))
{
throw Exception(
"cv_bridge.cvtColorForDisplay() does not have an output encoding \
that is color or mono, and has is bit in depth");
"cv_bridge.cvtColorForDisplay() does not have an output encoding "
"that is color or mono, and has is bit in depth");
}
}

Expand Down Expand Up @@ -651,7 +667,7 @@ CvImageConstPtr cvtColorForDisplay(
// Perform scaling if asked for
if (options.do_dynamic_scaling) {
float inf = std::numeric_limits<float>::infinity();
cv::Mat mask = ((source->image!=inf) & (source->image!=-inf));
cv::Mat mask = ((source->image != inf) & (source->image != -inf));
cv::minMaxLoc(source->image, &min_image_value, &max_image_value, NULL, NULL, mask);
if (min_image_value == max_image_value) {
CvImagePtr result(new CvImage());
Expand All @@ -671,8 +687,8 @@ CvImageConstPtr cvtColorForDisplay(
if (min_image_value != max_image_value) {
if (enc::numChannels(source->encoding) != 1) {
throw Exception(
"cv_bridge.cvtColorForDisplay() scaling for images \
with more than one channel is unsupported");
"cv_bridge.cvtColorForDisplay() scaling for images "
"with more than one channel is unsupported");
}
CvImagePtr img_scaled(new CvImage());
img_scaled->header = source->header;
Expand Down
7 changes: 2 additions & 5 deletions cv_bridge/src/cv_mat_sensor_msgs_image_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,12 +179,9 @@ ROSCvMatContainer::get_sensor_msgs_msg_image_copy(
{
sensor_msgs_image.height = frame_.rows;
sensor_msgs_image.width = frame_.cols;
if (encoding_override_.has_value() && !encoding_override_.value().empty())
{
if (encoding_override_.has_value() && !encoding_override_.value().empty()) {
sensor_msgs_image.encoding = encoding_override_.value();
}
else
{
} else {
switch (frame_.type()) {
case CV_8UC1:
sensor_msgs_image.encoding = "mono8";
Expand Down
12 changes: 6 additions & 6 deletions cv_bridge/src/module.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,11 @@
// limitations under the License.
//

#ifndef CV_BRIDGE_MODULE_HPP_
#define CV_BRIDGE_MODULE_HPP_
#ifndef MODULE_HPP_
#define MODULE_HPP_

#define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION
#include <numpy/ndarrayobject.h>

#include <iostream>

Expand All @@ -33,9 +36,6 @@
#include <cv_bridge/cv_bridge.hpp>
#include <Python.h>

#define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION
#include <numpy/ndarrayobject.h>

#include <opencv2/core/core.hpp>

namespace bp = boost::python;
Expand All @@ -50,4 +50,4 @@ static void * do_numpy_import()
return nullptr;
}

#endif // CV_BRIDGE_MODULE_HPP_
#endif // MODULE_HPP_
Loading