Skip to content

Commit

Permalink
Merge branch 'coverity-fixes-v1' of https://github.com/SamerKhshiboun…
Browse files Browse the repository at this point in the history
…/realsense-ros into coverity-fixes-v1
  • Loading branch information
SamerKhshiboun committed Jan 8, 2024
2 parents dc44bfc + 3c86c17 commit 24e5505
Showing 1 changed file with 11 additions and 11 deletions.
22 changes: 11 additions & 11 deletions realsense2_camera/src/dynamic_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,8 @@ namespace realsense2_camera

template <class T>
T Parameters::setParam(std::string param_name, const T& initial_value,
std::function<void(const rclcpp::Parameter&)>& func,
rcl_interfaces::msg::ParameterDescriptor& descriptor)
std::function<void(const rclcpp::Parameter&)> func,
rcl_interfaces::msg::ParameterDescriptor descriptor)
{
T result_value(initial_value);
try
Expand Down Expand Up @@ -168,8 +168,8 @@ namespace realsense2_camera
// if param is destroyed the behavior of the callback is undefined.
template <class T>
void Parameters::setParamT(std::string param_name, T& param,
std::function<void(const rclcpp::Parameter&)>& func,
rcl_interfaces::msg::ParameterDescriptor& descriptor)
std::function<void(const rclcpp::Parameter&)> func,
rcl_interfaces::msg::ParameterDescriptor descriptor)

{
param = setParam<T>(param_name, param,
Expand Down Expand Up @@ -267,14 +267,14 @@ namespace realsense2_camera
_param_functions.erase(param_name);
}

template void Parameters::setParamT<bool>(std::string param_name, bool& param, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template void Parameters::setParamT<int>(std::string param_name, int& param, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template void Parameters::setParamT<double>(std::string param_name, double& param, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template void Parameters::setParamT<bool>(std::string param_name, bool& param, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);
template void Parameters::setParamT<int>(std::string param_name, int& param, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);
template void Parameters::setParamT<double>(std::string param_name, double& param, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);

template bool Parameters::setParam<bool>(std::string param_name, const bool& initial_value, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template int Parameters::setParam<int>(std::string param_name, const int& initial_value, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template double Parameters::setParam<double>(std::string param_name, const double& initial_value, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template std::string Parameters::setParam<std::string>(std::string param_name, const std::string& initial_value, std::function<void(const rclcpp::Parameter&)>& func, rcl_interfaces::msg::ParameterDescriptor& descriptor);
template bool Parameters::setParam<bool>(std::string param_name, const bool& initial_value, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);
template int Parameters::setParam<int>(std::string param_name, const int& initial_value, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);
template double Parameters::setParam<double>(std::string param_name, const double& initial_value, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);
template std::string Parameters::setParam<std::string>(std::string param_name, const std::string& initial_value, std::function<void(const rclcpp::Parameter&)> func, rcl_interfaces::msg::ParameterDescriptor descriptor);

template void Parameters::setParamValue<int>(int& param, const int& value);
template void Parameters::setParamValue<bool>(bool& param, const bool& value);
Expand Down

0 comments on commit 24e5505

Please sign in to comment.