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

Fixing the data_type of ROS Params exposure & gain #2940

Merged
merged 2 commits into from
Dec 19, 2023
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
1 change: 1 addition & 0 deletions realsense2_camera/include/ros_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@ namespace realsense2_camera
void set_sensor_auto_exposure_roi();
void registerAutoExposureROIOptions();
void UpdateSequenceIdCallback();
template<class T>
void set_sensor_parameter_to_ros(rs2_option option);

private:
Expand Down
7 changes: 4 additions & 3 deletions realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,8 +154,8 @@ void RosSensor::UpdateSequenceIdCallback()
{
set_option(RS2_OPTION_SEQUENCE_ID, parameter.get_value<int>());
std::vector<std::function<void()> > funcs;
funcs.push_back([this](){set_sensor_parameter_to_ros(RS2_OPTION_GAIN);});
funcs.push_back([this](){set_sensor_parameter_to_ros(RS2_OPTION_EXPOSURE);});
funcs.push_back([this](){set_sensor_parameter_to_ros<int>(RS2_OPTION_GAIN);});
funcs.push_back([this](){set_sensor_parameter_to_ros<int>(RS2_OPTION_EXPOSURE);});
_params.getParameters()->pushUpdateFunctions(funcs);
});
}
Expand All @@ -166,11 +166,12 @@ void RosSensor::UpdateSequenceIdCallback()
}
}

template<class T>
void RosSensor::set_sensor_parameter_to_ros(rs2_option option)
{
std::string module_name = create_graph_resource_name(rs2_to_ros(get_info(RS2_CAMERA_INFO_NAME)));
const std::string option_name(module_name + "." + create_graph_resource_name(rs2_option_to_string(option)));
float value = get_option(option);
auto value = static_cast<T>(get_option(option));
_params.getParameters()->setRosParamValue(option_name, &value);
}

Expand Down