Skip to content

Commit

Permalink
Return failure in SetParam callback in case of error
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Dec 14, 2023
1 parent dc6cbdc commit 8384c89
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 14 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -505,7 +505,7 @@ The following post processing filters are available:
- `depth_module.hdr_enabled`: to enable/disable HDR
- The way to set exposure and gain values for each sequence in runtime is by first selecting the sequence id, using the `depth_module.sequence_id` parameter and then modifying the `depth_module.gain`, and `depth_module.exposure`.
- From FW versions 5.14.x.x and above, if HDR is enabled, the preset configs (like exposure, gain, etc.,) cannot be updated.
- The user should disable the HDR first using `depth_module.hdr_enabled` parameter and then, update the required presets.
- Disable the HDR first using `depth_module.hdr_enabled` parameter and then, update the required presets.
- To view the effect on the infrared image for each sequence id use the `filter_by_sequence_id.sequence_id` parameter.
- To initialize these parameters in start time use the following parameters:
- `depth_module.exposure.1`
Expand Down
12 changes: 7 additions & 5 deletions realsense2_camera/src/dynamic_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ namespace realsense2_camera
_params_backend.add_on_set_parameters_callback(
[this](const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const auto & parameter : parameters)
{
try
Expand All @@ -43,15 +45,15 @@ namespace realsense2_camera
}
}
}
catch(const std::out_of_range& e)
{}
catch(const std::exception& e)
{
std::cerr << e.what() << ":" << parameter.get_name() << '\n';
result.successful = false;
result.reason = e.what();
ROS_WARN_STREAM("Set parameter {" << parameter.get_name()
<< "} failed: " << e.what());
}
}
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;

return result;
});
monitor_update_functions(); // Start parameters update thread
Expand Down
9 changes: 1 addition & 8 deletions realsense2_camera/src/sensor_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,14 +70,7 @@ std::map<std::string, int> get_enum_method(rs2::options sensor, rs2_option optio
template<class T>
void param_set_option(rs2::options sensor, rs2_option option, const rclcpp::Parameter& parameter)
{
try
{
sensor.set_option(option, parameter.get_value<T>());
}
catch(const std::exception& e)
{
std::cout << "Failed to set value: " << e.what() << std::endl;
}
sensor.set_option(option, parameter.get_value<T>());
}

void SensorParams::clearParameters()
Expand Down

0 comments on commit 8384c89

Please sign in to comment.