Skip to content

Commit cfd1af4

Browse files
committed
fix: remove unnecessary change
1 parent 3d1593c commit cfd1af4

File tree

4 files changed

+4
-9
lines changed

4 files changed

+4
-9
lines changed

perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,6 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node
5555
{
5656
public:
5757
explicit PointcloudBasedOccupancyGridMapNode(const rclcpp::NodeOptions & node_options);
58-
~PointcloudBasedOccupancyGridMapNode();
5958

6059
private:
6160
void onPointcloudWithObstacleAndRaw(

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud(
5858
constexpr double min_angle = autoware::universe_utils::deg2rad(-180.0);
5959
constexpr double max_angle = autoware::universe_utils::deg2rad(180.0);
6060
constexpr double angle_increment = autoware::universe_utils::deg2rad(0.1);
61+
const auto angle_increment_inv = 1.0 / angle_increment;
6162
const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/);
6263

6364
// Transform Matrix from base_link to map frame
@@ -92,7 +93,6 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud(
9293
obstacle_pointcloud.fields[pcl::getFieldIndex(obstacle_pointcloud, "z")].offset;
9394
const size_t raw_pointcloud_size = raw_pointcloud.width * raw_pointcloud.height;
9495
const size_t obstacle_pointcloud_size = obstacle_pointcloud.width * obstacle_pointcloud.height;
95-
9696
const size_t raw_reserve_size = raw_pointcloud_size / angle_bin_size;
9797
const size_t obstacle_reserve_size = obstacle_pointcloud_size / angle_bin_size;
9898
for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) {
@@ -102,7 +102,6 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud(
102102
obstacle_pointcloud_angle_bin.reserve(obstacle_reserve_size);
103103
}
104104
size_t global_offset = 0;
105-
const auto angle_increment_inv = 1.0 / angle_increment;
106105
for (size_t i = 0; i < raw_pointcloud_size; ++i) {
107106
Eigen::Vector4f pt(
108107
*reinterpret_cast<const float *>(&raw_pointcloud.data[global_offset + x_offset_raw]),
@@ -134,6 +133,7 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud(
134133
});
135134
}
136135
global_offset = 0;
136+
// Create obstacle angle bins and sort points by range
137137
for (size_t i = 0; i < obstacle_pointcloud_size; ++i) {
138138
Eigen::Vector4f pt(
139139
*reinterpret_cast<const float *>(

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp

+2-5
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
5959
constexpr double min_angle = autoware::universe_utils::deg2rad(-180.0);
6060
constexpr double max_angle = autoware::universe_utils::deg2rad(180.0);
6161
constexpr double angle_increment = autoware::universe_utils::deg2rad(0.1);
62+
const auto angle_increment_inv = 1.0 / angle_increment;
6263
const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/);
6364

6465
// Transform from base_link to map frame
@@ -94,7 +95,6 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
9495
double projected_wx;
9596
double projected_wy;
9697
};
97-
9898
std::vector</*angle bin*/ std::vector<BinInfo3D>> obstacle_pointcloud_angle_bins(angle_bin_size);
9999
std::vector</*angle bin*/ std::vector<BinInfo3D>> raw_pointcloud_angle_bins(angle_bin_size);
100100
const int x_offset_raw = raw_pointcloud.fields[pcl::getFieldIndex(raw_pointcloud, "x")].offset;
@@ -108,7 +108,6 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
108108
obstacle_pointcloud.fields[pcl::getFieldIndex(obstacle_pointcloud, "z")].offset;
109109
const size_t raw_pointcloud_size = raw_pointcloud.width * raw_pointcloud.height;
110110
const size_t obstacle_pointcloud_size = obstacle_pointcloud.width * obstacle_pointcloud.height;
111-
112111
const size_t raw_reserve_size = raw_pointcloud_size / angle_bin_size;
113112
const size_t obstacle_reserve_size = obstacle_pointcloud_size / angle_bin_size;
114113
for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) {
@@ -118,8 +117,6 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
118117
obstacle_pointcloud_angle_bin.reserve(obstacle_reserve_size);
119118
}
120119
size_t global_offset = 0;
121-
const auto angle_increment_inv = 1.0 / angle_increment;
122-
123120
for (size_t i = 0; i < raw_pointcloud_size; i++) {
124121
Eigen::Vector4f pt(
125122
*reinterpret_cast<const float *>(&raw_pointcloud.data[global_offset + x_offset_raw]),
@@ -151,8 +148,8 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
151148
return a.range < b.range;
152149
});
153150
}
154-
155151
global_offset = 0;
152+
// Create obstacle angle bins and sort points by range
156153
for (size_t i = 0; i < obstacle_pointcloud_size; i++) {
157154
Eigen::Vector4f pt(
158155
*reinterpret_cast<const float *>(

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -199,7 +199,6 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
199199
occupancy_grid_map_ptr_->updateOrigin(
200200
gridmap_origin.position.x - occupancy_grid_map_ptr_->getSizeInMetersX() / 2,
201201
gridmap_origin.position.y - occupancy_grid_map_ptr_->getSizeInMetersY() / 2);
202-
203202
occupancy_grid_map_ptr_->updateWithPointCloud(
204203
*input_raw_use, (use_input_obstacle_pc_common ? input_obstacle_pc_common : *input_obstacle_use),
205204
robot_pose, scan_origin);

0 commit comments

Comments
 (0)