Skip to content

Commit

Permalink
Removed Boost dependency (#909)
Browse files Browse the repository at this point in the history
Removed Boost dependency. Related with
#407

---------

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 22, 2024
1 parent 3042ecc commit 6dd6c82
Show file tree
Hide file tree
Showing 10 changed files with 61 additions and 48 deletions.
2 changes: 0 additions & 2 deletions image_view/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@ endif()
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

find_package(Boost REQUIRED)
find_package(OpenCV REQUIRED)

# Deal with the GUI's
Expand All @@ -30,7 +29,6 @@ ament_auto_add_library(${PROJECT_NAME}_nodes SHARED
)
target_link_libraries(${PROJECT_NAME}_nodes
${OpenCV_LIBRARIES}
${Boost_LIBRARIES}
)
target_compile_definitions(${PROJECT_NAME}_nodes
PRIVATE "COMPOSITION_BUILDING_DLL"
Expand Down
4 changes: 1 addition & 3 deletions image_view/include/image_view/extract_images_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/msg/image.hpp>

#include <boost/format.hpp>

namespace image_view
{

Expand All @@ -74,7 +72,7 @@ class ExtractImagesNode
std::mutex image_mutex_;

std::string window_name_;
boost::format filename_format_;
std::string filename_format_;
int count_;
rclcpp::Time _time;
double sec_per_frame_;
Expand Down
4 changes: 1 addition & 3 deletions image_view/include/image_view/image_saver_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,6 @@
#include <memory>
#include <string>

#include <boost/format.hpp>

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <std_srvs/srv/empty.hpp>
Expand All @@ -69,7 +67,7 @@ class ImageSaverNode
explicit ImageSaverNode(const rclcpp::NodeOptions & options);

private:
boost::format g_format;
std::string g_format;
bool stamped_filename_;
bool save_all_image_{false};
bool save_image_service_{false};
Expand Down
4 changes: 1 addition & 3 deletions image_view/include/image_view/image_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@
#include <sensor_msgs/msg/image.hpp>
#include <image_transport/image_transport.hpp>

#include <boost/format.hpp>

namespace image_view
{

Expand Down Expand Up @@ -61,7 +59,7 @@ class ImageViewNode
bool autosize_;
int window_height_, window_width_;
bool g_gui;
boost::format filename_format_;
std::string filename_format_;
image_transport::Subscriber sub_;
int count_;
double min_image_value_, max_image_value_;
Expand Down
5 changes: 2 additions & 3 deletions image_view/include/image_view/stereo_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@

#include <memory>
#include <mutex>
#include <string>

#include "message_filters/subscriber.h"
#include "message_filters/sync_policies/approximate_time.h"
Expand All @@ -63,8 +64,6 @@
#include <sensor_msgs/msg/image.hpp>
#include <stereo_msgs/msg/disparity_image.hpp>

#include <boost/format.hpp>

namespace image_view
{

Expand Down Expand Up @@ -101,7 +100,7 @@ class StereoViewNode
cv::Mat_<cv::Vec3b> disparity_color_;
std::mutex image_mutex_;

boost::format filename_format_;
std::string filename_format_;
int save_count_;

rclcpp::TimerBase::SharedPtr check_synced_timer_;
Expand Down
8 changes: 3 additions & 5 deletions image_view/src/extract_images_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,8 @@
#include <rclcpp_components/register_node_macro.hpp>
#include <sensor_msgs/msg/image.hpp>

#include <boost/format.hpp>

#include "image_view/extract_images_node.hpp"
#include "utils.hpp"

namespace image_view
{
Expand Down Expand Up @@ -95,8 +94,7 @@ ExtractImagesNode::ExtractImagesNode(const rclcpp::NodeOptions & options)
}

this->declare_parameter<std::string>("filename_format", std::string("frame%04i.jpg"));
std::string format_string = this->get_parameter("filename_format").as_string();
filename_format_.parse(format_string);
filename_format_ = this->get_parameter("filename_format").as_string();

this->declare_parameter<double>("sec_per_frame", 0.1);
sec_per_frame_ = this->get_parameter("sec_per_frame").as_double();
Expand Down Expand Up @@ -130,7 +128,7 @@ void ExtractImagesNode::image_cb(const sensor_msgs::msg::Image::ConstSharedPtr &
_time = this->now();

if (!image.empty()) {
std::string filename = (filename_format_ % count_).str();
std::string filename = string_format(filename_format_, count_);

cv::imwrite(filename, image);

Expand Down
25 changes: 4 additions & 21 deletions image_view/src/image_saver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@

#include "image_view/image_saver_node.hpp"

#include <boost/format.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <rclcpp/rclcpp.hpp>
Expand All @@ -65,6 +64,8 @@
#include <std_srvs/srv/empty.hpp>
#include <std_srvs/srv/trigger.hpp>

#include "utils.hpp"

namespace image_view
{

Expand Down Expand Up @@ -92,13 +93,11 @@ ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options)
&ImageSaverNode::callbackWithoutCameraInfo, this, std::placeholders::_1),
hints.getTransport());

std::string format_string;
format_string = this->declare_parameter("filename_format", std::string("left%04i.%s"));
g_format = this->declare_parameter("filename_format", std::string("left%04i.%s"));
encoding_ = this->declare_parameter("encoding", std::string("bgr8"));
save_all_image_ = this->declare_parameter("save_all_image", true);
stamped_filename_ = this->declare_parameter("stamped_filename", false);
request_start_end_ = this->declare_parameter("request_start_end", false);
g_format.parse(format_string);

save_srv_ = this->create_service<std_srvs::srv::Empty>(
"save",
Expand Down Expand Up @@ -131,23 +130,7 @@ bool ImageSaverNode::saveImage(
}

if (!image.empty()) {
try {
filename = (g_format).str();
} catch (...) {
g_format.clear();
}

try {
filename = (g_format % count_).str();
} catch (...) {
g_format.clear();
}

try {
filename = (g_format % count_ % "jpg").str();
} catch (...) {
g_format.clear();
}
filename = string_format(g_format, count_, "jpg");

if (save_all_image_ || save_image_service_) {
if (stamped_filename_) {
Expand Down
8 changes: 4 additions & 4 deletions image_view/src/image_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,14 +58,15 @@

#include "image_view/image_view_node.hpp"

#include <boost/format.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <std_msgs/msg/header.hpp>

#include "utils.hpp"

namespace image_view
{

Expand Down Expand Up @@ -135,9 +136,8 @@ ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options)
autosize_ = this->declare_parameter("autosize", false);
window_height_ = this->declare_parameter("height", -1);
window_width_ = this->declare_parameter("width", -1);
std::string format_string =
filename_format_ =
this->declare_parameter("filename_format", std::string("frame%04i.jpg"));
filename_format_.parse(format_string);

rcl_interfaces::msg::ParameterDescriptor colormap_paramDescriptor;
colormap_paramDescriptor.name = "colormap";
Expand Down Expand Up @@ -253,7 +253,7 @@ void ImageViewNode::mouseCb(int event, int /* x */, int /* y */, int /* flags */
return;
}

std::string filename = (this_->filename_format_ % this_->count_).str();
std::string filename = string_format(this_->filename_format_, this_->count_);

if (cv::imwrite(filename, image->image)) {
RCLCPP_INFO(this_->get_logger(), "Saved image %s", filename.c_str());
Expand Down
8 changes: 4 additions & 4 deletions image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@

#include "image_view/stereo_view_node.hpp"

#include <boost/format.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <rclcpp/rclcpp.hpp>
Expand All @@ -70,6 +69,8 @@
#include <sensor_msgs/msg/image.hpp>
#include <stereo_msgs/msg/disparity_image.hpp>

#include "utils.hpp"

namespace image_view
{

Expand All @@ -94,8 +95,7 @@ StereoViewNode::StereoViewNode(const rclcpp::NodeOptions & options)
bool autosize = this->declare_parameter("autosize", true);

this->declare_parameter<std::string>("filename_format", std::string("frame%04i.jpg"));
std::string format_string = this->get_parameter("filename_format").as_string();
filename_format_.parse(format_string);
filename_format_ = this->get_parameter("filename_format").as_string();

// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", std::string("raw"));
Expand Down Expand Up @@ -265,7 +265,7 @@ void StereoViewNode::imageCb(
void StereoViewNode::saveImage(const char * prefix, const cv::Mat & image)
{
if (!image.empty()) {
std::string filename = (filename_format_ % prefix % save_count_).str();
std::string filename = string_format(filename_format_, prefix, save_count_);
cv::imwrite(filename, image);
RCLCPP_INFO(this->get_logger(), "Saved image %s", filename.c_str());
} else {
Expand Down
41 changes: 41 additions & 0 deletions image_view/src/utils.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UTILS_HPP_
#define UTILS_HPP_

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

namespace image_view
{
// TODO(ahcorde): Use std::format when C++20 is available
template<typename ... Args>
std::string string_format(const std::string & format, Args ... args)
{
// Extra space for '\0'
int size_s = std::snprintf(nullptr, 0, format.c_str(), args ...) + 1;
if (size_s <= 0) {
throw std::runtime_error("Error during formatting.");
}
auto size = static_cast<size_t>(size_s);
std::unique_ptr<char[]> buf(new char[size]);
std::snprintf(buf.get(), size, format.c_str(), args ...);
// We don't want the '\0' inside
return std::string(buf.get(), buf.get() + size - 1);
}
} // namespace image_view

#endif // UTILS_HPP_

0 comments on commit 6dd6c82

Please sign in to comment.