Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: fix parameters and clean up node handles #136

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 3 additions & 8 deletions include/web_video_server/web_video_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#define WEB_VIDEO_SERVER_H_

#include <rclcpp/rclcpp.hpp>
#include <cv_bridge/cv_bridge.h>
#include <cv_bridge/cv_bridge.hpp>

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In my case, using humble the cv_bridge.hpp is not found by the compilator

Suggested change
#include <cv_bridge/cv_bridge.hpp>
#include <cv_bridge/cv_bridge.h>

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In my case, using humble the cv_bridge.hpp is not found by the compilator

The cv_bridge.h header seems to be deprecated:
#warning This header is obsolete, please include cv_bridge/cv_bridge.hpp instead

Since we are compiling using -werror, this breaks compilation for us.
Is there a compile time switch that we can use to check for the ros2 version?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yay, I just notice the root cause of the problem. It is because the humble branch of cv_bridge has not been updated with the new header file. Still, we can fix it here at compile time by detecting ROS distro at compile time by doing something like that.

Suggested change
#include <cv_bridge/cv_bridge.hpp>
#ifdef USE_CV_BRIDGE_H
#include <cv_bridge/cv_bridge.h>
#else
#include <cv_bridge/cv_bridge.hpp>
#endif

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This has been fixed in #149

#include <vector>
#include "web_video_server/image_streamer.h"
#include "async_web_server_cpp/http_server.hpp"
Expand All @@ -16,25 +16,20 @@ namespace web_video_server
* @class WebVideoServer
* @brief
*/
class WebVideoServer
class WebVideoServer : public rclcpp::Node
{
public:
/**
* @brief Constructor
* @return
*/
WebVideoServer(rclcpp::Node::SharedPtr &nh, rclcpp::Node::SharedPtr &private_nh);
WebVideoServer(const std::string& nodeName);

/**
* @brief Destructor - Cleans up
*/
virtual ~WebVideoServer();

/**
* @brief Starts the server and spins
*/
void spin();

void setup_cleanup_inactive_streams();

bool handle_stream(const async_web_server_cpp::HttpRequest &request,
Expand Down
2 changes: 1 addition & 1 deletion src/image_streamer.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include "web_video_server/image_streamer.h"
#include <cv_bridge/cv_bridge.h>
#include <cv_bridge/cv_bridge.hpp>

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same problem here

Suggested change
#include <cv_bridge/cv_bridge.hpp>
#include <cv_bridge/cv_bridge.h>

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same here

Suggested change
#include <cv_bridge/cv_bridge.hpp>
#ifdef USE_CV_BRIDGE_H
#include <cv_bridge/cv_bridge.h>
#else
#include <cv_bridge/cv_bridge.hpp>
#endif

#include <iostream>

namespace web_video_server
Expand Down
77 changes: 42 additions & 35 deletions src/web_video_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,47 +49,57 @@ static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler
return false;
}

WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr &nh, rclcpp::Node::SharedPtr &private_nh) :
nh_(nh), handler_group_(
WebVideoServer::WebVideoServer(const std::string& nodeName) :
Node(nodeName),
nh_(std::shared_ptr<WebVideoServer>(this, [](auto *) {})),
handler_group_(
async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found))
{
declare_parameter("port", rclcpp::PARAMETER_INTEGER);
declare_parameter("verbose", rclcpp::PARAMETER_BOOL);
declare_parameter("address", rclcpp::PARAMETER_STRING);
declare_parameter("server_threads", rclcpp::PARAMETER_INTEGER);
declare_parameter("ros_threads", rclcpp::PARAMETER_INTEGER);
declare_parameter("publish_rate", rclcpp::PARAMETER_DOUBLE);
declare_parameter("default_stream_type", rclcpp::PARAMETER_STRING);

rclcpp::Parameter parameter;
if (private_nh->get_parameter("port", parameter)) {
if (get_parameter("port", parameter)) {
port_ = parameter.as_int();
} else {
port_ = 8080;
}
if (private_nh->get_parameter("verbose", parameter)) {
if (get_parameter("verbose", parameter)) {
__verbose = parameter.as_bool();
} else {
__verbose = true;
}

if (private_nh->get_parameter("address", parameter)) {
if (get_parameter("address", parameter)) {
address_ = parameter.as_string();
} else {
address_ = "0.0.0.0";
}

int server_threads;
if (private_nh->get_parameter("server_threads", parameter)) {
if (get_parameter("server_threads", parameter)) {
server_threads = parameter.as_int();
} else {
server_threads = 1;
}

if (private_nh->get_parameter("ros_threads", parameter)) {
if (get_parameter("ros_threads", parameter)) {
ros_threads_ = parameter.as_int();
} else {
ros_threads_ = 2;
}
if (private_nh->get_parameter("publish_rate", parameter)) {
if (get_parameter("publish_rate", parameter)) {
publish_rate_ = parameter.as_double();
} else {
publish_rate_ = -1.0;
}

if (private_nh->get_parameter("default_stream_type", parameter)) {
if (get_parameter("default_stream_type", parameter)) {
__default_stream_type = parameter.as_string();
} else {
__default_stream_type = "mjpeg";
Expand Down Expand Up @@ -117,32 +127,26 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr &nh, rclcpp::Node::Shared
}

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This print was removed, but I found it really useful to check that everything is launching correctly

Suggested change
}
RCLCPP_INFO(nh_->get_logger(), "Waiting For connections on %s:%d", address_.c_str(), port_);
}

catch(boost::exception& e)
{
RCLCPP_ERROR(nh_->get_logger(), "Exception when creating the web server! %s:%d", address_.c_str(), port_);
RCLCPP_ERROR(get_logger(), "Exception when creating the web server! %s:%d", address_.c_str(), port_);
throw;
}

if ( publish_rate_ > 0 ) {
create_wall_timer(1s / publish_rate_, [this](){restreamFrames(1.0 / publish_rate_);});
}

server_->run();
}

WebVideoServer::~WebVideoServer()
{
server_->stop();
}

void WebVideoServer::setup_cleanup_inactive_streams()
{
std::function<void()> callback = std::bind(&WebVideoServer::cleanup_inactive_streams, this);
cleanup_timer_ = nh_->create_wall_timer(500ms, callback);
}

void WebVideoServer::spin()
{
server_->run();
RCLCPP_INFO(nh_->get_logger(), "Waiting For connections on %s:%d", address_.c_str(), port_);
rclcpp::executors::MultiThreadedExecutor spinner(rclcpp::ExecutorOptions(), ros_threads_);
spinner.add_node(nh_);
if ( publish_rate_ > 0 ) {
nh_->create_wall_timer(1s / publish_rate_, [this](){restreamFrames(1.0 / publish_rate_);});
}
spinner.spin();
server_->stop();
cleanup_timer_ = create_wall_timer(500ms, callback);
}

void WebVideoServer::restreamFrames( double max_age )
Expand All @@ -169,7 +173,7 @@ void WebVideoServer::cleanup_inactive_streams()
{
for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)
{
RCLCPP_INFO(nh_->get_logger(), "Removed Stream: %s", (*itr)->getTopic().c_str());
RCLCPP_INFO(get_logger(), "Removed Stream: %s", (*itr)->getTopic().c_str());
}
}
image_subscribers_.erase(new_end, image_subscribers_.end());
Expand All @@ -188,7 +192,7 @@ bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ
if (type == std::string("ros_compressed"))
{
std::string compressed_topic_name = topic + "/compressed";
auto tnat = nh_->get_topic_names_and_types();
auto tnat = get_topic_names_and_types();
bool did_find_compressed_topic = false;
for (auto topic_and_types : tnat) {
if (topic_and_types.second.size() > 1) {
Expand All @@ -203,7 +207,7 @@ bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ
}
if (!did_find_compressed_topic)
{
RCLCPP_WARN(nh_->get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str());
RCLCPP_WARN(get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str());
type = "mjpeg";
}
}
Expand Down Expand Up @@ -245,7 +249,7 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques
{

std::string compressed_topic_name = topic + "/compressed";
auto tnat = nh_->get_topic_names_and_types();
auto tnat = get_topic_names_and_types();
bool did_find_compressed_topic = false;
for (auto topic_and_types : tnat) {
if (topic_and_types.second.size() > 1) {
Expand All @@ -260,7 +264,7 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques
}
if (!did_find_compressed_topic)
{
RCLCPP_WARN(nh_->get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str());
RCLCPP_WARN(get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str());
type = "mjpeg";
}
}
Expand Down Expand Up @@ -289,7 +293,7 @@ bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest
{
std::vector<std::string> image_topics;
std::vector<std::string> camera_info_topics;
auto tnat = nh_->get_topic_names_and_types();
auto tnat = get_topic_names_and_types();
for (auto topic_and_types : tnat) {
if (topic_and_types.second.size() > 1) {
// explicitly avoid topics with more than one type
Expand Down Expand Up @@ -377,13 +381,16 @@ bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest

int main(int argc, char **argv)
{


rclcpp::init(argc, argv);
auto nh = std::make_shared<rclcpp::Node>("web_video_server");
auto private_nh = std::make_shared<rclcpp::Node>("_web_video_server");
auto node = std::make_shared<web_video_server::WebVideoServer>("web_video_server");
node->setup_cleanup_inactive_streams();
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);

web_video_server::WebVideoServer server(nh, private_nh);
server.setup_cleanup_inactive_streams();
server.spin();
executor.spin();
rclcpp::shutdown();

return (0);
}