Skip to content

Commit

Permalink
Disabling hdr while updating exposure & gain values
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Nov 30, 2023
1 parent 218e327 commit 9d423b3
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 0 deletions.
3 changes: 3 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -531,7 +531,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.
- The user should 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
14 changes: 14 additions & 0 deletions realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,15 @@ void RosSensor::UpdateSequenceIdCallback()
if (!supports(RS2_OPTION_SEQUENCE_ID))
return;

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

// 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 @@ -147,6 +156,11 @@ void RosSensor::UpdateSequenceIdCallback()
return;
}

if (is_hdr_enabled)
{
set_option(RS2_OPTION_HDR_ENABLED, true);
}

}

void RosSensor::set_sensor_parameter_to_ros(rs2_option option)
Expand Down

0 comments on commit 9d423b3

Please sign in to comment.