ROS 강좌 122 mjpeg_stream 수신
환경
이 기사는 다음 환경에서 작동합니다.
품목
값
CPU
Core i5-8250U
우분투
18.04
ROS
Melodic
Gazebo
9.0.0
파이썬
2.7.17
OpenCV
3.2.0
Qt
5.5.1
설치에 대한 자세한 내용은 ROS 강좌02 설치을 참조하십시오.
또한이 기사의 프로그램은 github에 업로드되었습니다. ROS 강좌 11 git 저장소을 참조하십시오.
개요
이전 (62 웹캠 이미지를 브라우저에서 보기)에 sensor_msgs/Image의 이미지를 web브라우저로 보는 것을 했습니다. 이번에는 이것을 c++ 프로그램에서 살펴 보겠습니다.
동영상 형식
동영상의 전송 형식은 여러 가지 있습니다만, web-video-server
에서는 motion-jpeg(mjpeg)라고 하는 형식으로 전달합니다. 또 이 형식의 스트림은 OpenCV를 사용해 수신할 수 있습니다.
OpenCV에서 수신 및 표시
소스 코드(cpp)
ros_lecture/app_lecture/src/mjpeg_opencv.cpp#include <unistd.h>
#include <memory>
#include <iostream>
#include <thread>
#include <functional>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
class MjpegView
{
public:
MjpegView(std::string target, std::string topic)
{
std::string uri = "http://" + target + "/stream?topic=" + topic;
if (!vcap_.open(uri))
{
std::cout << "Error opening video stream or file" << std::endl;
return;
}
cv::namedWindow("Output Window");
recv_thread_ = std::thread(std::bind(&MjpegView::loop, this));
}
private:
void loop(void)
{
while (true)
{
cv::Mat image;
if (!vcap_.read(image))
{
std::cout << "No frame" << std::endl;
return;
}
cv::imshow("Output Window", image);
cv::waitKey(1);
}
}
cv::VideoCapture vcap_;
std::thread recv_thread_;
};
int main(int, char**)
{
MjpegView mjpeg_view("localhost:8080", "/camera/image_raw");
while (true)
{
sleep(1);
}
}
이전 (62 웹캠 이미지를 브라우저에서 보기)에 sensor_msgs/Image의 이미지를 web브라우저로 보는 것을 했습니다. 이번에는 이것을 c++ 프로그램에서 살펴 보겠습니다.
동영상 형식
동영상의 전송 형식은 여러 가지 있습니다만,
web-video-server
에서는 motion-jpeg(mjpeg)라고 하는 형식으로 전달합니다. 또 이 형식의 스트림은 OpenCV를 사용해 수신할 수 있습니다.OpenCV에서 수신 및 표시
소스 코드(cpp)
ros_lecture/app_lecture/src/mjpeg_opencv.cpp#include <unistd.h>
#include <memory>
#include <iostream>
#include <thread>
#include <functional>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
class MjpegView
{
public:
MjpegView(std::string target, std::string topic)
{
std::string uri = "http://" + target + "/stream?topic=" + topic;
if (!vcap_.open(uri))
{
std::cout << "Error opening video stream or file" << std::endl;
return;
}
cv::namedWindow("Output Window");
recv_thread_ = std::thread(std::bind(&MjpegView::loop, this));
}
private:
void loop(void)
{
while (true)
{
cv::Mat image;
if (!vcap_.read(image))
{
std::cout << "No frame" << std::endl;
return;
}
cv::imshow("Output Window", image);
cv::waitKey(1);
}
}
cv::VideoCapture vcap_;
std::thread recv_thread_;
};
int main(int, char**)
{
MjpegView mjpeg_view("localhost:8080", "/camera/image_raw");
while (true)
{
sleep(1);
}
}
#include <unistd.h>
#include <memory>
#include <iostream>
#include <thread>
#include <functional>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
class MjpegView
{
public:
MjpegView(std::string target, std::string topic)
{
std::string uri = "http://" + target + "/stream?topic=" + topic;
if (!vcap_.open(uri))
{
std::cout << "Error opening video stream or file" << std::endl;
return;
}
cv::namedWindow("Output Window");
recv_thread_ = std::thread(std::bind(&MjpegView::loop, this));
}
private:
void loop(void)
{
while (true)
{
cv::Mat image;
if (!vcap_.read(image))
{
std::cout << "No frame" << std::endl;
return;
}
cv::imshow("Output Window", image);
cv::waitKey(1);
}
}
cv::VideoCapture vcap_;
std::thread recv_thread_;
};
int main(int, char**)
{
MjpegView mjpeg_view("localhost:8080", "/camera/image_raw");
while (true)
{
sleep(1);
}
}
cv::VideoCapture
가 mjpeg sream을 수신하는 클래스입니다. open()
에서 인수는 mjpeg stream에 uri입니다. 웹 브라우저로 보이는 url을 넣으면 액세스합니다. read()
함수에서받은 mjpeg의 프레임을 가져옵니다. 이 함수는 가져올 때까지 차단합니다. 소스 코드(CMake)
ros_lecture/app_lecture/CMakeLists.txt
find_library(PTHREAD_LIBRARY pthread) # この行を追加
find_package(OpenCV REQUIRED) # この行を追加
include_directories(
# include
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS} # この行を追加
Simple-WebSocket-Server
)
add_executable(mjpeg_opencv src/mjpeg_opencv.cpp) # この行を追加
target_link_libraries(mjpeg_opencv
${PTHREAD_LIBRARY} # この行を追加
${OpenCV_LIBRARIES} # この行を追加
)
빌드
cd ~/catkin_ws
catkin_make
실행
첫 번째 터미널
roslaunch cam_lecture sim_only.launch
두 번째 터미널
rosrun web_video_server web_video_server
세 번째 터미널
rosrun app_lecture mjpeg_opencv
다음과 같은 OpenCV 화면이 나옵니다.
OpenCV에서 수신하여 Qt로 표시합니다.
Qt 쪽이 OpenCV보다 다른 요소와 조합하여 GUI를 만드는 데 적합합니다. OpenCV에서 받고 Qt 형식으로 변환하여 Qt로 표시해 봅니다.
소스 코드(cpp)
ros_lecture/app_lecture/src/mjpeg_qt.cpp#include <future>
#include <unistd.h>
#include <memory>
#include <iostream>
#include <thread>
#include <functional>
#include <opencv2/opencv.hpp>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <QApplication>
#include <QLabel>
#include <QImage>
class MjpegView
{
public:
MjpegView(std::string target, std::string topic)
{
std::string uri = "http://" + target + "/stream?topic=" + topic;
if (!vcap_.open(uri))
{
std::cout << "Error opening video stream or file" << std::endl;
return;
}
label_ = new QLabel("######## basic1 ########");
label_->show();
recv_thread_ = std::thread(std::bind(&MjpegView::loop, this));
}
private:
void loop(void)
{
while (true)
{
cv::Mat image;
if (!vcap_.read(image))
{
std::cout << "No frame" << std::endl;
return;
}
cv::Mat rgb_image;
cv::cvtColor(image, rgb_image, cv::COLOR_BGR2RGB);
QImage qimage(rgb_image.data, rgb_image.cols, rgb_image.rows, QImage::QImage::Format_RGB888);
label_->resize(rgb_image.cols, rgb_image.rows);
label_->setPixmap(QPixmap::fromImage(qimage));
}
}
cv::VideoCapture vcap_;
QLabel* label_;
std::thread recv_thread_;
std::thread qt_thread_;
};
int main(int argc, char** argv)
{
QApplication app(argc, argv);
MjpegView mjpeg_view("localhost:8080", "/camera/image_raw");
return app.exec();
}
#include <future>
#include <unistd.h>
#include <memory>
#include <iostream>
#include <thread>
#include <functional>
#include <opencv2/opencv.hpp>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <QApplication>
#include <QLabel>
#include <QImage>
class MjpegView
{
public:
MjpegView(std::string target, std::string topic)
{
std::string uri = "http://" + target + "/stream?topic=" + topic;
if (!vcap_.open(uri))
{
std::cout << "Error opening video stream or file" << std::endl;
return;
}
label_ = new QLabel("######## basic1 ########");
label_->show();
recv_thread_ = std::thread(std::bind(&MjpegView::loop, this));
}
private:
void loop(void)
{
while (true)
{
cv::Mat image;
if (!vcap_.read(image))
{
std::cout << "No frame" << std::endl;
return;
}
cv::Mat rgb_image;
cv::cvtColor(image, rgb_image, cv::COLOR_BGR2RGB);
QImage qimage(rgb_image.data, rgb_image.cols, rgb_image.rows, QImage::QImage::Format_RGB888);
label_->resize(rgb_image.cols, rgb_image.rows);
label_->setPixmap(QPixmap::fromImage(qimage));
}
}
cv::VideoCapture vcap_;
QLabel* label_;
std::thread recv_thread_;
std::thread qt_thread_;
};
int main(int argc, char** argv)
{
QApplication app(argc, argv);
MjpegView mjpeg_view("localhost:8080", "/camera/image_raw");
return app.exec();
}
소스 코드(CMake)
set(CMAKE_AUTOMOC ON)
find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED
Core
Widgets
)
set(QT_LIBRARIES Qt5::Widgets)
add_definitions(-DQT_NO_KEYWORDS)
add_executable(mjpeg_qt src/mjpeg_qt.cpp)
target_link_libraries(mjpeg_qt
${PTHREAD_LIBRARY}
${OpenCV_LIBRARIES}
${QT_LIBRARIES}
)
Qt를 빌드하는 설정을 추가했습니다.
빌드
cd ~/catkin_ws
catkin_make
실행
첫 번째 터미널
roslaunch cam_lecture sim_only.launch
두 번째 터미널
rosrun web_video_server web_video_server
세 번째 터미널
rosrun app_lecture mjpeg_qt
다음과 같은 Qt 화면이 나옵니다.
참고
OpenCV에서 mjpg 수신
Opencv->Qt 변환
목차 페이지 링크
ROS 강좌의 목차에 대한 링크
Reference
이 문제에 관하여(ROS 강좌 122 mjpeg_stream 수신), 우리는 이곳에서 더 많은 자료를 발견하고 링크를 클릭하여 보았다
https://qiita.com/srs/items/ec631b6d985bc73f368f
텍스트를 자유롭게 공유하거나 복사할 수 있습니다.하지만 이 문서의 URL은 참조 URL로 남겨 두십시오.
우수한 개발자 콘텐츠 발견에 전념
(Collection and Share based on the CC Protocol.)
ROS 강좌의 목차에 대한 링크
Reference
이 문제에 관하여(ROS 강좌 122 mjpeg_stream 수신), 우리는 이곳에서 더 많은 자료를 발견하고 링크를 클릭하여 보았다 https://qiita.com/srs/items/ec631b6d985bc73f368f텍스트를 자유롭게 공유하거나 복사할 수 있습니다.하지만 이 문서의 URL은 참조 URL로 남겨 두십시오.
우수한 개발자 콘텐츠 발견에 전념 (Collection and Share based on the CC Protocol.)