Skip to content

Commit aee851c

Browse files
committed
Use std::mutex instead of boost::mutex
1 parent 79f91e7 commit aee851c

File tree

10 files changed

+18
-18
lines changed

10 files changed

+18
-18
lines changed

include/web_video_server/image_streamer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ class ImageTransportImageStreamer : public ImageStreamer
106106

107107
rclcpp::Time last_frame;
108108
cv::Mat output_size_image;
109-
boost::mutex send_mutex_;
109+
std::mutex send_mutex_;
110110

111111
private:
112112
image_transport::ImageTransport it_;

include/web_video_server/libav_streamer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ class LibavStreamer : public ImageTransportImageStreamer
7878
AVFrame * frame_;
7979
struct SwsContext * sws_context_;
8080
rclcpp::Time first_image_timestamp_;
81-
boost::mutex encode_mutex_;
81+
std::mutex encode_mutex_;
8282

8383
std::string format_name_;
8484
std::string codec_name_;

include/web_video_server/ros_compressed_streamer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class RosCompressedStreamer : public ImageStreamer
6363
rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr image_sub_;
6464
rclcpp::Time last_frame;
6565
sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg;
66-
boost::mutex send_mutex_;
66+
std::mutex send_mutex_;
6767
std::string qos_profile_name_;
6868
};
6969

include/web_video_server/web_video_server.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ class WebVideoServer
119119

120120
std::vector<std::shared_ptr<ImageStreamer>> image_subscribers_;
121121
std::map<std::string, std::shared_ptr<ImageStreamerType>> stream_types_;
122-
boost::mutex subscriber_mutex_;
122+
std::mutex subscriber_mutex_;
123123
};
124124

125125
} // namespace web_video_server

src/image_streamer.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ void ImageTransportImageStreamer::restreamFrame(double max_age)
117117
}
118118
try {
119119
if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) {
120-
boost::mutex::scoped_lock lock(send_mutex_);
120+
std::scoped_lock lock(send_mutex_);
121121
// don't update last_frame, it may remain an old value.
122122
sendImage(output_size_image, node_->now());
123123
}
@@ -184,7 +184,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
184184
cv::flip(img, img, true);
185185
}
186186

187-
boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image
187+
std::scoped_lock lock(send_mutex_); // protects output_size_image
188188
if (output_width_ != input_width || output_height_ != input_height) {
189189
cv::Mat img_resized;
190190
cv::Size new_size(output_width_, output_height_);

src/jpeg_streamers.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ MjpegStreamer::MjpegStreamer(
4747
MjpegStreamer::~MjpegStreamer()
4848
{
4949
this->inactive_ = true;
50-
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
50+
std::scoped_lock lock(send_mutex_); // protects sendImage.
5151
}
5252

5353
void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
@@ -91,7 +91,7 @@ JpegSnapshotStreamer::JpegSnapshotStreamer(
9191
JpegSnapshotStreamer::~JpegSnapshotStreamer()
9292
{
9393
this->inactive_ = true;
94-
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
94+
std::scoped_lock lock(send_mutex_); // protects sendImage.
9595
}
9696

9797
void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)

src/libav_streamer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -217,7 +217,7 @@ void LibavStreamer::initializeEncoder()
217217

218218
void LibavStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
219219
{
220-
boost::mutex::scoped_lock lock(encode_mutex_);
220+
std::scoped_lock lock(encode_mutex_);
221221
if (0 == first_image_timestamp_.nanoseconds()) {
222222
first_image_timestamp_ = time;
223223
}

src/png_streamers.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ PngStreamer::PngStreamer(
5252
PngStreamer::~PngStreamer()
5353
{
5454
this->inactive_ = true;
55-
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
55+
std::scoped_lock lock(send_mutex_); // protects sendImage.
5656
}
5757

5858
cv::Mat PngStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
@@ -107,7 +107,7 @@ PngSnapshotStreamer::PngSnapshotStreamer(
107107
PngSnapshotStreamer::~PngSnapshotStreamer()
108108
{
109109
this->inactive_ = true;
110-
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
110+
std::scoped_lock lock(send_mutex_); // protects sendImage.
111111
}
112112

113113
cv::Mat PngSnapshotStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)

src/ros_compressed_streamer.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ RosCompressedStreamer::RosCompressedStreamer(
4545
RosCompressedStreamer::~RosCompressedStreamer()
4646
{
4747
this->inactive_ = true;
48-
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
48+
std::scoped_lock lock(send_mutex_); // protects sendImage.
4949
}
5050

5151
void RosCompressedStreamer::start()
@@ -81,7 +81,7 @@ void RosCompressedStreamer::restreamFrame(double max_age)
8181
}
8282

8383
if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) {
84-
boost::mutex::scoped_lock lock(send_mutex_);
84+
std::scoped_lock lock(send_mutex_);
8585
sendImage(last_msg, node_->now() ); // don't update last_frame, it may remain an old value.
8686
}
8787
}
@@ -128,7 +128,7 @@ void RosCompressedStreamer::sendImage(
128128
void RosCompressedStreamer::imageCallback(
129129
const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg)
130130
{
131-
boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame
131+
std::scoped_lock lock(send_mutex_); // protects last_msg and last_frame
132132
last_msg = msg;
133133
last_frame = rclcpp::Time(msg->header.stamp);
134134
sendImage(last_msg, last_frame);

src/web_video_server.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ void WebVideoServer::spin()
135135

136136
void WebVideoServer::restreamFrames(double max_age)
137137
{
138-
boost::mutex::scoped_lock lock(subscriber_mutex_);
138+
std::scoped_lock lock(subscriber_mutex_);
139139

140140
typedef std::vector<std::shared_ptr<ImageStreamer>>::iterator itr_type;
141141

@@ -146,7 +146,7 @@ void WebVideoServer::restreamFrames(double max_age)
146146

147147
void WebVideoServer::cleanup_inactive_streams()
148148
{
149-
boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock);
149+
std::unique_lock lock(subscriber_mutex_, std::try_to_lock);
150150
if (lock) {
151151
typedef std::vector<std::shared_ptr<ImageStreamer>>::iterator itr_type;
152152
itr_type new_end = std::partition(
@@ -214,7 +214,7 @@ bool WebVideoServer::handle_stream(
214214
std::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer(request,
215215
connection, node_);
216216
streamer->start();
217-
boost::mutex::scoped_lock lock(subscriber_mutex_);
217+
std::scoped_lock lock(subscriber_mutex_);
218218
image_subscribers_.push_back(streamer);
219219
} else {
220220
async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(
@@ -232,7 +232,7 @@ bool WebVideoServer::handle_snapshot(
232232
connection, node_);
233233
streamer->start();
234234

235-
boost::mutex::scoped_lock lock(subscriber_mutex_);
235+
std::scoped_lock lock(subscriber_mutex_);
236236
image_subscribers_.push_back(streamer);
237237
return true;
238238
}

0 commit comments

Comments
 (0)