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

Disabling hdr while updating exposure & gain values #2934

Merged
merged 3 commits into from
Dec 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
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
3 changes: 3 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -502,7 +502,10 @@ The following post processing filters are available:
* The depth FOV and the texture FOV are not similar. By default, pointcloud is limited to the section of depth containing the texture. You can have a full depth to pointcloud, coloring the regions beyond the texture with zeros, by setting `pointcloud.allow_no_texture_points` to true.
* pointcloud is of an unordered format by default. This can be changed by setting `pointcloud.ordered_pc` to true.
- ```hdr_merge```: Allows depth image to be created by merging the information from 2 consecutive frames, taken with different exposure and gain values.
- `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.
- 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;
Nir-Az marked this conversation as resolved.
Show resolved Hide resolved
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
19 changes: 18 additions & 1 deletion realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,24 @@ void RosSensor::UpdateSequenceIdCallback()
if (!supports(RS2_OPTION_SEQUENCE_ID))
return;

bool is_hdr_enabled = static_cast<bool>(get_option(RS2_OPTION_HDR_ENABLED));

// Deleter to revert back the RS2_OPTION_HDR_ENABLED value at the end.
auto deleter_to_revert_hdr = std::unique_ptr<bool, std::function<void(bool*)>>(&is_hdr_enabled,
[&](bool* enable_back_hdr) {
if (enable_back_hdr && *enable_back_hdr)
{
set_option(RS2_OPTION_HDR_ENABLED, true);
}
});

// From FW version 5.14.x.x, if HDR is enabled, updating UVC controls like exposure, gain , etc are restricted.
// So, disable it before updating.
if (is_hdr_enabled)
{
set_option(RS2_OPTION_HDR_ENABLED, false);
}

int original_seq_id = static_cast<int>(get_option(RS2_OPTION_SEQUENCE_ID)); // To Set back to default.
std::string module_name = create_graph_resource_name(rs2_to_ros(get_info(RS2_CAMERA_INFO_NAME)));

Expand Down Expand Up @@ -146,7 +164,6 @@ void RosSensor::UpdateSequenceIdCallback()
ROS_WARN_STREAM("Setting alternative callback: Failed to set parameter:" << option_name << " : " << e.what());
return;
}

}

void RosSensor::set_sensor_parameter_to_ros(rs2_option option)
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>());
Nir-Az marked this conversation as resolved.
Show resolved Hide resolved
}

void SensorParams::clearParameters()
Expand Down
Loading