提交 11c9aeab 编写于 作者: G gineshidalgo99

Video can be read/written for multi-stereo processing

上级 1803f4b9
# Number of days of inactivity before an issue becomes stale
daysUntilStale: 60
# Number of days of inactivity before a stale issue is closed
daysUntilClose: 7
# Issues with these labels will never be considered stale
exemptLabels:
- bug/typo
- enhancement
# Label to use when marking an issue as stale
staleLabel: stale/old
# Comment to post when marking an issue as stale. Set to `false` to disable
markComment: >
This issue has been automatically marked as stale because it has not had
recent activity. It will be closed if no further activity occurs. Thank you
for your contributions.
# Comment to post when closing a stale issue. Set to `false` to disable
closeComment: false
......@@ -183,33 +183,38 @@ Each flag is divided into flag name, default value, and description.
- DEFINE_double(hand_scale_range, 0.4, "Analogous purpose than `scale_gap` but applied to the hand keypoint detector. Total range between smallest and biggest scale. The scales will be centered in ratio 1. E.g. if scaleRange = 0.4 and scalesNumber = 2, then there will be 2 scales, 0.8 and 1.2.");
- DEFINE_bool(hand_tracking, false, "Adding hand tracking might improve hand keypoints detection for webcam (if the frame rate is high enough, i.e. >7 FPS per GPU) and video. This is not person ID tracking, it simply looks for hands in positions at which hands were located in previous frames, but it does not guarantee the same person ID among frames.");
8. OpenPose Rendering
8. OpenPose 3-D Reconstruction
DEFINE_bool(3d, false, "Running OpenPose 3-D reconstruction demo: 1) Reading from a stereo camera system. 2) Performing 3-D reconstruction from the multiple views. 3) Displaying 3-D reconstruction results. Note that it will only display 1 person. If multiple people is present, it will fail.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per iteration, allowing tasks such as stereo camera processing (`--3d`). Note that `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the parameter folder as this number indicates.");
9. OpenPose Rendering
- DEFINE_int32(part_to_show, 0, "Prediction channel to visualize (default: 0). 0 for all the body parts, 1-18 for each body part heat map, 19 for the background heat map, 20 for all the body part heat maps together, 21 for all the PAFs, 22-40 for each body part pair PAF.");
- DEFINE_bool(disable_blending, false, "If enabled, it will render the results (keypoint skeletons or heatmaps) on a black background, instead of being rendered into the original image. Related: `part_to_show`, `alpha_pose`, and `alpha_pose`.");
9. OpenPose Rendering Pose
10. OpenPose Rendering Pose
- DEFINE_double(render_threshold, 0.05, "Only estimated keypoints whose score confidences are higher than this threshold will be rendered. Generally, a high threshold (> 0.5) will only render very clear body parts; while small thresholds (~0.1) will also output guessed and occluded keypoints, but also more false positives (i.e. wrong detections).");
- DEFINE_int32(render_pose, -1, "Set to 0 for no rendering, 1 for CPU rendering (slightly faster), and 2 for GPU rendering (slower but greater functionality, e.g. `alpha_X` flags). If -1, it will pick CPU if CPU_ONLY is enabled, or GPU if CUDA is enabled. If rendering is enabled, it will render both `outputData` and `cvOutputData` with the original image and desired body part to be shown (i.e. keypoints, heat maps or PAFs).");
- DEFINE_double(alpha_pose, 0.6, "Blending factor (range 0-1) for the body part rendering. 1 will show it completely, 0 will hide it. Only valid for GPU rendering.");
- DEFINE_double(alpha_heatmap, 0.7, "Blending factor (range 0-1) between heatmap and original frame. 1 will only show the heatmap, 0 will only show the frame. Only valid for GPU rendering.");
10. OpenPose Rendering Face
11. OpenPose Rendering Face
- DEFINE_double(face_render_threshold, 0.4, "Analogous to `render_threshold`, but applied to the face keypoints.");
- DEFINE_int32(face_render, -1, "Analogous to `render_pose` but applied to the face. Extra option: -1 to use the same configuration that `render_pose` is using.");
- DEFINE_double(face_alpha_pose, 0.6, "Analogous to `alpha_pose` but applied to face.");
- DEFINE_double(face_alpha_heatmap, 0.7, "Analogous to `alpha_heatmap` but applied to face.");
11. OpenPose Rendering Hand
12. OpenPose Rendering Hand
- DEFINE_double(hand_render_threshold, 0.2, "Analogous to `render_threshold`, but applied to the hand keypoints.");
- DEFINE_int32(hand_render, -1, "Analogous to `render_pose` but applied to the hand. Extra option: -1 to use the same configuration that `render_pose` is using.");
- DEFINE_double(hand_alpha_pose, 0.6, "Analogous to `alpha_pose` but applied to hand.");
- DEFINE_double(hand_alpha_heatmap, 0.7, "Analogous to `alpha_heatmap` but applied to hand.");
12. Display
13. Display
- DEFINE_bool(fullscreen, false, "Run in full-screen mode (press f during runtime to toggle).");
- DEFINE_bool(no_gui_verbose, false, "Do not write text on output images on GUI (e.g. number of current frame and people). It does not affect the pose rendering.");
- DEFINE_int32(display, -1, "Display mode: -1 for automatic selection; 0 for no display (useful if there is no X server and/or to slightly speed up the processing if visual output is not required); 2 for 2-D display; 3 for 3-D display (if `--3d` enabled); and 1 for both 2-D and 3-D display.");
12. Result Saving
14. Result Saving
- DEFINE_string(write_images, "", "Directory to write rendered frames in `write_images_format` image format.");
- DEFINE_string(write_images_format, "png", "File extension and format for `write_images`, e.g. png, jpg or bmp. Check the OpenCV function cv::imwrite for all compatible extensions.");
- DEFINE_string(write_video, "", "Full file path to write rendered frames in motion JPEG video format. It might fail if the final path does not finish in `.avi`. It internally uses cv::VideoWriter.");
......
......@@ -134,6 +134,10 @@ build\x64\Release\OpenPoseDemo.exe --flir_camera --3d --number_people_max 1 --fa
3. Fast stereo camera image saving (without keypoint detection) for later post-processing
```
# Ubuntu (same flags for Windows version)
# Saving video
# Note: saving in PNG rather than JPG will improve image quality, but slow down FPS (depending on hard disk writing speed and camera number)
./build/examples/openpose/openpose.bin --flir_camera --num_gpu 0 --write_video output_folder_path/video.avi
# Saving images
# Note: saving in PNG rather than JPG will improve image quality, but slow down FPS (depending on hard disk writing speed and camera number)
./build/examples/openpose/openpose.bin --flir_camera --num_gpu 0 --write_images output_folder_path/ --write_images_format jpg
```
......@@ -143,7 +147,11 @@ build\x64\Release\OpenPoseDemo.exe --flir_camera --3d --number_people_max 1 --fa
# Ubuntu (same flags for Windows version)
# Optionally add `--face` and/or `--hand` to include face and/or hands
# Assuming 3 cameras
./build/examples/openpose/openpose.bin --image_dir output_folder_path/ --image_dir_stereo 3 --3d --number_people_max 1
# Note: We highly recommend to reduce `--output_resolution`. E.g. for 3 cameras recording at 1920x1080, the resulting image is (3x1920)x1080, so we recommend e.g. 1920x360 (x3 reduction).
# Video
./build/examples/openpose/openpose.bin --video output_folder_path/video.avi --3d_views 3 --3d --number_people_max 1 --output_resolution {desired_output_resolution}
# Images
./build/examples/openpose/openpose.bin --image_dir output_folder_path/ --3d_views 3 --3d --number_people_max 1 --output_resolution {desired_output_resolution}
```
......
......@@ -187,9 +187,10 @@ OpenPose Library - Release Notes
15. Camera parameters (flir camera) are read from disk at runtime rather than being compiled.
16. 3-D reconstruction module can be implemented with different camera brands or custom image sources.
17. Flag `--write_json` includes 3-D keypoints.
18. Flag `--image_dir_stereo` added to allow `--image_dir` to load stereo images.
18. 3-D reconstruction module can be used with images and videos. Flag `--3d_views` added to allow `--image_dir` and `--video` allow loading stereo images.
19. Flag `--camera_resolution` applicable to `--flir_camera`.
20. Throw error message if requested GPU IDs does not exist (e.g. asking for 2 GPUs starting in ID 1 if there is only 2 GPUs in total).
21. VideoSaver (`--write_video`) compatible with multi-camera setting. It will save all the different views concatenated.
2. Functions or parameters renamed:
1. Flag `no_display` renamed as `display`, able to select between `NoDisplay`, `Display2D`, `Display3D`, and `DisplayAll`.
2. 3-D reconstruction demo is now inside the OpenPose demo binary.
......
......@@ -54,10 +54,6 @@ DEFINE_string(video, "", "Use a video file instea
" example video.");
DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20"
" images. Read all standard formats (jpg, png, bmp, etc.).");
DEFINE_int32(image_dir_stereo, 1, "Complementary option to `--image_dir`. OpenPose will read as many images per iteration,"
" allowing tasks such as stereo camera processing. Note that `--camera_parameters_folder`"
" must be set. OpenPose must find as many `xml` files in the parameter folder as this"
" number indicates.");
DEFINE_bool(flir_camera, false, "Whether to use FLIR (Point-Grey) stereo camera.");
DEFINE_string(ip_camera, "", "String with the IP camera URL. It supports protocols like RTSP and HTTP.");
DEFINE_uint64(frame_first, 0, "Start on desired frame number. Indexes are 0-based, i.e. the first frame has index 0.");
......@@ -151,6 +147,10 @@ DEFINE_bool(3d, false, "Running OpenPose 3-D re
" 2) Performing 3-D reconstruction from the multiple views. 3) Displaying 3-D reconstruction"
" results. Note that it will only display 1 person. If multiple people is present, it will"
" fail.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per"
" iteration, allowing tasks such as stereo camera processing (`--3d`). Note that"
" `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the"
" parameter folder as this number indicates.");
// OpenPose identification
DEFINE_bool(identification, false, "Whether to enable people identification across frames. Not available yet, coming soon.");
// OpenPose Rendering
......@@ -243,7 +243,7 @@ int openPoseDemo()
const auto producerSharedPtr = op::flagsToProducer(FLAGS_image_dir, FLAGS_video, FLAGS_ip_camera, FLAGS_camera,
FLAGS_flir_camera, FLAGS_camera_resolution, FLAGS_camera_fps,
FLAGS_camera_parameter_folder,
(unsigned int) FLAGS_image_dir_stereo);
(unsigned int) FLAGS_3d_views);
// poseModel
const auto poseModel = op::flagsToPoseModel(FLAGS_model_pose);
// JSON saving
......
......@@ -63,10 +63,6 @@ DEFINE_string(video, "", "Use a video file instea
" example video.");
DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20"
" images. Read all standard formats (jpg, png, bmp, etc.).");
DEFINE_int32(image_dir_stereo, 1, "Complementary option to `--image_dir`. OpenPose will read as many images per iteration,"
" allowing tasks such as stereo camera processing. Note that `--camera_parameters_folder`"
" must be set. OpenPose must find as many `xml` files in the parameter folder as this"
" number indicates.");
DEFINE_bool(flir_camera, false, "Whether to use FLIR (Point-Grey) stereo camera.");
DEFINE_string(ip_camera, "", "String with the IP camera URL. It supports protocols like RTSP and HTTP.");
DEFINE_uint64(frame_first, 0, "Start on desired frame number. Indexes are 0-based, i.e. the first frame has index 0.");
......@@ -160,6 +156,10 @@ DEFINE_bool(3d, false, "Running OpenPose 3-D re
" 2) Performing 3-D reconstruction from the multiple views. 3) Displaying 3-D reconstruction"
" results. Note that it will only display 1 person. If multiple people is present, it will"
" fail.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per"
" iteration, allowing tasks such as stereo camera processing (`--3d`). Note that"
" `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the"
" parameter folder as this number indicates.");
// OpenPose Rendering
DEFINE_int32(part_to_show, 0, "Prediction channel to visualize (default: 0). 0 for all the body parts, 1-18 for each body"
" part heat map, 19 for the background heat map, 20 for all the body part heat maps"
......@@ -245,7 +245,7 @@ int openPoseTutorialWrapper4()
const auto producerSharedPtr = op::flagsToProducer(FLAGS_image_dir, FLAGS_video, FLAGS_ip_camera, FLAGS_camera,
FLAGS_flir_camera, FLAGS_camera_resolution, FLAGS_camera_fps,
FLAGS_camera_parameter_folder,
(unsigned int) FLAGS_image_dir_stereo);
(unsigned int) FLAGS_3d_views);
// poseModel
const auto poseModel = op::flagsToPoseModel(FLAGS_model_pose);
// JSON saving
......
......@@ -40,10 +40,6 @@ DEFINE_string(video, "", "Use a video file instea
" example video.");
DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20"
" images. Read all standard formats (jpg, png, bmp, etc.).");
DEFINE_int32(image_dir_stereo, 1, "Complementary option to `--image_dir`. OpenPose will read as many images per iteration,"
" allowing tasks such as stereo camera processing. Note that `--camera_parameters_folder`"
" must be set. OpenPose must find as many `xml` files in the parameter folder as this"
" number indicates.");
DEFINE_bool(flir_camera, false, "Whether to use FLIR (Point-Grey) stereo camera.");
DEFINE_string(ip_camera, "", "String with the IP camera URL. It supports protocols like RTSP and HTTP.");
DEFINE_bool(process_real_time, false, "Enable to keep the original source frame rate (e.g. for video). If the processing time is"
......@@ -52,6 +48,10 @@ DEFINE_string(camera_parameter_folder, "models/cameraParameters/flir/", "String
// OpenPose
DEFINE_string(output_resolution, "-1x-1", "The image resolution (display and output). Use \"-1x-1\" to force the program to use the"
" input image resolution.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per"
" iteration, allowing tasks such as stereo camera processing (`--3d`). Note that"
" `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the"
" parameter folder as this number indicates.");
// Consumer
DEFINE_bool(fullscreen, false, "Run in full-screen mode (press f during runtime to toggle).");
......@@ -72,7 +72,7 @@ int openPoseTutorialThread1()
const auto producerSharedPtr = op::flagsToProducer(FLAGS_image_dir, FLAGS_video, FLAGS_ip_camera, FLAGS_camera,
FLAGS_flir_camera, FLAGS_camera_resolution, FLAGS_camera_fps,
FLAGS_camera_parameter_folder,
(unsigned int) FLAGS_image_dir_stereo);
(unsigned int) FLAGS_3d_views);
const auto displayProducerFpsMode = (FLAGS_process_real_time
? op::ProducerFpsMode::OriginalFps : op::ProducerFpsMode::RetrievalFps);
producerSharedPtr->setProducerFpsMode(displayProducerFpsMode);
......
......@@ -41,10 +41,6 @@ DEFINE_string(video, "", "Use a video file instea
" example video.");
DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20"
" images. Read all standard formats (jpg, png, bmp, etc.).");
DEFINE_int32(image_dir_stereo, 1, "Complementary option to `--image_dir`. OpenPose will read as many images per iteration,"
" allowing tasks such as stereo camera processing. Note that `--camera_parameters_folder`"
" must be set. OpenPose must find as many `xml` files in the parameter folder as this"
" number indicates.");
DEFINE_bool(flir_camera, false, "Whether to use FLIR (Point-Grey) stereo camera.");
DEFINE_string(ip_camera, "", "String with the IP camera URL. It supports protocols like RTSP and HTTP.");
DEFINE_bool(process_real_time, false, "Enable to keep the original source frame rate (e.g. for video). If the processing time is"
......@@ -53,6 +49,10 @@ DEFINE_string(camera_parameter_folder, "models/cameraParameters/flir/", "String
// OpenPose
DEFINE_string(output_resolution, "-1x-1", "The image resolution (display and output). Use \"-1x-1\" to force the program to use the"
" input image resolution.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per"
" iteration, allowing tasks such as stereo camera processing (`--3d`). Note that"
" `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the"
" parameter folder as this number indicates.");
// Consumer
DEFINE_bool(fullscreen, false, "Run in full-screen mode (press f during runtime to toggle).");
......@@ -106,7 +106,7 @@ int openPoseTutorialThread2()
const auto producerSharedPtr = op::flagsToProducer(FLAGS_image_dir, FLAGS_video, FLAGS_ip_camera, FLAGS_camera,
FLAGS_flir_camera, FLAGS_camera_resolution, FLAGS_camera_fps,
FLAGS_camera_parameter_folder,
(unsigned int) FLAGS_image_dir_stereo);
(unsigned int) FLAGS_3d_views);
const auto displayProducerFpsMode = (FLAGS_process_real_time
? op::ProducerFpsMode::OriginalFps : op::ProducerFpsMode::RetrievalFps);
producerSharedPtr->setProducerFpsMode(displayProducerFpsMode);
......
......@@ -53,10 +53,6 @@ DEFINE_string(video, "", "Use a video file instea
" example video.");
DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20"
" images. Read all standard formats (jpg, png, bmp, etc.).");
DEFINE_int32(image_dir_stereo, 1, "Complementary option to `--image_dir`. OpenPose will read as many images per iteration,"
" allowing tasks such as stereo camera processing. Note that `--camera_parameters_folder`"
" must be set. OpenPose must find as many `xml` files in the parameter folder as this"
" number indicates.");
DEFINE_bool(flir_camera, false, "Whether to use FLIR (Point-Grey) stereo camera.");
DEFINE_string(ip_camera, "", "String with the IP camera URL. It supports protocols like RTSP and HTTP.");
DEFINE_uint64(frame_first, 0, "Start on desired frame number. Indexes are 0-based, i.e. the first frame has index 0.");
......@@ -150,6 +146,10 @@ DEFINE_bool(3d, false, "Running OpenPose 3-D re
" 2) Performing 3-D reconstruction from the multiple views. 3) Displaying 3-D reconstruction"
" results. Note that it will only display 1 person. If multiple people is present, it will"
" fail.");
DEFINE_int32(3d_views, 1, "Complementary option to `--image_dir` or `--video`. OpenPose will read as many images per"
" iteration, allowing tasks such as stereo camera processing (`--3d`). Note that"
" `--camera_parameters_folder` must be set. OpenPose must find as many `xml` files in the"
" parameter folder as this number indicates.");
// OpenPose Rendering
DEFINE_int32(part_to_show, 0, "Prediction channel to visualize (default: 0). 0 for all the body parts, 1-18 for each body"
" part heat map, 19 for the background heat map, 20 for all the body part heat maps"
......@@ -320,7 +320,7 @@ int openPoseTutorialWrapper1()
const auto producerSharedPtr = op::flagsToProducer(FLAGS_image_dir, FLAGS_video, FLAGS_ip_camera, FLAGS_camera,
FLAGS_flir_camera, FLAGS_camera_resolution, FLAGS_camera_fps,
FLAGS_camera_parameter_folder,
(unsigned int) FLAGS_image_dir_stereo);
(unsigned int) FLAGS_3d_views);
// poseModel
const auto poseModel = op::flagsToPoseModel(FLAGS_model_pose);
// JSON saving
......
......@@ -12,8 +12,6 @@ namespace op
public:
VideoSaver(const std::string& videoSaverPath, const int cvFourcc, const double fps, const Point<int>& cvSize);
VideoSaver(const std::vector<std::string>& videoSaverPaths, const int cvFourcc, const double fps, const Point<int>& cvSize);
bool isOpened();
void write(const cv::Mat& cvMat);
......@@ -21,7 +19,12 @@ namespace op
void write(const std::vector<cv::Mat>& cvMats);
private:
std::vector<cv::VideoWriter> mVideoWriters;
const std::string mVideoSaverPath;
const int mCvFourcc;
const double mFps;
const Point<int> mCvSize;
cv::VideoWriter mVideoWriter;
unsigned int mNumberImages;
DELETE_COPY(VideoSaver);
};
......
#ifndef OPENPOSE_PRODUCER_VIDEO_READER_HPP
#define OPENPOSE_PRODUCER_VIDEO_READER_HPP
#include <openpose/3d/cameraParameterReader.hpp>
#include <openpose/core/common.hpp>
#include <openpose/producer/videoCaptureReader.hpp>
......@@ -17,25 +18,26 @@ namespace op
* Constructor of VideoReader. It opens the video as a wrapper of cv::VideoCapture. It includes a flag to
* indicate whether the video should be repeated once it is completely read.
* @param videoPath const std::string parameter with the full video path location.
* @param imageDirectoryStereo const int parameter with the number of images per iteration (>1 would represent
* stereo processing).
* @param cameraParameterPath const std::string parameter with the folder path containing the camera
* parameters (only required if imageDirectorystereo > 1).
*/
explicit VideoReader(const std::string& videoPath);
explicit VideoReader(const std::string& videoPath, const unsigned int imageDirectoryStereo = 1,
const std::string& cameraParameterPath = "");
std::vector<cv::Mat> getCameraMatrices();
std::string getNextFrameName();
inline double get(const int capProperty)
{
return VideoCaptureReader::get(capProperty);
}
double get(const int capProperty);
inline void set(const int capProperty, const double value)
{
VideoCaptureReader::set(capProperty, value);
}
void set(const int capProperty, const double value);
private:
const unsigned int mImageDirectoryStereo;
const std::string mPathName;
CameraParameterReader mCameraParameterReader;
cv::Mat getRawFrame();
......
......@@ -2,35 +2,45 @@
namespace op
{
VideoSaver::VideoSaver(const std::string& videoSaverPath, const int cvFourcc, const double fps,
const Point<int>& cvSize) :
VideoSaver::VideoSaver{std::vector<std::string>{videoSaverPath}, cvFourcc, fps, cvSize}
cv::VideoWriter openVideo(const std::string& videoSaverPath, const int cvFourcc, const double fps,
const Point<int>& cvSize, const int numberImages)
{
try
{
return cv::VideoWriter{videoSaverPath, cvFourcc, fps, cv::Size{numberImages*cvSize.x, cvSize.y}};
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
return cv::VideoWriter{};
}
}
VideoSaver::VideoSaver(const std::vector<std::string>& videoSaverPaths, const int cvFourcc, const double fps,
const Point<int>& cvSize)
VideoSaver::VideoSaver(const std::string& videoSaverPath, const int cvFourcc, const double fps,
const Point<int>& cvSize) :
mVideoSaverPath{videoSaverPath},
mCvFourcc{cvFourcc},
mFps{fps},
mCvSize{cvSize},
mNumberImages{1}
{
try
{
// Security checks
if (cvSize.x <= 0 || cvSize.y <= 0)
error("Desired frame size to save frames is <= 0.", __LINE__, __FUNCTION__, __FILE__);
if (fps <= 0.)
error("Desired fps to save frames is <= 0.", __LINE__, __FUNCTION__, __FILE__);
for (const auto& videoSaverPath : videoSaverPaths)
// Open video-writter
mVideoWriter = openVideo(mVideoSaverPath, mCvFourcc, mFps, mCvSize, mNumberImages);
// Check it was successfully opened
if (!mVideoWriter.isOpened())
{
mVideoWriters.emplace_back(videoSaverPath, cvFourcc, fps, cv::Size{cvSize.x, cvSize.y});
if (!mVideoWriters.crbegin()->isOpened())
{
const std::string errorMessage{"Video to write frames could not be opened as `" + videoSaverPath
+ "`. Please, check that:\n\t1. The path ends in `.avi`."
"\n\t2. The parent folder exists.\n\t3. OpenCV is properly"
" compiled with the FFmpeg codecs in order to save video."};
error(errorMessage, __LINE__, __FUNCTION__, __FILE__);
}
const std::string errorMessage{"Video to write frames could not be opened as `" + videoSaverPath
+ "`. Please, check that:\n\t1. The path ends in `.avi`."
"\n\t2. The parent folder exists.\n\t3. OpenCV is properly"
" compiled with the FFmpeg codecs in order to save video."};
error(errorMessage, __LINE__, __FUNCTION__, __FILE__);
}
}
catch (const std::exception& e)
......@@ -43,16 +53,7 @@ namespace op
{
try
{
bool opened = (!mVideoWriters.empty());
for (const auto& videoWriter : mVideoWriters)
{
if (!videoWriter.isOpened())
{
opened = false;
break;
}
}
return opened;
return mVideoWriter.isOpened();
}
catch (const std::exception& e)
{
......@@ -77,14 +78,25 @@ namespace op
{
try
{
// Security checks
if (!isOpened())
error("Video to write frames is not opened.", __LINE__, __FUNCTION__, __FILE__);
if (cvMats.size() != mVideoWriters.size())
error("Size cvMats != size video writers");
for (auto i = 0u ; i < mVideoWriters.size() ; i++)
mVideoWriters[i].write(cvMats[i]);
if (cvMats.empty())
error("The image(s) to be saved cannot be empty.", __LINE__, __FUNCTION__, __FILE__);
// Re-shape video writer if required
if (mNumberImages != cvMats.size())
{
mNumberImages = cvMats.size();
mVideoWriter = openVideo(mVideoSaverPath, mCvFourcc, mFps, mCvSize, mNumberImages);
}
// Concat images
cv::Mat cvOutputData;
if (cvMats.size() > 1)
cv::hconcat(cvMats.data(), cvMats.size(), cvOutputData);
else
cvOutputData = cvMats.at(0);
// Save concatenated image
mVideoWriter.write(cvOutputData);
}
catch (const std::exception& e)
{
......
......@@ -46,10 +46,10 @@ namespace op
// Security check
if (serialNumbers.size() != mImageDirectoryStereo && mImageDirectoryStereo > 1)
error("Found different number of camera parameter files than the number indicated by"
" `--image_dir_stereo` ("
" `--3d_views` ("
+ std::to_string(serialNumbers.size()) + " vs. "
+ std::to_string(mImageDirectoryStereo) + "). Make them equal or add"
+ " `--image_dir_stereo 1`",
+ " `--3d_views 1`",
__LINE__, __FUNCTION__, __FILE__);
// Get serial numbers
for (auto& serialNumber : serialNumbers)
......
......@@ -3,10 +3,39 @@
namespace op
{
VideoReader::VideoReader(const std::string & videoPath) :
VideoReader::VideoReader(const std::string & videoPath, const unsigned int imageDirectoryStereo,
const std::string& cameraParameterPath) :
VideoCaptureReader{videoPath, ProducerType::Video},
mImageDirectoryStereo{imageDirectoryStereo},
mPathName{getFileNameNoExtension(videoPath)}
{
try
{
// Read camera parameters from SN
auto serialNumbers = getFilesOnDirectory(cameraParameterPath, ".xml");
// Security check
if (serialNumbers.size() != mImageDirectoryStereo && mImageDirectoryStereo > 1)
error("Found different number of camera parameter files than the number indicated by"
" `--3d_views` ("
+ std::to_string(serialNumbers.size()) + " vs. "
+ std::to_string(mImageDirectoryStereo) + "). Make them equal or add"
+ " `--3d_views 1`",
__LINE__, __FUNCTION__, __FILE__);
// Get serial numbers
for (auto& serialNumber : serialNumbers)
serialNumber = getFileNameNoExtension(serialNumber);
// Get camera paremeters
if (mImageDirectoryStereo > 1)
mCameraParameterReader.readParameters(cameraParameterPath, serialNumbers);
// Set video size
if (mImageDirectoryStereo > 1)
set(CV_CAP_PROP_FRAME_WIDTH, get(CV_CAP_PROP_FRAME_WIDTH)/mImageDirectoryStereo);
// set(CV_CAP_PROP_FRAME_HEIGHT)
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
std::vector<cv::Mat> VideoReader::getCameraMatrices()
......@@ -35,6 +64,37 @@ namespace op
}
}
double VideoReader::get(const int capProperty)
{
try
{
if (capProperty == CV_CAP_PROP_FRAME_WIDTH)
return VideoCaptureReader::get(capProperty) / mImageDirectoryStereo;
else
return VideoCaptureReader::get(capProperty);
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
return 0.;
}
}
void VideoReader::set(const int capProperty, const double value)
{
try
{
if (capProperty == CV_CAP_PROP_FRAME_WIDTH)
return VideoCaptureReader::set(capProperty, value * mImageDirectoryStereo);
else
VideoCaptureReader::set(capProperty, value);
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
cv::Mat VideoReader::getRawFrame()
{
try
......@@ -52,7 +112,26 @@ namespace op
{
try
{
return VideoCaptureReader::getRawFrames();
auto cvMats = VideoCaptureReader::getRawFrames();
// Split image
if (cvMats.size() == 1 && mImageDirectoryStereo > 1)
{
cv::Mat cvMatConcatenated = cvMats.at(0);
cvMats.clear();
const auto individualWidth = cvMatConcatenated.cols/mImageDirectoryStereo;
for (auto i = 0u ; i < mImageDirectoryStereo ; i++)
cvMats.emplace_back(
cv::Mat(cvMatConcatenated,
cv::Rect{(int)(i*individualWidth), 0,
(int)individualWidth,
(int)cvMatConcatenated.rows}));
}
// Security check
else if (cvMats.size() != 1 && mImageDirectoryStereo > 1)
error("Unexpected error. Notify us (" + std::to_string(mImageDirectoryStereo) + " vs. "
+ std::to_string(mImageDirectoryStereo) + ").", __LINE__, __FUNCTION__, __FILE__);
// Return images
return cvMats;
}
catch (const std::exception& e)
{
......
......@@ -151,7 +151,7 @@ namespace op
return std::make_shared<ImageDirectoryReader>(imageDirectory, imageDirectoryStereo,
cameraParameterPath);
else if (type == ProducerType::Video)
return std::make_shared<VideoReader>(videoPath);
return std::make_shared<VideoReader>(videoPath, imageDirectoryStereo, cameraParameterPath);
else if (type == ProducerType::IPCamera)
return std::make_shared<IpCameraReader>(ipCameraPath);
// Flir camera
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册