Skip to content

Commit

Permalink
Replace nh with node
Browse files Browse the repository at this point in the history
  • Loading branch information
bjsowa committed Oct 2, 2024
1 parent da1f1bb commit 9791a0a
Show file tree
Hide file tree
Showing 18 changed files with 119 additions and 119 deletions.
4 changes: 2 additions & 2 deletions include/web_video_server/h264_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ class H264Streamer : public LibavStreamer
{
public:
H264Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~H264Streamer();
protected:
virtual void initializeEncoder();
Expand All @@ -26,7 +26,7 @@ class H264StreamerType : public LibavStreamerType
H264StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
};

}
Expand Down
8 changes: 4 additions & 4 deletions include/web_video_server/image_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class ImageStreamer
public:
ImageStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);

virtual void start() = 0;
virtual ~ImageStreamer();
Expand All @@ -41,7 +41,7 @@ class ImageStreamer
protected:
async_web_server_cpp::HttpConnectionPtr connection_;
async_web_server_cpp::HttpRequest request_;
rclcpp::Node::SharedPtr nh_;
rclcpp::Node::SharedPtr node_;
bool inactive_;
image_transport::Subscriber image_sub_;
std::string topic_;
Expand All @@ -52,7 +52,7 @@ class ImageTransportImageStreamer : public ImageStreamer
{
public:
ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
virtual ~ImageTransportImageStreamer();

virtual void start();
Expand Down Expand Up @@ -85,7 +85,7 @@ 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 nh) = 0;
rclcpp::Node::SharedPtr node) = 0;

virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0;
};
Expand Down
6 changes: 3 additions & 3 deletions include/web_video_server/jpeg_streamers.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class MjpegStreamer : public ImageTransportImageStreamer
{
public:
MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~MjpegStreamer();
protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
Expand All @@ -29,15 +29,15 @@ 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 nh);
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 nh);
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
~JpegSnapshotStreamer();
protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/libav_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class LibavStreamer : public ImageTransportImageStreamer
{
public:
LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh, const std::string &format_name, const std::string &codec_name,
rclcpp::Node::SharedPtr node, const std::string &format_name, const std::string &codec_name,
const std::string &content_type);

~LibavStreamer();
Expand Down Expand Up @@ -65,7 +65,7 @@ class LibavStreamerType : public ImageStreamerType

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

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

Expand Down
6 changes: 3 additions & 3 deletions include/web_video_server/png_streamers.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class PngStreamer : public ImageTransportImageStreamer
{
public:
PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~PngStreamer();
protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
Expand All @@ -29,15 +29,15 @@ 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 nh);
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 nh);
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node);
~PngSnapshotStreamer();
protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/ros_compressed_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class RosCompressedStreamer : public ImageStreamer
{
public:
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~RosCompressedStreamer();
virtual void start();
virtual void restreamFrame(double max_age);
Expand All @@ -37,7 +37,7 @@ 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 nh);
rclcpp::Node::SharedPtr node);
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
};

Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/vp8_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class Vp8Streamer : public LibavStreamer
{
public:
Vp8Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~Vp8Streamer();
protected:
virtual void initializeEncoder();
Expand All @@ -63,7 +63,7 @@ class Vp8StreamerType : public LibavStreamerType
Vp8StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
};

}
Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/vp9_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ class Vp9Streamer : public LibavStreamer
{
public:
Vp9Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
~Vp9Streamer();
protected:
virtual void initializeEncoder();
Expand All @@ -25,7 +25,7 @@ class Vp9StreamerType : public LibavStreamerType
Vp9StreamerType();
virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh);
rclcpp::Node::SharedPtr node);
};

}
Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/web_video_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class WebVideoServer
* @brief Constructor
* @return
*/
WebVideoServer(rclcpp::Node::SharedPtr &nh);
WebVideoServer(rclcpp::Node::SharedPtr &node);

/**
* @brief Destructor - Cleans up
Expand Down Expand Up @@ -59,7 +59,7 @@ class WebVideoServer
void restreamFrames(double max_age);
void cleanup_inactive_streams();

rclcpp::Node::SharedPtr nh_;
rclcpp::Node::SharedPtr node_;
rclcpp::WallTimer<rclcpp::VoidCallbackType>::SharedPtr cleanup_timer_;
int ros_threads_;
double publish_rate_;
Expand Down
8 changes: 4 additions & 4 deletions src/h264_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ namespace web_video_server
{

H264Streamer::H264Streamer(const async_web_server_cpp::HttpRequest& request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) :
LibavStreamer(request, connection, nh, "mp4", "libx264", "video/mp4")
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) :
LibavStreamer(request, connection, node, "mp4", "libx264", "video/mp4")
{
/* possible quality presets:
* ultrafast, superfast, veryfast, faster, fast, medium, slow, slower, veryslow, placebo
Expand Down Expand Up @@ -41,9 +41,9 @@ H264StreamerType::H264StreamerType() :

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

}
40 changes: 20 additions & 20 deletions src/image_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@ namespace web_video_server
{

ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) :
request_(request), connection_(connection), nh_(nh), inactive_(false)
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) :
request_(request), connection_(connection), node_(node), inactive_(false)
{
topic_ = request.get_query_param_value_or_default("topic", "");
}
Expand All @@ -23,8 +23,8 @@ ImageStreamer::~ImageStreamer()
}

ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) :
ImageStreamer(request, connection, nh), it_(nh), initialized_(false)
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) :
ImageStreamer(request, connection, node), it_(node), initialized_(false)
{
output_width_ = request.get_query_param_value_or_default<int>("width", -1);
output_height_ = request.get_query_param_value_or_default<int>("height", -1);
Expand All @@ -39,8 +39,8 @@ ImageTransportImageStreamer::~ImageTransportImageStreamer()

void ImageTransportImageStreamer::start()
{
image_transport::TransportHints hints(nh_.get(), default_transport_);
auto tnat = nh_->get_topic_names_and_types();
image_transport::TransportHints hints(node_.get(), default_transport_);
auto tnat = node_->get_topic_names_and_types();
inactive_ = true;
for (auto topic_and_types : tnat) {
if (topic_and_types.second.size() > 1) {
Expand All @@ -55,19 +55,19 @@ void ImageTransportImageStreamer::start()
}

// Get QoS profile from query parameter
RCLCPP_INFO(nh_->get_logger(), "Streaming topic %s with QoS profile %s", topic_.c_str(), qos_profile_name_.c_str());
RCLCPP_INFO(node_->get_logger(), "Streaming topic %s with QoS profile %s", topic_.c_str(), qos_profile_name_.c_str());
auto qos_profile = get_qos_profile_from_name(qos_profile_name_);
if (!qos_profile) {
qos_profile = rmw_qos_profile_default;
RCLCPP_ERROR(
nh_->get_logger(),
node_->get_logger(),
"Invalid QoS profile %s specified. Using default profile.",
qos_profile_name_.c_str());
}

// Create subscriber
image_sub_ = image_transport::create_subscription(
nh_.get(), topic_, std::bind(&ImageTransportImageStreamer::imageCallback, this, std::placeholders::_1),
node_.get(), topic_, std::bind(&ImageTransportImageStreamer::imageCallback, this, std::placeholders::_1),
default_transport_, qos_profile.value());
}

Expand All @@ -80,29 +80,29 @@ void ImageTransportImageStreamer::restreamFrame(double max_age)
if (inactive_ || !initialized_ )
return;
try {
if ( last_frame + rclcpp::Duration::from_seconds(max_age) < nh_->now() ) {
if ( last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) {
boost::mutex::scoped_lock lock(send_mutex_);
sendImage(output_size_image, nh_->now() ); // don't update last_frame, it may remain an old value.
sendImage(output_size_image, node_->now() ); // don't update last_frame, it may remain an old value.
}
}
catch (boost::system::system_error &e)
{
// happens when client disconnects
RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what());
RCLCPP_DEBUG(node_->get_logger(), "system_error exception: %s", e.what());
inactive_ = true;
return;
}
catch (std::exception &e)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what());
RCLCPP_ERROR(node_->get_logger(), "exception: %s", e.what());
inactive_ = true;
return;
}
catch (...)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "exception");
RCLCPP_ERROR(node_->get_logger(), "exception");
inactive_ = true;
return;
}
Expand Down Expand Up @@ -170,41 +170,41 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
initialized_ = true;
}

last_frame = nh_->now();
last_frame = node_->now();
sendImage(output_size_image, msg->header.stamp);
}
catch (cv_bridge::Exception &e)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "cv_bridge exception: %s", e.what());
RCLCPP_ERROR(node_->get_logger(), "cv_bridge exception: %s", e.what());
inactive_ = true;
return;
}
catch (cv::Exception &e)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "cv_bridge exception: %s", e.what());
RCLCPP_ERROR(node_->get_logger(), "cv_bridge exception: %s", e.what());
inactive_ = true;
return;
}
catch (boost::system::system_error &e)
{
// happens when client disconnects
RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what());
RCLCPP_DEBUG(node_->get_logger(), "system_error exception: %s", e.what());
inactive_ = true;
return;
}
catch (std::exception &e)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what());
RCLCPP_ERROR(node_->get_logger(), "exception: %s", e.what());
inactive_ = true;
return;
}
catch (...)
{
// TODO THROTTLE with 30
RCLCPP_ERROR(nh_->get_logger(), "exception");
RCLCPP_ERROR(node_->get_logger(), "exception");
inactive_ = true;
return;
}
Expand Down
12 changes: 6 additions & 6 deletions src/jpeg_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ namespace web_video_server
{

MjpegStreamer::MjpegStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) :
ImageTransportImageStreamer(request, connection, nh), stream_(std::bind(&rclcpp::Node::now, nh), connection)
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node) :
ImageTransportImageStreamer(request, connection, node), stream_(std::bind(&rclcpp::Node::now, node), connection)
{
quality_ = request.get_query_param_value_or_default<int>("quality", 95);
stream_.sendInitialHeader();
Expand All @@ -32,9 +32,9 @@ void MjpegStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)

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

std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request)
Expand All @@ -48,8 +48,8 @@ std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpReq

JpegSnapshotStreamer::JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
rclcpp::Node::SharedPtr nh) :
ImageTransportImageStreamer(request, connection, nh)
rclcpp::Node::SharedPtr node) :
ImageTransportImageStreamer(request, connection, node)
{
quality_ = request.get_query_param_value_or_default<int>("quality", 95);
}
Expand Down
Loading

0 comments on commit 9791a0a

Please sign in to comment.