Skip to content

Commit

Permalink
add rotation filter to rs-post-processing example and remove override…
Browse files Browse the repository at this point in the history
… of should process
  • Loading branch information
noacoohen committed Nov 13, 2024
1 parent e09a015 commit 224ba48
Show file tree
Hide file tree
Showing 4 changed files with 50 additions and 75 deletions.
33 changes: 27 additions & 6 deletions examples/post-processing/rs-post-processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ int main(int argc, char * argv[]) try

// Declare filters
rs2::decimation_filter dec_filter; // Decimation - reduces depth frame density
rs2::rotation_filter rot_filter; // Rotation - rotates frames
rs2::threshold_filter thr_filter; // Threshold - removes values outside recommended range
rs2::spatial_filter spat_filter; // Spatial - edge-preserving spatial smoothing
rs2::temporal_filter temp_filter; // Temporal - reduces temporal noise
Expand All @@ -85,6 +86,7 @@ int main(int argc, char * argv[]) try

// The following order of emplacement will dictate the orders in which filters are applied
filters.emplace_back("Decimate", dec_filter);
filters.emplace_back( "Rotate", rot_filter );
filters.emplace_back("Threshold", thr_filter);
filters.emplace_back(disparity_filter_name, depth_to_disparity);
filters.emplace_back("Spatial", spat_filter);
Expand Down Expand Up @@ -115,11 +117,12 @@ int main(int argc, char * argv[]) try
/* Apply filters.
The implemented flow of the filters pipeline is in the following order:
1. apply decimation filter
2. apply threshold filter
3. transform the scene into disparity domain
4. apply spatial filter
5. apply temporal filter
6. revert the results back (if step Disparity filter was applied
2. apply rotation filter
3. apply threshold filter
4. transform the scene into disparity domain
5. apply spatial filter
6. apply temporal filter
7. revert the results back (if step Disparity filter was applied
to depth domain (each post processing block is optional and can be applied independantly).
*/
bool revert_disparity = false;
Expand Down Expand Up @@ -269,11 +272,29 @@ void render_ui(float w, float h, std::vector<filter_options>& filters)
ImGui::Checkbox(filter.filter_name.c_str(), &tmp_value);
filter.is_enabled = tmp_value;
ImGui::PopStyleColor();


if( filter.filter_name == "Rotate" ) // Combo box specifically for the rotation filter
{
offset_y += elements_margin;
ImGui::PushItemWidth( w / 4 );
ImGui::SetCursorPos( { offset_x, offset_y } );
static const char * rotation_modes[] = { "0", "90", "180", "270" };
static int current_rotation_mode = 0;
if( ImGui::Combo( "Rotation Angle", &current_rotation_mode, rotation_modes, 4 ) )
{
float rotation_value = std::stof( rotation_modes[current_rotation_mode] );
filter.supported_options[RS2_OPTION_ROTATION].value = rotation_value;

if (filter.supported_options.size() == 0)
// Set the filter's option using the new value
filter.filter.set_option( RS2_OPTION_ROTATION, rotation_value );
}
}
if( filter.supported_options.size() == 0 )
{
offset_y += elements_margin;
}

// Draw a slider for each of the filter's options
for (auto& option_slider_pair : filter.supported_options)
{
Expand Down
81 changes: 22 additions & 59 deletions src/proc/rotation-filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ namespace librealsense {
, _real_height( 0 )
, _rotated_width( 0 )
, _rotated_height( 0 )
, _value( 0 )
{
auto rotation_control = std::make_shared< ptr_option< int > >( rotation_min_val,
rotation_max_val,
Expand Down Expand Up @@ -51,49 +52,32 @@ namespace librealsense {
register_option( RS2_OPTION_ROTATION, rotation_control );
}

rotation_filter::rotation_filter( std::vector< stream_filter > streams_to_rotate ):
stream_filter_processing_block("Rotation Filter"),
_streams_to_rotate(streams_to_rotate),
_control_val(rotation_default_val),
_real_width(0),
_real_height(0),
_rotated_width(0),
_rotated_height(0)
{
auto rotation_control = std::make_shared< ptr_option< int > >(
rotation_min_val,
rotation_max_val,
rotation_step,
rotation_default_val,
&_control_val, "Rotation angle");

auto weak_rotation_control = std::weak_ptr< ptr_option< int > >( rotation_control );
rotation_control->on_set(
[this, weak_rotation_control]( float val )
{
auto strong_rotation_control = weak_rotation_control.lock();
if(!strong_rotation_control) return;

std::lock_guard<std::mutex> lock(_mutex);

if( ! strong_rotation_control->is_valid( val ) )
throw invalid_value_exception( rsutils::string::from()
<< "Unsupported rotation scale " << val << " is out of range." );

_value = val;

});

register_option( RS2_OPTION_ROTATION, rotation_control );
}

rs2::frame rotation_filter::process_frame(const rs2::frame_source& source, const rs2::frame& f)
{
if( _value == rotation_default_val )
return f;

auto src = f.as< rs2::video_frame >();
rs2::stream_profile profile = f.get_profile();
rs2_stream type = profile.stream_type();
rs2_extension tgt_type;
if( type == RS2_STREAM_INFRARED )
{
tgt_type = RS2_EXTENSION_VIDEO_FRAME;
}
else if( f.is< rs2::disparity_frame >() )
{
tgt_type = RS2_EXTENSION_DISPARITY_FRAME;
}
else if( f.is< rs2::depth_frame >() )
{
tgt_type = RS2_EXTENSION_DEPTH_FRAME;
}
else
{
return f;
}

auto src = f.as< rs2::video_frame >();
_target_stream_profile = profile;

if( _value == 90 || _value == -90 )
Expand All @@ -109,13 +93,6 @@ namespace librealsense {
auto bpp = src.get_bytes_per_pixel();
update_output_profile( f );

rs2_stream type = profile.stream_type();
rs2_extension tgt_type;
if( type == RS2_STREAM_COLOR || type == RS2_STREAM_INFRARED )
tgt_type = RS2_EXTENSION_VIDEO_FRAME;
else
tgt_type = f.is< rs2::disparity_frame >() ? RS2_EXTENSION_DISPARITY_FRAME : RS2_EXTENSION_DEPTH_FRAME;

if (auto tgt = prepare_target_frame(f, source, tgt_type))
{
int rotated_width = ( _value == 90 || _value == -90 ) ? src.get_height() : src.get_width();
Expand Down Expand Up @@ -242,20 +219,6 @@ namespace librealsense {
}

}

bool rotation_filter::should_process( const rs2::frame & frame )
{
if( ! frame || frame.is< rs2::frameset >() )
return false;
auto profile = frame.get_profile();
for( auto stream : _streams_to_rotate )
{
if( stream.match( frame ) )
return true;
}
return false;
}



}

4 changes: 0 additions & 4 deletions src/proc/rotation-filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@ namespace librealsense
public:
rotation_filter();

rotation_filter( std::vector< stream_filter > streams_to_rotate );

protected:
rs2::frame prepare_target_frame(const rs2::frame& f, const rs2::frame_source& source, rs2_extension tgt_type);

Expand All @@ -25,8 +23,6 @@ namespace librealsense

rs2::frame process_frame(const rs2::frame_source& source, const rs2::frame& f) override;

bool should_process( const rs2::frame & frame ) override;

private:
void update_output_profile(const rs2::frame& f);

Expand Down
7 changes: 1 addition & 6 deletions src/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,12 +263,7 @@ void log_callback_end( uint32_t fps,
dec->get_option(RS2_OPTION_STREAM_FORMAT_FILTER).set(RS2_FORMAT_Z16);
res.push_back(dec);
}
std::vector<stream_filter> streams_to_rotate;
stream_filter depth_filter( RS2_STREAM_DEPTH, RS2_FORMAT_Z16, -1);
streams_to_rotate.push_back( depth_filter );
stream_filter ir_filter( RS2_STREAM_INFRARED, RS2_FORMAT_Y8, -1 );
streams_to_rotate.push_back( ir_filter );
res.push_back( std::make_shared< rotation_filter >( streams_to_rotate ) );
res.push_back( std::make_shared< rotation_filter >( ));
return res;
}

Expand Down

0 comments on commit 224ba48

Please sign in to comment.