Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
ftl
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Requirements
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Locked files
Build
Pipelines
Jobs
Pipeline schedules
Test cases
Artifacts
Deploy
Releases
Package registry
Container registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Code review analytics
Issue analytics
Insights
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Nicolas Pope
ftl
Commits
e2f8c986
Commit
e2f8c986
authored
5 years ago
by
Sebastian Hahta
Browse files
Options
Downloads
Patches
Plain Diff
camera params to depth resolution
parent
f35c5048
No related branches found
No related tags found
1 merge request
!196
High resolution colour
Pipeline
#16768
passed
5 years ago
Stage: all
Changes
2
Pipelines
1
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
components/rgbd-sources/src/source.cpp
+0
-16
0 additions, 16 deletions
components/rgbd-sources/src/source.cpp
components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
+22
-23
22 additions, 23 deletions
...ents/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
with
22 additions
and
39 deletions
components/rgbd-sources/src/source.cpp
+
0
−
16
View file @
e2f8c986
...
@@ -308,22 +308,6 @@ void Source::notify(int64_t ts, cv::cuda::GpuMat &c1, cv::cuda::GpuMat &c2) {
...
@@ -308,22 +308,6 @@ void Source::notify(int64_t ts, cv::cuda::GpuMat &c1, cv::cuda::GpuMat &c2) {
impl_
->
params_
=
impl_
->
params_
.
scaled
(
max_width
,
max_height
);
impl_
->
params_
=
impl_
->
params_
.
scaled
(
max_width
,
max_height
);
}
}
// Should channel 1 be scaled?
if
(
c1
.
cols
<
max_width
||
c1
.
rows
<
max_height
)
{
LOG
(
WARNING
)
<<
"Resizing on GPU"
;
cv
::
cuda
::
resize
(
c1
,
c1
,
cv
::
Size
(
max_width
,
max_height
));
}
// Should channel 2 be scaled?
if
(
!
c2
.
empty
()
&&
(
c2
.
cols
<
max_width
||
c2
.
rows
<
max_height
))
{
LOG
(
WARNING
)
<<
"Resizing on GPU"
;
if
(
c2
.
type
()
==
CV_32F
)
{
cv
::
cuda
::
resize
(
c2
,
c2
,
cv
::
Size
(
max_width
,
max_height
),
0.0
,
0.0
,
cv
::
INTER_NEAREST
);
}
else
{
cv
::
cuda
::
resize
(
c2
,
c2
,
cv
::
Size
(
max_width
,
max_height
));
}
}
if
(
callback_
)
callback_
(
ts
,
c1
,
c2
);
if
(
callback_
)
callback_
(
ts
,
c1
,
c2
);
}
}
...
...
This diff is collapsed.
Click to expand it.
components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
+
22
−
23
View file @
e2f8c986
...
@@ -71,7 +71,28 @@ void StereoVideoSource::init(const string &file) {
...
@@ -71,7 +71,28 @@ void StereoVideoSource::init(const string &file) {
color_size_
=
cv
::
Size
(
lsrc_
->
width
(),
lsrc_
->
height
());
color_size_
=
cv
::
Size
(
lsrc_
->
width
(),
lsrc_
->
height
());
frames_
=
std
::
vector
<
Frame
>
(
2
);
frames_
=
std
::
vector
<
Frame
>
(
2
);
calib_
=
ftl
::
create
<
Calibrate
>
(
host_
,
"calibration"
,
color_size_
,
stream_
);
pipeline_input_
=
ftl
::
config
::
create
<
ftl
::
operators
::
Graph
>
(
host_
,
"input"
);
#ifdef HAVE_OPTFLOW
pipeline_input_
->
append
<
ftl
::
operators
::
NVOpticalFlow
>
(
"optflow"
);
#endif
pipeline_depth_
=
ftl
::
config
::
create
<
ftl
::
operators
::
Graph
>
(
host_
,
"disparity"
);
depth_size_
=
cv
::
Size
(
pipeline_depth_
->
value
(
"width"
,
color_size_
.
width
),
pipeline_depth_
->
value
(
"height"
,
color_size_
.
height
));
pipeline_depth_
->
append
<
ftl
::
operators
::
FixstarsSGM
>
(
"algorithm"
);
#ifdef HAVE_OPTFLOW
pipeline_depth_
->
append
<
ftl
::
operators
::
OpticalFlowTemporalSmoothing
>
(
"optflow_filter"
);
#endif
pipeline_depth_
->
append
<
ftl
::
operators
::
DisparityBilateralFilter
>
(
"bilateral_filter"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
DisparityToDepth
>
(
"calculate_depth"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
ColourChannels
>
(
"colour"
);
// Convert BGR to BGRA
pipeline_depth_
->
append
<
ftl
::
operators
::
Normals
>
(
"normals"
);
// Estimate surface normals
pipeline_depth_
->
append
<
ftl
::
operators
::
CrossSupport
>
(
"cross"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
DiscontinuityMask
>
(
"discontinuity_mask"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
AggreMLS
>
(
"mls"
);
// Perform MLS (using smoothing channel)
calib_
=
ftl
::
create
<
Calibrate
>
(
host_
,
"calibration"
,
depth_size_
,
stream_
);
if
(
!
calib_
->
isCalibrated
())
LOG
(
WARNING
)
<<
"Cameras are not calibrated!"
;
if
(
!
calib_
->
isCalibrated
())
LOG
(
WARNING
)
<<
"Cameras are not calibrated!"
;
// Generate camera parameters from camera matrix
// Generate camera parameters from camera matrix
...
@@ -125,28 +146,6 @@ void StereoVideoSource::init(const string &file) {
...
@@ -125,28 +146,6 @@ void StereoVideoSource::init(const string &file) {
mask_l_gpu
.
download
(
mask_l
);
mask_l_gpu
.
download
(
mask_l
);
mask_l_
=
(
mask_l
==
0
);
mask_l_
=
(
mask_l
==
0
);
pipeline_input_
=
ftl
::
config
::
create
<
ftl
::
operators
::
Graph
>
(
host_
,
"input"
);
#ifdef HAVE_OPTFLOW
pipeline_input_
->
append
<
ftl
::
operators
::
NVOpticalFlow
>
(
"optflow"
);
#endif
pipeline_depth_
=
ftl
::
config
::
create
<
ftl
::
operators
::
Graph
>
(
host_
,
"disparity"
);
depth_size_
=
cv
::
Size
(
pipeline_depth_
->
value
(
"width"
,
color_size_
.
width
),
pipeline_depth_
->
value
(
"height"
,
color_size_
.
height
));
pipeline_depth_
->
append
<
ftl
::
operators
::
FixstarsSGM
>
(
"algorithm"
);
#ifdef HAVE_OPTFLOW
pipeline_depth_
->
append
<
ftl
::
operators
::
OpticalFlowTemporalSmoothing
>
(
"optflow_filter"
);
#endif
pipeline_depth_
->
append
<
ftl
::
operators
::
DisparityBilateralFilter
>
(
"bilateral_filter"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
DisparityToDepth
>
(
"calculate_depth"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
ColourChannels
>
(
"colour"
);
// Convert BGR to BGRA
pipeline_depth_
->
append
<
ftl
::
operators
::
Normals
>
(
"normals"
);
// Estimate surface normals
pipeline_depth_
->
append
<
ftl
::
operators
::
CrossSupport
>
(
"cross"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
DiscontinuityMask
>
(
"discontinuity_mask"
);
pipeline_depth_
->
append
<
ftl
::
operators
::
AggreMLS
>
(
"mls"
);
// Perform MLS (using smoothing channel)
LOG
(
INFO
)
<<
"StereoVideo source ready..."
;
LOG
(
INFO
)
<<
"StereoVideo source ready..."
;
ready_
=
true
;
ready_
=
true
;
}
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment