Skip to content

Commit

Permalink
remove operator () from processing interface API
Browse files Browse the repository at this point in the history
  • Loading branch information
matkatz committed Aug 15, 2018
1 parent 6850677 commit 7ac9785
Show file tree
Hide file tree
Showing 12 changed files with 14 additions and 30 deletions.
2 changes: 1 addition & 1 deletion common/model-views.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1413,7 +1413,7 @@ namespace rs2
{
if (viewer.synchronization_enable && (!viewer.is_3d_view || viewer.is_3d_depth_source(f) || viewer.is_3d_texture_source(f)))
{
viewer.s(f);
viewer.s.invoke(f);
}
else
{
Expand Down
2 changes: 1 addition & 1 deletion examples/align/rs-align.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ int main(int argc, char * argv[]) try
pip_stream.y = altered_other_frame_rect.y + altered_other_frame_rect.h - pip_stream.h - (std::max(w, h) / 25);

// Render depth (as picture in pipcture)
renderer.upload(c(aligned_depth_frame));
renderer.upload(c.process(aligned_depth_frame));
renderer.show(pip_stream);

// Using ImGui library to provide a slide controller to select the depth clipping distance
Expand Down
2 changes: 1 addition & 1 deletion examples/capture/rs-capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ int main(int argc, char * argv[]) try
{
rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera

rs2::frame depth = color_map(data.get_depth_frame()); // Find and colorize the depth data
rs2::frame depth = color_map.process(data.get_depth_frame()); // Find and colorize the depth data
rs2::frame color = data.get_color_frame(); // Find the color data

// For cameras that don't have RGB sensor, we'll render infrared frames instead of color
Expand Down
2 changes: 1 addition & 1 deletion examples/multicam/rs-multicam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ class device_container
{
rs2::frame new_frame = frameset[i];
int stream_id = new_frame.get_profile().unique_id();
view.second.frames_per_stream[stream_id] = view.second.colorize_frame(new_frame); //update view port with the new stream
view.second.frames_per_stream[stream_id] = view.second.colorize_frame.process(new_frame); //update view port with the new stream
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion examples/post-processing/rs-post-processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ void update_data(rs2::frame_queue& data, rs2::frame& colorized_depth, rs2::point
if (data.poll_for_frame(&f)) // Try to take the depth and points from the queue
{
points = pc.calculate(f); // Generate pointcloud from the depth data
colorized_depth = color_map(f); // Colorize the depth frame with a color map
colorized_depth = color_map.process(f); // Colorize the depth frame with a color map
pc.map_to(colorized_depth); // Map the colored depth to the point cloud
view.tex.upload(colorized_depth); // and upload the texture to the view (without this the view will be B&W)
}
Expand Down
4 changes: 2 additions & 2 deletions examples/record-playback/rs-record-playback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ int main(int argc, char * argv[]) try
if (!device.as<rs2::playback>())
{
frames = pipe->wait_for_frames(); // wait for next set of frames from the camera
depth = color_map(frames.get_depth_frame()); // Find and colorize the depth data
depth = color_map.process(frames.get_depth_frame()); // Find and colorize the depth data
}

// Set options for the ImGui buttons
Expand Down Expand Up @@ -164,7 +164,7 @@ int main(int argc, char * argv[]) try
rs2::playback playback = device.as<rs2::playback>();
if (pipe->poll_for_frames(&frames)) // Check if new frames are ready
{
depth = color_map(frames.get_depth_frame()); // Find and colorize the depth data for rendering
depth = color_map.process(frames.get_depth_frame()); // Find and colorize the depth data for rendering
}

// Render a seek bar for the player
Expand Down
2 changes: 1 addition & 1 deletion examples/save-to-disk/rs-save-to-disk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ int main(int argc, char * argv[]) try
{
auto stream = frame.get_profile().stream_type();
// Use the colorizer to get an rgb image for the depth stream
if (vf.is<rs2::depth_frame>()) vf = color_map(frame);
if (vf.is<rs2::depth_frame>()) vf = color_map.process(frame);

// Write images to disk
std::stringstream png_file;
Expand Down
2 changes: 1 addition & 1 deletion examples/sensor-control/helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ namespace helper
{
try
{
renderer.render(colorize(decimate.process(frame)), { 0, 0, view_width, view_height });
renderer.render(colorize.process(decimate.process(frame)), { 0, 0, view_width, view_height });
}
catch (const std::exception& e)
{
Expand Down
1 change: 0 additions & 1 deletion include/librealsense2/hpp/rs_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,7 +291,6 @@ namespace rs2
public:
virtual rs2::frame process(rs2::frame frame) const = 0;
virtual rs2_processing_block* get() const = 0;
virtual rs2::frame operator()(frame f) const = 0;
virtual ~process_interface() = default;
};

Expand Down
19 changes: 1 addition & 18 deletions include/librealsense2/hpp/rs_processing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -257,13 +257,6 @@ namespace rs2
return f;
}
/**
* Does the same thing as "process" function
*/
rs2::frame operator()(frame f) const override
{
return process(std::move(f));
}
/**
* constructor with already created low level processing block assigned.
*
* \param[in] block - low level rs2_processing_block created before.
Expand Down Expand Up @@ -368,15 +361,6 @@ namespace rs2
* Real asynchronous syncer within syncer class
*/
asynchronous_syncer() : processing_block(init(), 1) {}
/**
* Start and set the callback when the synchronization is done.
* \param[in] on_frame - callback function, will be invoked when synchronization is finished.
*/
template<class S>
void start(S on_frame)
{
start(on_frame);
}

private:
std::shared_ptr<rs2_processing_block> init()
Expand All @@ -401,7 +385,6 @@ namespace rs2
:_results(queue_size)
{
_sync.start(_results);

}

/**
Expand Down Expand Up @@ -449,7 +432,7 @@ namespace rs2

void operator()(frame f) const
{
_sync(std::move(f));
_sync.invoke(std::move(f));
}
private:
asynchronous_syncer _sync;
Expand Down
4 changes: 3 additions & 1 deletion src/proc/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ namespace librealsense
_depth_intrinsics = optional_value<rs2_intrinsics>();
_depth_units = optional_value<float>();
_extrinsics = optional_value<rs2_extrinsics>();
_other_stream = nullptr;
}

bool found_depth_intrinsics = false;
Expand Down Expand Up @@ -123,7 +124,8 @@ namespace librealsense

if (!_other_stream.get())
{
_other_stream = std::make_shared<rs2::video_stream_profile>(other.get_profile().as<rs2::video_stream_profile>());
auto osp = other.get_profile().as<rs2::video_stream_profile>();
_other_stream = std::make_shared<rs2::video_stream_profile>(osp.clone(osp.stream_type(), osp.stream_index(), osp.format()));
_other_intrinsics = optional_value<rs2_intrinsics>();
_extrinsics = optional_value<rs2_extrinsics>();
}
Expand Down
2 changes: 1 addition & 1 deletion tools/convert/converters/converter-png.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace rs2 {
}

if (frame.get_profile().stream_type() == rs2_stream::RS2_STREAM_DEPTH) {
frame = _colorizer(frame);
frame = _colorizer.process(frame);
}

std::stringstream filename;
Expand Down

0 comments on commit 7ac9785

Please sign in to comment.