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

fix(autoware_probabilistic_occupancy_grid_map): fix unusedFunction #8574

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -120,8 +120,6 @@ bool extractCommonPointCloud(
const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc,
sensor_msgs::msg::PointCloud2 & output_obstacle_pc);

unsigned char getApproximateOccupancyState(const unsigned char & value);

} // namespace utils
} // namespace autoware::occupancy_grid_map

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,21 +191,5 @@ bool extractCommonPointCloud(
return true;
}

/**
* @brief Convert unsigned char value to closest cost value
* @param cost Cost value
* @return Probability
*/
unsigned char getApproximateOccupancyState(const unsigned char & value)
{
if (value >= cost_value::OCCUPIED_THRESHOLD) {
return cost_value::LETHAL_OBSTACLE;
} else if (value <= cost_value::FREE_THRESHOLD) {
return cost_value::FREE_SPACE;
} else {
return cost_value::NO_INFORMATION;
}
}

} // namespace utils
} // namespace autoware::occupancy_grid_map
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.90 to 6.88, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.

Check notice on line 1 in perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Code Duplication

The module no longer contains too many functions with similar structure
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -369,42 +369,6 @@
return fused_map;
}

/**
* @brief Update occupancy grid map with asynchronous input (currently unused)
*
* @param occupancy_grid_msg
*/
void GridMapFusionNode::updateGridMap(
const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg)
{
// get updater map origin

// origin is set to current updater map
auto map_for_update = OccupancyGridMsgToCostmap2D(*occupancy_grid_msg);

// update
occupancy_grid_map_updater_ptr_->update(map_for_update);
}

nav2_costmap_2d::Costmap2D GridMapFusionNode::OccupancyGridMsgToCostmap2D(
const nav_msgs::msg::OccupancyGrid & occupancy_grid_map)
{
nav2_costmap_2d::Costmap2D costmap2d(
occupancy_grid_map.info.width, occupancy_grid_map.info.height,
occupancy_grid_map.info.resolution, occupancy_grid_map.info.origin.position.x,
occupancy_grid_map.info.origin.position.y, 0);

for (unsigned int i = 0; i < occupancy_grid_map.info.width; i++) {
for (unsigned int j = 0; j < occupancy_grid_map.info.height; j++) {
const unsigned int index = i + j * occupancy_grid_map.info.width;
costmap2d.setCost(
i, j, cost_value::inverse_cost_translation_table[occupancy_grid_map.data[index]]);
}
}

return costmap2d;
}

OccupancyGridMapFixedBlindSpot GridMapFusionNode::OccupancyGridMsgToGridMap(
const nav_msgs::msg::OccupancyGrid & occupancy_grid_map)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,16 +66,12 @@ class GridMapFusionNode : public rclcpp::Node
const std::string & frame_id, const builtin_interfaces::msg::Time & stamp,
const float & robot_pose_z, const nav2_costmap_2d::Costmap2D & occupancy_grid_map);

nav2_costmap_2d::Costmap2D OccupancyGridMsgToCostmap2D(
const nav_msgs::msg::OccupancyGrid & occupancy_grid_map);
OccupancyGridMapFixedBlindSpot OccupancyGridMsgToGridMap(
const nav_msgs::msg::OccupancyGrid & occupancy_grid_map);
OccupancyGridMapFixedBlindSpot SingleFrameOccupancyFusion(
std::vector<OccupancyGridMapFixedBlindSpot> & occupancy_grid_maps,
const builtin_interfaces::msg::Time latest_stamp, const std::vector<double> & weights);

void updateGridMap(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg);

void setPeriod(const int64_t new_period);
void timer_callback();
void publish();
Expand Down
Loading