Skip to content

Commit

Permalink
fix coverity scan issues
Browse files Browse the repository at this point in the history
  • Loading branch information
SamerKhshiboun committed Jan 8, 2024
1 parent 79b7fb3 commit 3c86c17
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 12 deletions.
1 change: 0 additions & 1 deletion realsense2_camera/include/named_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<int>(_filters.size()));
for (auto filter_it : _filters)
for (auto& filter_it : _filters)
{
frameset = filter_it->Process(frameset);
}
Expand Down
12 changes: 6 additions & 6 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 All @@ -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;
}
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
2 changes: 1 addition & 1 deletion realsense2_camera/src/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ void BaseRealSenseNode::setDynamicParams()
}
sort(enum_vec.begin(), enum_vec.end(), [](std::pair<std::string, int> e1, std::pair<std::string, int> 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;
}
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/src/profile_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ std::map<stream_index_pair, rs2::stream_profile> ProfilesManager::getDefaultProf
void ProfilesManager::addWantedProfiles(std::vector<rs2::stream_profile>& wanted_profiles)
{
std::map<stream_index_pair, bool> 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;
Expand Down
4 changes: 2 additions & 2 deletions realsense2_camera/src/sensor_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -277,14 +277,14 @@ void SensorParams::registerDynamicOptions(rs2::options sensor, const std::string
{
std::vector<std::pair<std::string, int> > 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<std::string, int> e1, std::pair<std::string, int> 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;
}
Expand Down

0 comments on commit 3c86c17

Please sign in to comment.