Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Initial commit: Exchange boolean full_dp to integer sgbm_mode. #945

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions stereo_image_proc/launch/stereo_image_proc.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ def generate_launch_description():
'uniqueness_ratio': LaunchConfiguration('uniqueness_ratio'),
'P1': LaunchConfiguration('P1'),
'P2': LaunchConfiguration('P2'),
'full_dp': LaunchConfiguration('full_dp'),
'sgbm_mode': LaunchConfiguration('sgbm_mode'),
}],
remappings=[
('left/image_rect', [LaunchConfiguration('left_namespace'), '/image_rect']),
Expand Down Expand Up @@ -199,8 +199,8 @@ def generate_launch_description():
'(Semi-Global Block Matching only)'
),
DeclareLaunchArgument(
name='full_dp', default_value='False',
description='Run the full variant of the algorithm (Semi-Global Block Matching only)'
name='sgbm_mode', default_value='0',
description='The mode of the SGBM matcher to be used'
),
ComposableNodeContainer(
condition=LaunchConfigurationEquals('container', ''),
Expand Down
18 changes: 8 additions & 10 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,6 +258,12 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
"Maximum allowed difference in the left-right disparity check in pixels"
" (Semi-Global Block Matching only)",
0, 0, 128, 1);
add_param_to_map(
int_params,
"sgbm_mode",
"Mode of the SGBM stereo matcher."
"",
0, 0, 3, 1);

// Describe double parameters
std::map<std::string, std::pair<double, rcl_interfaces::msg::ParameterDescriptor>> double_params;
Expand All @@ -277,17 +283,9 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
"The second parameter ccontrolling the disparity smoothness (Semi-Global Block Matching only)",
400.0, 0.0, 4000.0, 0.0);

// Describe bool parameters
std::map<std::string, std::pair<bool, rcl_interfaces::msg::ParameterDescriptor>> bool_params;
rcl_interfaces::msg::ParameterDescriptor full_dp_descriptor;
full_dp_descriptor.description =
"Run the full variant of the algorithm (Semi-Global Block Matching only)";
bool_params["full_dp"] = std::make_pair(false, full_dp_descriptor);

// Declaring parameters triggers the previously registered callback
this->declare_parameters("", int_params);
this->declare_parameters("", double_params);
this->declare_parameters("", bool_params);

// Publisher options to allow reconfigurable qos settings and connect callback
rclcpp::PublisherOptions pub_opts;
Expand Down Expand Up @@ -424,8 +422,8 @@ rcl_interfaces::msg::SetParametersResult DisparityNode::parameterSetCb(
block_matcher_.setSpeckleSize(param.as_int());
} else if ("speckle_range" == param_name) {
block_matcher_.setSpeckleRange(param.as_int());
} else if ("full_dp" == param_name) {
block_matcher_.setSgbmMode(param.as_bool());
} else if ("sgbm_mode" == param_name) {
block_matcher_.setSgbmMode(param.as_int());
} else if ("P1" == param_name) {
block_matcher_.setP1(param.as_double());
} else if ("P2" == param_name) {
Expand Down
Loading