Skip to content

Commit

Permalink
Replace boost with std (#164)
Browse files Browse the repository at this point in the history
* Use std::shared_ptr instead of boost::shared_ptr

* Use std::mutex instead of boost::mutex

* Replace boost::lexical_cast with std::to_string

* Use C++11 foreach loop and auto

* Update boost linking

* Reformat

* Fix cpplint errors

* Replace boost::bind with lambda in std::partition

* Reformat
  • Loading branch information
bjsowa authored Oct 10, 2024
1 parent 59e827e commit 1ba7ce4
Show file tree
Hide file tree
Showing 20 changed files with 80 additions and 77 deletions.
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)

find_package(OpenCV REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)
find_package(Boost REQUIRED COMPONENTS system)

find_package(PkgConfig REQUIRED)
pkg_check_modules(avcodec libavcodec REQUIRED)
Expand All @@ -36,7 +36,6 @@ endif()

## Specify additional locations of header files
include_directories(include
${Boost_INCLUDE_DIRS}
${avcodec_INCLUDE_DIRS}
${avformat_INCLUDE_DIRS}
${avutil_INCLUDE_DIRS}
Expand Down Expand Up @@ -68,7 +67,8 @@ target_link_libraries(${PROJECT_NAME}
cv_bridge::cv_bridge
image_transport::image_transport
rclcpp::rclcpp
${Boost_LIBRARIES}
Boost::boost
Boost::system
${OpenCV_LIBS}
${avcodec_LIBRARIES}
${avformat_LIBRARIES}
Expand Down
3 changes: 2 additions & 1 deletion include/web_video_server/h264_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#pragma once

#include <memory>
#include <string>

#include "image_transport/image_transport.hpp"
Expand Down Expand Up @@ -57,7 +58,7 @@ class H264StreamerType : public LibavStreamerType
{
public:
H264StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
5 changes: 3 additions & 2 deletions include/web_video_server/image_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#pragma once

#include <memory>
#include <string>

#include <opencv2/opencv.hpp>
Expand Down Expand Up @@ -106,7 +107,7 @@ class ImageTransportImageStreamer : public ImageStreamer

rclcpp::Time last_frame;
cv::Mat output_size_image;
boost::mutex send_mutex_;
std::mutex send_mutex_;

private:
image_transport::ImageTransport it_;
Expand All @@ -118,7 +119,7 @@ class ImageTransportImageStreamer : public ImageStreamer
class ImageStreamerType
{
public:
virtual boost::shared_ptr<ImageStreamer> create_streamer(
virtual std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node) = 0;
Expand Down
3 changes: 2 additions & 1 deletion include/web_video_server/jpeg_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#pragma once

#include <memory>
#include <string>

#include "image_transport/image_transport.hpp"
Expand Down Expand Up @@ -61,7 +62,7 @@ class MjpegStreamer : public ImageTransportImageStreamer
class MjpegStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
5 changes: 3 additions & 2 deletions include/web_video_server/libav_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ extern "C"
#include <libavutil/imgutils.h>
}

#include <memory>
#include <string>

#include "image_transport/image_transport.hpp"
Expand Down Expand Up @@ -78,7 +79,7 @@ class LibavStreamer : public ImageTransportImageStreamer
AVFrame * frame_;
struct SwsContext * sws_context_;
rclcpp::Time first_image_timestamp_;
boost::mutex encode_mutex_;
std::mutex encode_mutex_;

std::string format_name_;
std::string codec_name_;
Expand All @@ -98,7 +99,7 @@ class LibavStreamerType : public ImageStreamerType
const std::string & format_name, const std::string & codec_name,
const std::string & content_type);

boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
3 changes: 2 additions & 1 deletion include/web_video_server/png_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#pragma once

#include <memory>
#include <string>

#include "image_transport/image_transport.hpp"
Expand Down Expand Up @@ -61,7 +62,7 @@ class PngStreamer : public ImageTransportImageStreamer
class PngStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
5 changes: 3 additions & 2 deletions include/web_video_server/ros_compressed_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#pragma once

#include <memory>
#include <string>

#include "sensor_msgs/msg/compressed_image.hpp"
Expand Down Expand Up @@ -63,14 +64,14 @@ class RosCompressedStreamer : public ImageStreamer
rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr image_sub_;
rclcpp::Time last_frame;
sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg;
boost::mutex send_mutex_;
std::mutex send_mutex_;
std::string qos_profile_name_;
};

class RosCompressedStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
3 changes: 2 additions & 1 deletion include/web_video_server/vp8_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#pragma once

#include <memory>
#include <string>

#include "image_transport/image_transport.hpp"
Expand Down Expand Up @@ -60,7 +61,7 @@ class Vp8StreamerType : public LibavStreamerType
{
public:
Vp8StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
4 changes: 3 additions & 1 deletion include/web_video_server/vp9_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@

#pragma once

#include <memory>

#include "image_transport/image_transport.hpp"
#include "web_video_server/libav_streamer.hpp"
#include "async_web_server_cpp/http_request.hpp"
Expand All @@ -54,7 +56,7 @@ class Vp9StreamerType : public LibavStreamerType
{
public:
Vp9StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(
std::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Expand Down
9 changes: 5 additions & 4 deletions include/web_video_server/web_video_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#pragma once

#include <map>
#include <memory>
#include <string>
#include <vector>

Expand Down Expand Up @@ -114,12 +115,12 @@ class WebVideoServer
bool verbose_;
std::string default_stream_type_;

boost::shared_ptr<async_web_server_cpp::HttpServer> server_;
std::shared_ptr<async_web_server_cpp::HttpServer> server_;
async_web_server_cpp::HttpRequestHandlerGroup handler_group_;

std::vector<boost::shared_ptr<ImageStreamer>> image_subscribers_;
std::map<std::string, boost::shared_ptr<ImageStreamerType>> stream_types_;
boost::mutex subscriber_mutex_;
std::vector<std::shared_ptr<ImageStreamer>> image_subscribers_;
std::map<std::string, std::shared_ptr<ImageStreamerType>> stream_types_;
std::mutex subscriber_mutex_;
};

} // namespace web_video_server
4 changes: 2 additions & 2 deletions src/h264_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,12 +69,12 @@ H264StreamerType::H264StreamerType()
{
}

boost::shared_ptr<ImageStreamer> H264StreamerType::create_streamer(
std::shared_ptr<ImageStreamer> H264StreamerType::create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node)
{
return boost::shared_ptr<ImageStreamer>(new H264Streamer(request, connection, node));
return std::make_shared<H264Streamer>(request, connection, node);
}

} // namespace web_video_server
4 changes: 2 additions & 2 deletions src/image_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ void ImageTransportImageStreamer::restreamFrame(double max_age)
}
try {
if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) {
boost::mutex::scoped_lock lock(send_mutex_);
std::scoped_lock lock(send_mutex_);
// don't update last_frame, it may remain an old value.
sendImage(output_size_image, node_->now());
}
Expand Down Expand Up @@ -184,7 +184,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
cv::flip(img, img, true);
}

boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image
std::scoped_lock lock(send_mutex_); // protects output_size_image
if (output_width_ != input_width || output_height_ != input_height) {
cv::Mat img_resized;
cv::Size new_size(output_width_, output_height_);
Expand Down
10 changes: 5 additions & 5 deletions src/jpeg_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ MjpegStreamer::MjpegStreamer(
MjpegStreamer::~MjpegStreamer()
{
this->inactive_ = true;
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
std::scoped_lock lock(send_mutex_); // protects sendImage.
}

void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
Expand All @@ -62,12 +62,12 @@ void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
stream_.sendPartAndClear(time, "image/jpeg", encoded_buffer);
}

boost::shared_ptr<ImageStreamer> MjpegStreamerType::create_streamer(
std::shared_ptr<ImageStreamer> MjpegStreamerType::create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node)
{
return boost::shared_ptr<ImageStreamer>(new MjpegStreamer(request, connection, node));
return std::make_shared<MjpegStreamer>(request, connection, node);
}

std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request)
Expand All @@ -91,7 +91,7 @@ JpegSnapshotStreamer::JpegSnapshotStreamer(
JpegSnapshotStreamer::~JpegSnapshotStreamer()
{
this->inactive_ = true;
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
std::scoped_lock lock(send_mutex_); // protects sendImage.
}

void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
Expand All @@ -115,7 +115,7 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & t
.header("Pragma", "no-cache")
.header("Content-type", "image/jpeg")
.header("Access-Control-Allow-Origin", "*")
.header("Content-Length", boost::lexical_cast<std::string>(encoded_buffer.size()))
.header("Content-Length", std::to_string(encoded_buffer.size()))
.write(connection_);
connection_->write_and_clear(encoded_buffer);
inactive_ = true;
Expand Down
9 changes: 5 additions & 4 deletions src/libav_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ void LibavStreamer::initializeEncoder()

void LibavStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
{
boost::mutex::scoped_lock lock(encode_mutex_);
std::scoped_lock lock(encode_mutex_);
if (0 == first_image_timestamp_.nanoseconds()) {
first_image_timestamp_ = time;
}
Expand Down Expand Up @@ -303,13 +303,14 @@ LibavStreamerType::LibavStreamerType(
{
}

boost::shared_ptr<ImageStreamer> LibavStreamerType::create_streamer(
std::shared_ptr<ImageStreamer> LibavStreamerType::create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node)
{
return boost::shared_ptr<ImageStreamer>(
new LibavStreamer(request, connection, node, format_name_, codec_name_, content_type_));
return std::make_shared<LibavStreamer>(
request, connection, node, format_name_, codec_name_,
content_type_);
}

std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request)
Expand Down
3 changes: 1 addition & 2 deletions src/multipart_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,7 @@ void MultipartStream::sendPartHeader(
headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp));
headers->push_back(
async_web_server_cpp::HttpHeader(
"Content-Length",
boost::lexical_cast<std::string>(payload_size)));
"Content-Length", std::to_string(payload_size)));
connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers);
}

Expand Down
10 changes: 5 additions & 5 deletions src/png_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ PngStreamer::PngStreamer(
PngStreamer::~PngStreamer()
{
this->inactive_ = true;
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
std::scoped_lock lock(send_mutex_); // protects sendImage.
}

cv::Mat PngStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
Expand All @@ -78,12 +78,12 @@ void PngStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
stream_.sendPartAndClear(time, "image/png", encoded_buffer);
}

boost::shared_ptr<ImageStreamer> PngStreamerType::create_streamer(
std::shared_ptr<ImageStreamer> PngStreamerType::create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node)
{
return boost::shared_ptr<ImageStreamer>(new PngStreamer(request, connection, node));
return std::make_shared<PngStreamer>(request, connection, node);
}

std::string PngStreamerType::create_viewer(const async_web_server_cpp::HttpRequest & request)
Expand All @@ -107,7 +107,7 @@ PngSnapshotStreamer::PngSnapshotStreamer(
PngSnapshotStreamer::~PngSnapshotStreamer()
{
this->inactive_ = true;
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
std::scoped_lock lock(send_mutex_); // protects sendImage.
}

cv::Mat PngSnapshotStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
Expand Down Expand Up @@ -142,7 +142,7 @@ void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & ti
.header("Pragma", "no-cache")
.header("Content-type", "image/png")
.header("Access-Control-Allow-Origin", "*")
.header("Content-Length", boost::lexical_cast<std::string>(encoded_buffer.size()))
.header("Content-Length", std::to_string(encoded_buffer.size()))
.write(connection_);
connection_->write_and_clear(encoded_buffer);
inactive_ = true;
Expand Down
Loading

0 comments on commit 1ba7ce4

Please sign in to comment.