Skip to content

Commit

Permalink
Reformat the code with uncrustify (#158)
Browse files Browse the repository at this point in the history
* Reformat using ament_uncrustify

* Add ament_cmake_uncrustify test

* Fix ament_uncrustify errors on humble
  • Loading branch information
bjsowa authored Oct 3, 2024
1 parent ff6a8e6 commit 140ff53
Show file tree
Hide file tree
Showing 22 changed files with 598 additions and 532 deletions.
15 changes: 9 additions & 6 deletions include/web_video_server/h264_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,12 @@ namespace web_video_server
class H264Streamer : public LibavStreamer
{
public:
H264Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
H264Streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
~H264Streamer();

protected:
virtual void initializeEncoder();
std::string preset_;
Expand All @@ -24,12 +27,12 @@ class H264StreamerType : public LibavStreamerType
{
public:
H264StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
virtual boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
};

}

#endif

29 changes: 16 additions & 13 deletions include/web_video_server/image_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,10 @@ namespace web_video_server
class ImageStreamer
{
public:
ImageStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
ImageStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);

virtual void start() = 0;
virtual ~ImageStreamer();
Expand All @@ -26,7 +27,6 @@ class ImageStreamer
{
return inactive_;
}
;

/**
* Restreams the last received image frame if older than max_age.
Expand All @@ -37,7 +37,7 @@ class ImageStreamer
{
return topic_;
}
;

protected:
async_web_server_cpp::HttpConnectionPtr connection_;
async_web_server_cpp::HttpRequest request_;
Expand All @@ -51,14 +51,16 @@ class ImageStreamer
class ImageTransportImageStreamer : public ImageStreamer
{
public:
ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
ImageTransportImageStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
virtual ~ImageTransportImageStreamer();

virtual void start();

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time) = 0;
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time) = 0;
virtual void restreamFrame(double max_age);
virtual void initialize(const cv::Mat &);

Expand All @@ -77,17 +79,18 @@ class ImageTransportImageStreamer : public ImageStreamer
image_transport::ImageTransport it_;
bool initialized_;

void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &msg);
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg);
};

class ImageStreamerType
{
public:
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node) = 0;
virtual boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node) = 0;

virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0;
virtual std::string create_viewer(const async_web_server_cpp::HttpRequest & request) = 0;
};

}
Expand Down
26 changes: 16 additions & 10 deletions include/web_video_server/jpeg_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,14 @@ namespace web_video_server
class MjpegStreamer : public ImageTransportImageStreamer
{
public:
MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
MjpegStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
~MjpegStreamer();

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);

private:
MultipartStream stream_;
Expand All @@ -27,20 +30,23 @@ class MjpegStreamer : public ImageTransportImageStreamer
class MjpegStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest & request);
};

class JpegSnapshotStreamer : public ImageTransportImageStreamer
{
public:
JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
JpegSnapshotStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
~JpegSnapshotStreamer();

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);

private:
int quality_;
Expand Down
41 changes: 23 additions & 18 deletions include/web_video_server/libav_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,26 +24,28 @@ namespace web_video_server
class LibavStreamer : public ImageTransportImageStreamer
{
public:
LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node, const std::string &format_name, const std::string &codec_name,
const std::string &content_type);
LibavStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node, const std::string & format_name, const std::string & codec_name,
const std::string & content_type);

~LibavStreamer();

protected:
virtual void initializeEncoder();
virtual void sendImage(const cv::Mat&, const rclcpp::Time& time);
virtual void initialize(const cv::Mat&);
AVFormatContext* format_context_;
const AVCodec* codec_;
AVCodecContext* codec_context_;
AVStream* video_stream_;
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
virtual void initialize(const cv::Mat &);
AVFormatContext * format_context_;
const AVCodec * codec_;
AVCodecContext * codec_context_;
AVStream * video_stream_;

AVDictionary* opt_; // container format options
AVDictionary * opt_; // container format options

private:
AVFrame* frame_;
struct SwsContext* sws_context_;
AVFrame * frame_;
struct SwsContext * sws_context_;
rclcpp::Time first_image_timestamp_;
boost::mutex encode_mutex_;

Expand All @@ -55,19 +57,22 @@ class LibavStreamer : public ImageTransportImageStreamer
int qmax_;
int gop_;

uint8_t* io_buffer_; // custom IO buffer
uint8_t * io_buffer_; // custom IO buffer
};

class LibavStreamerType : public ImageStreamerType
{
public:
LibavStreamerType(const std::string &format_name, const std::string &codec_name, const std::string &content_type);
LibavStreamerType(
const std::string & format_name, const std::string & codec_name,
const std::string & content_type);

boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);

std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
std::string create_viewer(const async_web_server_cpp::HttpRequest & request);

private:
const std::string format_name_;
Expand Down
28 changes: 17 additions & 11 deletions include/web_video_server/multipart_stream.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,24 +9,30 @@
namespace web_video_server
{

struct PendingFooter {
struct PendingFooter
{
rclcpp::Time timestamp;
std::weak_ptr<std::string> contents;
};

class MultipartStream {
class MultipartStream
{
public:
MultipartStream(std::function<rclcpp::Time()> get_now,
async_web_server_cpp::HttpConnectionPtr& connection,
const std::string& boundry="boundarydonotcross",
std::size_t max_queue_size=1);
MultipartStream(
std::function<rclcpp::Time()> get_now,
async_web_server_cpp::HttpConnectionPtr & connection,
const std::string & boundry = "boundarydonotcross",
std::size_t max_queue_size = 1);

void sendInitialHeader();
void sendPartHeader(const rclcpp::Time &time, const std::string& type, size_t payload_size);
void sendPartFooter(const rclcpp::Time &time);
void sendPartAndClear(const rclcpp::Time &time, const std::string& type, std::vector<unsigned char> &data);
void sendPart(const rclcpp::Time &time, const std::string& type, const boost::asio::const_buffer &buffer,
async_web_server_cpp::HttpConnection::ResourcePtr resource);
void sendPartHeader(const rclcpp::Time & time, const std::string & type, size_t payload_size);
void sendPartFooter(const rclcpp::Time & time);
void sendPartAndClear(
const rclcpp::Time & time, const std::string & type,
std::vector<unsigned char> & data);
void sendPart(
const rclcpp::Time & time, const std::string & type, const boost::asio::const_buffer & buffer,
async_web_server_cpp::HttpConnection::ResourcePtr resource);

private:
bool isBusy();
Expand Down
26 changes: 16 additions & 10 deletions include/web_video_server/png_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,14 @@ namespace web_video_server
class PngStreamer : public ImageTransportImageStreamer
{
public:
PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
PngStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
~PngStreamer();

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);

private:
MultipartStream stream_;
Expand All @@ -27,20 +30,23 @@ class PngStreamer : public ImageTransportImageStreamer
class PngStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest & request);
};

class PngSnapshotStreamer : public ImageTransportImageStreamer
{
public:
PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
PngSnapshotStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
~PngSnapshotStreamer();

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);

private:
int quality_;
Expand Down
19 changes: 12 additions & 7 deletions include/web_video_server/ros_compressed_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,18 @@ namespace web_video_server
class RosCompressedStreamer : public ImageStreamer
{
public:
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
RosCompressedStreamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
~RosCompressedStreamer();
virtual void start();
virtual void restreamFrame(double max_age);

protected:
virtual void sendImage(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg, const rclcpp::Time &time);
virtual void sendImage(
const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg,
const rclcpp::Time & time);

private:
void imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg);
Expand All @@ -35,10 +39,11 @@ class RosCompressedStreamer : public ImageStreamer
class RosCompressedStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest & request);
};

}
Expand Down
16 changes: 10 additions & 6 deletions include/web_video_server/vp8_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,11 +48,15 @@ namespace web_video_server
class Vp8Streamer : public LibavStreamer
{
public:
Vp8Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
Vp8Streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
~Vp8Streamer();

protected:
virtual void initializeEncoder();

private:
std::string quality_;
};
Expand All @@ -61,12 +65,12 @@ class Vp8StreamerType : public LibavStreamerType
{
public:
Vp8StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
virtual boost::shared_ptr<ImageStreamer> create_streamer(
const async_web_server_cpp::HttpRequest & request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr node);
};

}

#endif

Loading

0 comments on commit 140ff53

Please sign in to comment.