-
Notifications
You must be signed in to change notification settings - Fork 0
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
feat(behavior_velocity): add object to occupancy grid #7
Conversation
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/2)
@@ -81,7 +83,7 @@ void toQuantizedImage( | |||
const nav_msgs::msg::OccupancyGrid & occupancy_grid, cv::Mat * cv_image, const GridParam & param); | |||
void denoiseOccupancyGridCV( | |||
nav_msgs::msg::OccupancyGrid & occupancy_grid, grid_map::GridMap & grid_map, | |||
const GridParam & param); | |||
const GridParam & param, const bool is_show_debug_window); | |||
} // namespace grid_utils |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
nested namespaces can be concatenated
} // namespace grid_utils | |
} |
planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp
Outdated
Show resolved
Hide resolved
@@ -197,16 +206,21 @@ void toQuantizedImage( | |||
} | |||
void denoiseOccupancyGridCV( | |||
nav_msgs::msg::OccupancyGrid & occupancy_grid, grid_map::GridMap & grid_map, | |||
const GridParam & param) | |||
const GridParam & param, const bool is_show_debug_window) | |||
{ | |||
cv::Mat cv_image( | |||
occupancy_grid.info.width, occupancy_grid.info.height, CV_8UC1, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
use of a signed integer operand with a binary bitwise operator
planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot.hpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot.hpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot.hpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp
Outdated
Show resolved
Hide resolved
planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot.hpp
Outdated
Show resolved
Hide resolved
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (2/2)
planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp
Outdated
Show resolved
Hide resolved
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/1)
{ | ||
cv::Mat cv_image( | ||
occupancy_grid.info.width, occupancy_grid.info.height, CV_8UC1, | ||
cv::Scalar(grid_utils::occlusion_cost_value::OCCUPIED)); | ||
cv::Mat cv_canny( | ||
occupancy_grid.info.width, occupancy_grid.info.height, CV_8UC1, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
use of a signed integer operand with a binary bitwise operator
@@ -168,7 +168,16 @@ void imageToOccupancyGrid(const cv::Mat & cv_image, nav_msgs::msg::OccupancyGrid | |||
for (int x = width - 1; x >= 0; x--) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
interation 200*200
5e1136a
to
c959745
Compare
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
…sion judgement Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
c959745
to
675f532
Compare
intensity = grid_utils::occlusion_cost_value::FREE_SPACE; | ||
unsigned char intensity = occupancy_grid.data.at(idx); | ||
if (intensity <= param.free_space_max) { | ||
intensity = grid_utils::occlusion_cost_value::FREE_SPACE_IMAGE; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for apply morphologyEx(dilate and erode) more accurately
@@ -453,16 +453,16 @@ boost::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionS | |||
bool collision_free_at_intersection = | |||
grid_utils::isCollisionFree(grid, occlusion_spot_position, grid_map::Position(ip.x, ip.y)); | |||
bool obstacle_not_blocked_by_partition = true; | |||
if (!collision_free_at_intersection) continue; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
early continue
@@ -218,13 +218,31 @@ target_link_libraries(scene_module_virtual_traffic_light scene_module_lib) | |||
|
|||
|
|||
# SceneModule OcclusionSpot | |||
ament_auto_add_library(scene_module_occlusion_spot SHARED | |||
# Util | |||
ament_auto_add_library(occlusion_spot_lib SHARED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for faster compiling
@@ -112,8 +112,12 @@ struct PlannerParam | |||
{ | |||
DETECTION_METHOD detection_method; | |||
PASS_JUDGE pass_judge; | |||
bool debug; // [-] | |||
bool use_partition_lanelet; // [-] | |||
bool is_show_occlusion; // [-] |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
readability
@@ -23,6 +23,44 @@ namespace behavior_velocity_planner | |||
{ | |||
namespace grid_utils | |||
{ | |||
|
|||
Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double thickness) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
feature polygon judgement
…er data Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
…iment Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/1)
const auto & obj_label = obj.classification.at(0).label; | ||
using autoware_auto_perception_msgs::msg::ObjectClassification; | ||
if ( | ||
obj_label != ObjectClassification::CAR || obj_label != ObjectClassification::TRUCK || |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
logical expression is always true
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/1)
return line_poly; | ||
} | ||
|
||
TEST(compareTime, polygon_vs_line_iterator) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
class compareTime_polygon_vs_line_iterator_Test
defines a copy constructor and a copy assignment operator but does not define a destructor, a move constructor or a move assignment operator
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
6a54f33
to
38e805f
Compare
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/1)
close_partition.emplace_back(p); | ||
} | ||
} | ||
return; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
redundant return statement at the end of a function with a void return type
return; | |
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang-tidy
found issue(s) with the introduced code (1/1)
} | ||
|
||
std::vector<std::pair<grid_map::Position, grid_map::Position>> pointsToRays( | ||
const grid_map::Position p0, const grid_map::Position p1, const double radius) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
the const qualified parameter p0
is copied for each invocation; consider making it a reference
const grid_map::Position p0, const grid_map::Position p1, const double radius) | |
const grid_map::Position& p0, const grid_map::Position p1, const double radius) |
} | ||
|
||
std::vector<std::pair<grid_map::Position, grid_map::Position>> pointsToRays( | ||
const grid_map::Position p0, const grid_map::Position p1, const double radius) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
the const qualified parameter p1
is copied for each invocation; consider making it a reference
const grid_map::Position p0, const grid_map::Position p1, const double radius) | |
const grid_map::Position p0, const grid_map::Position& p1, const double radius) |
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
Draft
worst case time is millisec
![image](https://user-images.githubusercontent.com/65527974/158992376-29d0e40e-f437-491a-aa33-f79096af15f1.png)