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

refactor(occlusion_spot): add autoware prefix #7357

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
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(behavior_velocity_occlusion_spot_module)
project(autoware_behavior_velocity_occlusion_spot_module)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>behavior_velocity_occlusion_spot_module</name>
<name>autoware_behavior_velocity_occlusion_spot_module</name>
<version>0.1.0</version>
<description>The behavior_velocity_occlusion_spot_module package</description>
<description>The autoware_behavior_velocity_occlusion_spot_module package</description>

<maintainer email="[email protected]">Taiki Tanaka</maintainer>
<maintainer email="[email protected]">Tomoya Kimura</maintainer>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<library path="autoware_behavior_velocity_occlusion_spot_module">
<class type="autoware::behavior_velocity_planner::OcclusionSpotModulePlugin" base_class_type="autoware::behavior_velocity_planner::PluginInterface"/>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius)
// std::cout << boost::geometry::wkt(line_poly) << std::endl;
// std::cout << boost::geometry::wkt(line) << std::endl;

bg::correct(line_poly);
boost::geometry::correct(line_poly);
return line_poly;
}

Expand Down Expand Up @@ -142,7 +142,7 @@ Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, cons
poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, r, r, 0).position));
poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, 0, r, 0).position));

bg::correct(poly);
boost::geometry::correct(poly);
return poly;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,10 @@ using geometry_msgs::msg::Point;
using geometry_msgs::msg::TransformStamped;
using nav_msgs::msg::MapMetaData;
using nav_msgs::msg::OccupancyGrid;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;

namespace occlusion_cost_value
{
static constexpr unsigned char FREE_SPACE = 0;
Expand Down
Loading