From 3c86c178bbad0bd27aabfa56caf29216e337caeb Mon Sep 17 00:00:00 2001 From: SamerKhshiboun Date: Mon, 8 Jan 2024 10:04:32 +0200 Subject: [PATCH] fix coverity scan issues --- realsense2_camera/include/named_filter.h | 1 - realsense2_camera/src/base_realsense_node.cpp | 2 +- realsense2_camera/src/dynamic_params.cpp | 12 ++++++------ realsense2_camera/src/parameters.cpp | 2 +- realsense2_camera/src/profile_manager.cpp | 2 +- realsense2_camera/src/sensor_params.cpp | 4 ++-- 6 files changed, 11 insertions(+), 12 deletions(-) diff --git a/realsense2_camera/include/named_filter.h b/realsense2_camera/include/named_filter.h index 7fef1564c0..184902a8ce 100644 --- a/realsense2_camera/include/named_filter.h +++ b/realsense2_camera/include/named_filter.h @@ -60,7 +60,6 @@ namespace realsense2_camera void setParameters(); private: - bool _is_enabled_pc; rclcpp::Node& _node; bool _allow_no_texture_points; bool _ordered_pc; diff --git a/realsense2_camera/src/base_realsense_node.cpp b/realsense2_camera/src/base_realsense_node.cpp index a3ebd0e675..f13750a964 100755 --- a/realsense2_camera/src/base_realsense_node.cpp +++ b/realsense2_camera/src/base_realsense_node.cpp @@ -537,7 +537,7 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame) rs2::video_frame original_color_frame = frameset.get_color_frame(); ROS_DEBUG("num_filters: %d", static_cast(_filters.size())); - for (auto filter_it : _filters) + for (auto& filter_it : _filters) { frameset = filter_it->Process(frameset); } diff --git a/realsense2_camera/src/dynamic_params.cpp b/realsense2_camera/src/dynamic_params.cpp index 45db52d90a..c081dcbf0a 100644 --- a/realsense2_camera/src/dynamic_params.cpp +++ b/realsense2_camera/src/dynamic_params.cpp @@ -108,8 +108,8 @@ namespace realsense2_camera template T Parameters::setParam(std::string param_name, const T& initial_value, - std::function func, - rcl_interfaces::msg::ParameterDescriptor descriptor) + std::function& func, + rcl_interfaces::msg::ParameterDescriptor& descriptor) { T result_value(initial_value); try @@ -124,11 +124,11 @@ namespace realsense2_camera catch(const std::exception& e) { std::stringstream range; - for (auto val : descriptor.floating_point_range) + for (auto& val : descriptor.floating_point_range) { range << val.from_value << ", " << val.to_value; } - for (auto val : descriptor.integer_range) + for (auto& val : descriptor.integer_range) { range << val.from_value << ", " << val.to_value; } @@ -168,8 +168,8 @@ namespace realsense2_camera // if param is destroyed the behavior of the callback is undefined. template void Parameters::setParamT(std::string param_name, T& param, - std::function func, - rcl_interfaces::msg::ParameterDescriptor descriptor) + std::function& func, + rcl_interfaces::msg::ParameterDescriptor& descriptor) { param = setParam(param_name, param, diff --git a/realsense2_camera/src/parameters.cpp b/realsense2_camera/src/parameters.cpp index 72523cb801..c8cb7f0282 100644 --- a/realsense2_camera/src/parameters.cpp +++ b/realsense2_camera/src/parameters.cpp @@ -115,7 +115,7 @@ void BaseRealSenseNode::setDynamicParams() } sort(enum_vec.begin(), enum_vec.end(), [](std::pair e1, std::pair e2){return (e1.second < e2.second);}); std::stringstream enum_str_values; - for (auto vec_iter : enum_vec) + for (auto& vec_iter : enum_vec) { enum_str_values << std::setw(longest_desc+6) << std::left << vec_iter.first << " : " << vec_iter.second << std::endl; } diff --git a/realsense2_camera/src/profile_manager.cpp b/realsense2_camera/src/profile_manager.cpp index 95dadbbad6..3301692b48 100644 --- a/realsense2_camera/src/profile_manager.cpp +++ b/realsense2_camera/src/profile_manager.cpp @@ -142,7 +142,7 @@ std::map ProfilesManager::getDefaultProf void ProfilesManager::addWantedProfiles(std::vector& wanted_profiles) { std::map found_sips; - for (auto profile : _all_profiles) + for (auto const & profile : _all_profiles) { stream_index_pair sip(profile.stream_type(), profile.stream_index()); if (!(*_enabled_profiles[sip])) continue; diff --git a/realsense2_camera/src/sensor_params.cpp b/realsense2_camera/src/sensor_params.cpp index c347a1d979..b0f850cf49 100644 --- a/realsense2_camera/src/sensor_params.cpp +++ b/realsense2_camera/src/sensor_params.cpp @@ -277,14 +277,14 @@ void SensorParams::registerDynamicOptions(rs2::options sensor, const std::string { std::vector > enum_vec; size_t longest_desc(0); - for (auto enum_iter : enum_dict) + for (auto& enum_iter : enum_dict) { enum_vec.push_back(std::make_pair(enum_iter.first, enum_iter.second)); longest_desc = std::max(longest_desc, enum_iter.first.size()); } sort(enum_vec.begin(), enum_vec.end(), [](std::pair e1, std::pair e2){return (e1.second < e2.second);}); std::stringstream description; - for (auto vec_iter : enum_vec) + for (auto& vec_iter : enum_vec) { description << std::setw(longest_desc+6) << std::left << vec_iter.first << " : " << vec_iter.second << std::endl; }