Skip to content

Commit

Permalink
Port image processor library to ROS 2 (#484)
Browse files Browse the repository at this point in the history
* Add back processor.cpp

The implementation was removed (accidentally?) in #426.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Port processor.cpp for ROS 2

* Added library back to CMakeLists.txt
* Renamed image_proc executable to it's former name
* Made changes for library to compile
* Added new dependency to rcutils for logging
* Linted to satisfy tests

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored Dec 11, 2019
1 parent bb4c2db commit 70dd1b4
Show file tree
Hide file tree
Showing 4 changed files with 162 additions and 7 deletions.
30 changes: 24 additions & 6 deletions image_proc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rcutils REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(image_transport REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand All @@ -35,6 +36,18 @@ set(dependencies
rcutils
)

add_library(${PROJECT_NAME}
src/${PROJECT_NAME}/processor.cpp
)
target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBRARIES}
)
ament_target_dependencies(${PROJECT_NAME}
image_geometry
rcutils
sensor_msgs
)

add_library(rectify SHARED
src/rectify.cpp)
target_compile_definitions(rectify
Expand Down Expand Up @@ -103,26 +116,31 @@ ament_target_dependencies(crop_non_zero
rclcpp_components_register_nodes(crop_non_zero "image_proc::CropNonZeroNode")
set(node_plugins "${node_plugins}image_proc::CropNonZeroNode;$<TARGET_FILE:crop_non_zero>\n")

add_executable(image_proc
add_executable(image_proc_exe
src/image_proc.cpp
)

target_link_libraries(image_proc
target_link_libraries(image_proc_exe
debayer
rectify
ament_index_cpp::ament_index_cpp)
ament_index_cpp::ament_index_cpp
)

if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
target_link_libraries(image_proc "stdc++fs")
endif()

ament_target_dependencies(image_proc
ament_target_dependencies(image_proc_exe
${dependencies}
)

set_target_properties(image_proc_exe PROPERTIES OUTPUT_NAME image_proc)

install(TARGETS
image_proc
DESTINATION lib/${PROJECT_NAME}
${PROJECT_NAME} image_proc_exe
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)


Expand Down
2 changes: 1 addition & 1 deletion image_proc/include/image_proc/processor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class Processor
};

bool process(
const sensor_msgs::msg::Image::SharedConstPtr & raw_image,
const sensor_msgs::msg::Image::ConstSharedPtr & raw_image,
const image_geometry::PinholeCameraModel & model,
ImageSet & output, int flags = ALL) const;
};
Expand Down
1 change: 1 addition & 0 deletions image_proc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rcutils</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>sensor_msgs</depend>
Expand Down
136 changes: 136 additions & 0 deletions image_proc/src/image_proc/processor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
// Copyright 2008 Willow Garage, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// 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, this list of conditions and the following disclaimer.
// * 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.
// * Neither the name of {copyright_holder} nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include "image_proc/processor.hpp"

#include <rcutils/logging_macros.h>
#include <sensor_msgs/image_encodings.hpp>

#include <string>

namespace image_proc
{

namespace enc = sensor_msgs::image_encodings;

bool Processor::process(
const sensor_msgs::msg::Image::ConstSharedPtr & raw_image,
const image_geometry::PinholeCameraModel & model,
ImageSet & output, int flags) const
{
static const int MONO_EITHER = MONO | RECT;
static const int COLOR_EITHER = COLOR | RECT_COLOR;
if (!(flags & ALL)) {
return true;
}

// Check if raw_image is color
const std::string & raw_encoding = raw_image->encoding;
int raw_type = CV_8UC1;
if (raw_encoding == enc::BGR8 || raw_encoding == enc::RGB8) {
raw_type = CV_8UC3;
output.color_encoding = raw_encoding;
}
// Construct cv::Mat pointing to raw_image data
const cv::Mat raw(
raw_image->height, raw_image->width, raw_type,
const_cast<uint8_t *>(&raw_image->data[0]), raw_image->step);

///////////////////////////////////////////////////////
// Construct colorized (unrectified) images from raw //
///////////////////////////////////////////////////////

// Bayer case
if (raw_encoding.find("bayer") != std::string::npos) {
// Convert to color BGR
// TODO(unknown): Faster to convert directly to mono when color is not requested,
// but OpenCV doesn't support
int code = 0;
if (raw_encoding == enc::BAYER_RGGB8) {
code = cv::COLOR_BayerBG2BGR;
} else if (raw_encoding == enc::BAYER_BGGR8) {
code = cv::COLOR_BayerRG2BGR;
} else if (raw_encoding == enc::BAYER_GBRG8) {
code = cv::COLOR_BayerGR2BGR;
} else if (raw_encoding == enc::BAYER_GRBG8) {
code = cv::COLOR_BayerGB2BGR;
} else {
RCUTILS_LOG_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
return false;
}
cv::cvtColor(raw, output.color, code);
output.color_encoding = enc::BGR8;

if (flags & MONO_EITHER) {
cv::cvtColor(output.color, output.mono, cv::COLOR_BGR2GRAY);
}
} else if (raw_type == CV_8UC3) { // Color case
output.color = raw;
if (flags & MONO_EITHER) {
int code = (raw_encoding == enc::BGR8) ? cv::COLOR_BGR2GRAY : cv::COLOR_RGB2GRAY;
cv::cvtColor(output.color, output.mono, code);
}
} else if (raw_encoding == enc::MONO8) { // Mono case
output.mono = raw;
if (flags & COLOR_EITHER) {
output.color_encoding = enc::MONO8;
output.color = raw;
}
} else if (raw_encoding == enc::TYPE_8UC3) {
// 8UC3 does not specify a color encoding. Is it BGR, RGB, HSV, XYZ, LUV...?
RCUTILS_LOG_ERROR(
"[image_proc] Ambiguous encoding '8UC3'. "
"The camera driver should set the encoding to 'bgr8' or 'rgb8'.");
return false;
} else {
// Something else we can't handle
RCUTILS_LOG_ERROR("[image_proc] Unsupported encoding '%s'", raw_encoding.c_str());
return false;
}

//////////////////////////////////////////////////////
// Construct rectified images from colorized images //
//////////////////////////////////////////////////////

// TODO(unknown): If no distortion, could just point to the colorized data.
// But copy is already way faster than remap.
if (flags & RECT) {
model.rectifyImage(output.mono, output.rect, interpolation_);
}
if (flags & RECT_COLOR) {
model.rectifyImage(output.color, output.rect_color, interpolation_);
}

return true;
}

} // namespace image_proc

0 comments on commit 70dd1b4

Please sign in to comment.