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 build for ROS2 Foxy #111

Merged
merged 2 commits into from
May 17, 2021
Merged
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
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,6 @@ target_link_libraries(${PROJECT_NAME}
${swscale_LIBRARIES}
)

ament_package()

#############
## Install ##
#############
Expand All @@ -81,3 +79,5 @@ install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION include/${PROJECT_NAME}
FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp"
)

ament_package()
2 changes: 1 addition & 1 deletion include/web_video_server/h264_streamer.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef H264_STREAMERS_H_
#define H264_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/libav_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
4 changes: 2 additions & 2 deletions include/web_video_server/image_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
#define IMAGE_STREAMER_H_

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.h>
#include <image_transport/transport_hints.h>
#include <image_transport/image_transport.hpp>
#include <image_transport/transport_hints.hpp>
#include <opencv2/opencv.hpp>
#include "async_web_server_cpp/http_server.hpp"
#include "async_web_server_cpp/http_request.hpp"
Expand Down
2 changes: 1 addition & 1 deletion include/web_video_server/jpeg_streamers.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef JPEG_STREAMERS_H_
#define JPEG_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/image_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
2 changes: 1 addition & 1 deletion include/web_video_server/libav_streamer.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef LIBAV_STREAMERS_H_
#define LIBAV_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/image_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
2 changes: 1 addition & 1 deletion include/web_video_server/png_streamers.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef PNG_STREAMERS_H_
#define PNG_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/image_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
2 changes: 1 addition & 1 deletion include/web_video_server/vp8_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#ifndef VP8_STREAMERS_H_
#define VP8_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/libav_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
2 changes: 1 addition & 1 deletion include/web_video_server/vp9_streamer.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef VP9_STREAMERS_H_
#define VP9_STREAMERS_H_

#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include "web_video_server/libav_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
Expand Down
4 changes: 4 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,4 +28,8 @@
<exec_depend>async_web_server_cpp</exec_depend>
<exec_depend>ffmpeg</exec_depend>
<exec_depend>sensor_msgs</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
4 changes: 2 additions & 2 deletions src/jpeg_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ MjpegStreamer::~MjpegStreamer()
void MjpegStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
{
std::vector<int> encode_params;
encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
encode_params.push_back(quality_);

std::vector<uchar> encoded_buffer;
Expand Down Expand Up @@ -63,7 +63,7 @@ JpegSnapshotStreamer::~JpegSnapshotStreamer()
void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
{
std::vector<int> encode_params;
encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
encode_params.push_back(quality_);

std::vector<uchar> encoded_buffer;
Expand Down
4 changes: 2 additions & 2 deletions src/png_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ PngStreamer::~PngStreamer()
void PngStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
{
std::vector<int> encode_params;
encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION);
encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION);
encode_params.push_back(quality_);

std::vector<uchar> encoded_buffer;
Expand Down Expand Up @@ -63,7 +63,7 @@ PngSnapshotStreamer::~PngSnapshotStreamer()
void PngSnapshotStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
{
std::vector<int> encode_params;
encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION);
encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION);
encode_params.push_back(quality_);

std::vector<uchar> encoded_buffer;
Expand Down
4 changes: 2 additions & 2 deletions src/ros_compressed_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ RosCompressedStreamer::~RosCompressedStreamer()
void RosCompressedStreamer::start() {
std::string compressed_topic = topic_ + "/compressed";
image_sub_ = nh_->create_subscription<sensor_msgs::msg::CompressedImage>(
compressed_topic, std::bind(&RosCompressedStreamer::imageCallback, this, std::placeholders::_1), 1);
compressed_topic, 1, std::bind(&RosCompressedStreamer::imageCallback, this, std::placeholders::_1));
}

void RosCompressedStreamer::restreamFrame(double max_age)
Expand Down Expand Up @@ -77,7 +77,7 @@ void RosCompressedStreamer::sendImage(const sensor_msgs::msg::CompressedImage::C
void RosCompressedStreamer::imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg) {
boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame
last_msg = msg;
last_frame = rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec);
last_frame = rclcpp::Time(msg->header.stamp);
sendImage(last_msg, last_frame);
}

Expand Down
6 changes: 3 additions & 3 deletions src/web_video_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ 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::executor::create_default_executor_arguments(), ros_threads_);
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_);});
Expand Down Expand Up @@ -298,11 +298,11 @@ bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest
auto & topic_type = topic_and_types.second[0]; // explicitly take the first
// TODO debugging
fprintf(stderr, "topic_type: %s\n", topic_type.c_str());
if (topic_type == "sensor_msgs/Image")
if (topic_type == "sensor_msgs/msg/Image")
{
image_topics.push_back(topic_name);
}
else if (topic_type == "sensor_msgs/CameraInfo")
else if (topic_type == "sensor_msgs/msg/CameraInfo")
{
camera_info_topics.push_back(topic_name);
}
Expand Down