Skip to content

Commit f87cf32

Browse files
authored
feat(obstacle_velocity_limiter): move to motion_velocity_planner (#7439)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 0808eb1 commit f87cf32

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

51 files changed

+838
-1107
lines changed

Diff for: .github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -199,13 +199,13 @@ planning/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi
199199
planning/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
200200
planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp
201201
planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
202+
planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/** maxime.clement@tier4.jp
202203
planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
203204
planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** maxime.clement@tier4.jp
204205
planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** maxime.clement@tier4.jp
205206
planning/autoware_objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp
206207
planning/autoware_obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
207208
planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
208-
planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp
209209
planning/planning_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp
210210
planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp
211211
planning/autoware_route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp

Diff for: launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml

+10-26
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
<arg name="interface_output_topic" default="/planning/scenario_planning/lane_driving/trajectory"/>
44

55
<arg name="launch_out_of_lane_module" default="true"/>
6+
<arg name="launch_obstacle_velocity_limiter_module" default="true"/>
67
<!-- <arg name="launch_dynamic_obstacle_stop_module" default="true"/> -->
78
<arg name="launch_module_list_end" default="&quot;&quot;]"/>
89

@@ -13,6 +14,11 @@
1314
value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + 'autoware::motion_velocity_planner::OutOfLaneModule, '&quot;)"
1415
if="$(var launch_out_of_lane_module)"
1516
/>
17+
<let
18+
name="motion_velocity_planner_launch_modules"
19+
value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + 'autoware::motion_velocity_planner::ObstacleVelocityLimiterModule, '&quot;)"
20+
if="$(var launch_obstacle_velocity_limiter_module)"
21+
/>
1622
<!-- <let -->
1723
<!-- name="motion_velocity_planner_launch_modules" -->
1824
<!-- value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + 'motion_velocity_planner::DynamicObstacleStopModule, '&quot;)" -->
@@ -135,43 +141,21 @@
135141
<param from="$(var motion_velocity_planner_velocity_smoother_type_param_path)"/>
136142
<param from="$(var motion_velocity_planner_param_path)"/>
137143
<param from="$(var motion_velocity_planner_out_of_lane_module_param_path)"/>
144+
<param from="$(var motion_velocity_planner_obstacle_velocity_limiter_param_path)"/>
138145
<!-- <param from="$(var motion_velocity_planner_template_param_path)"/> -->
139146
<!-- composable node config -->
140147
<extra_arg name="use_intra_process_comms" value="false"/>
141148
</composable_node>
142149
</load_composable_node>
143150
</group>
144-
<!-- velocity limiter TODO(Maxime): move this node to the motion_velocity_planner -->
145-
<group>
146-
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
147-
<composable_node pkg="obstacle_velocity_limiter" plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode" name="obstacle_velocity_limiter" namespace="">
148-
<!-- topic remap -->
149-
<remap from="~/input/trajectory" to="motion_velocity_planner/trajectory"/>
150-
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
151-
<remap from="~/input/dynamic_obstacles" to="/perception/object_recognition/objects"/>
152-
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
153-
<remap from="~/input/obstacle_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
154-
<remap from="~/input/map" to="/map/vector_map"/>
155-
<remap from="~/output/trajectory" to="obstacle_velocity_limiter/trajectory"/>
156-
<remap from="~/output/debug_markers" to="debug_markers"/>
157-
<!-- params -->
158-
<param from="$(var common_param_path)"/>
159-
<param from="$(var vehicle_param_file)"/>
160-
<param from="$(var nearest_search_param_path)"/>
161-
<param from="$(var obstacle_velocity_limiter_param_path)"/>
162-
<!-- composable node config -->
163-
<extra_arg name="use_intra_process_comms" value="false"/>
164-
</composable_node>
165-
</load_composable_node>
166-
</group>
167151

168152
<!-- obstacle stop, adaptive cruise -->
169153
<group>
170154
<group if="$(eval &quot;'$(var motion_stop_planner_type)' == 'obstacle_cruise_planner'&quot;)">
171155
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
172156
<composable_node pkg="autoware_obstacle_cruise_planner" plugin="autoware::motion_planning::ObstacleCruisePlannerNode" name="obstacle_cruise_planner" namespace="">
173157
<!-- topic remap -->
174-
<remap from="~/input/trajectory" to="obstacle_velocity_limiter/trajectory"/>
158+
<remap from="~/input/trajectory" to="motion_velocity_planner/trajectory"/>
175159
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
176160
<remap from="~/input/acceleration" to="/localization/acceleration"/>
177161
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
@@ -194,7 +178,7 @@
194178
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
195179
<composable_node pkg="obstacle_stop_planner" plugin="motion_planning::ObstacleStopPlannerNode" name="obstacle_stop_planner" namespace="">
196180
<!-- topic remap -->
197-
<remap from="~/input/trajectory" to="obstacle_velocity_limiter/trajectory"/>
181+
<remap from="~/input/trajectory" to="motion_velocity_planner/trajectory"/>
198182
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
199183
<remap from="~/input/acceleration" to="/localization/acceleration"/>
200184
<remap from="~/input/pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
@@ -219,7 +203,7 @@
219203
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
220204
<composable_node pkg="topic_tools" plugin="topic_tools::RelayNode" name="obstacle_stop_relay" namespace="">
221205
<!-- params -->
222-
<param name="input_topic" value="obstacle_velocity_limiter/trajectory"/>
206+
<param name="input_topic" value="motion_velocity_planner/trajectory"/>
223207
<param name="output_topic" value="$(var interface_output_topic)"/>
224208
<param name="type" value="autoware_planning_msgs/msg/Trajectory"/>
225209
<!-- composable node config -->

Diff for: planning/.pages

+3-3
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,6 @@ nav:
5050
- 'About Obstacle Cruise': planning/autoware_obstacle_cruise_planner
5151
- 'How to Debug': planning/autoware_obstacle_cruise_planner/docs/debug
5252
- 'Obstacle Stop Planner': planning/obstacle_stop_planner
53-
- 'Obstacle Velocity Limiter': planning/obstacle_velocity_limiter
5453
- 'Path Smoother':
5554
- 'About Path Smoother': planning/autoware_path_smoother
5655
- 'Elastic Band': planning/autoware_path_smoother/docs/eb
@@ -63,9 +62,10 @@ nav:
6362
- 'About Surround Obstacle Checker': planning/autoware_surround_obstacle_checker
6463
- 'About Surround Obstacle Checker (Japanese)': planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja
6564
- 'Motion Velocity Planner':
66-
- 'About Motion Velocity Planner': planning/autoware_motion_velocity_planner_node/
65+
- 'About Motion Velocity Planner': planning/motion_velocity_planner/autoware_motion_velocity_planner_node/
6766
- 'Available Modules':
68-
- 'Out of Lane': planning/autoware_motion_velocity_planner_out_of_lane_module/
67+
- 'Out of Lane': planning/motion_velocity_planner/autoware_motion_velocity_planner_out_of_lane_module/
68+
- 'Obstacle Velocity Limiter': planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/
6969
- 'Velocity Smoother':
7070
- 'About Velocity Smoother': planning/autoware_velocity_smoother
7171
- 'About Velocity Smoother (Japanese)': planning/autoware_velocity_smoother/README.ja
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(autoware_motion_velocity_obstacle_velocity_limiter_module)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml)
7+
8+
ament_auto_add_library(${PROJECT_NAME} SHARED
9+
DIRECTORY src
10+
)
11+
12+
if(BUILD_TESTING)
13+
find_package(ament_lint_auto REQUIRED)
14+
ament_lint_auto_find_test_dependencies()
15+
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
16+
test/test_forward_projection.cpp
17+
test/test_obstacles.cpp
18+
test/test_collision_distance.cpp
19+
test/test_occupancy_grid_utils.cpp
20+
)
21+
target_link_libraries(test_${PROJECT_NAME}
22+
${PROJECT_NAME}
23+
)
24+
endif()
25+
26+
add_executable(collision_benchmark
27+
benchmarks/collision_checker_benchmark.cpp
28+
)
29+
target_link_libraries(collision_benchmark
30+
${PROJECT_NAME}
31+
)
32+
33+
ament_auto_package(
34+
INSTALL_TO_SHARE
35+
config
36+
)

Diff for: planning/obstacle_velocity_limiter/README.md renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/README.md

-21
Original file line numberDiff line numberDiff line change
@@ -142,27 +142,6 @@ Parameters `trajectory_preprocessing.max_length` and `trajectory_preprocessing.m
142142
To reduce computation cost at the cost of precision, the trajectory can be downsampled using parameter `trajectory_preprocessing.downsample_factor`.
143143
For example a value of `1` means all trajectory points will be evaluated while a value of `10` means only 1/10th of the points will be evaluated.
144144

145-
## Inputs / Outputs
146-
147-
### Inputs
148-
149-
| Name | Type | Description |
150-
| ----------------------------- | ------------------------------------------- | -------------------------------------------------- |
151-
| `~/input/trajectory` | `autoware_planning_msgs/Trajectory` | Reference trajectory |
152-
| `~/input/occupancy_grid` | `nav_msgs/OccupancyGrid` | Occupancy grid with obstacle information |
153-
| `~/input/obstacle_pointcloud` | `sensor_msgs/PointCloud2` | Pointcloud containing only obstacle points |
154-
| `~/input/dynamic_obstacles` | `autoware_perception_msgs/PredictedObjects` | Dynamic objects |
155-
| `~/input/odometry` | `nav_msgs/Odometry` | Odometry used to retrieve the current ego velocity |
156-
| `~/input/map` | `autoware_map_msgs/LaneletMapBin` | Vector map used to retrieve static obstacles |
157-
158-
### Outputs
159-
160-
| Name | Type | Description |
161-
| ------------------------------- | ----------------------------------- | -------------------------------------------------------- |
162-
| `~/output/trajectory` | `autoware_planning_msgs/Trajectory` | Trajectory with adjusted velocities |
163-
| `~/output/debug_markers` | `visualization_msgs/MarkerArray` | Debug markers (envelopes, obstacle polygons) |
164-
| `~/output/runtime_microseconds` | `tier4_debug_msgs/Float64` | Time taken to calculate the trajectory (in microseconds) |
165-
166145
## Parameters
167146

168147
| Name | Type | Description |

Diff for: planning/obstacle_velocity_limiter/benchmarks/collision_checker_benchmark.cpp renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -12,17 +12,17 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "obstacle_velocity_limiter/obstacles.hpp"
16-
#include "obstacle_velocity_limiter/types.hpp"
15+
#include "../src/obstacles.hpp"
16+
#include "../src/types.hpp"
1717

1818
#include <chrono>
1919
#include <random>
2020

21-
using obstacle_velocity_limiter::CollisionChecker;
22-
using obstacle_velocity_limiter::linestring_t;
23-
using obstacle_velocity_limiter::Obstacles;
24-
using obstacle_velocity_limiter::point_t;
25-
using obstacle_velocity_limiter::polygon_t;
21+
using autoware::motion_velocity_planner::obstacle_velocity_limiter::CollisionChecker;
22+
using autoware::motion_velocity_planner::obstacle_velocity_limiter::linestring_t;
23+
using autoware::motion_velocity_planner::obstacle_velocity_limiter::Obstacles;
24+
using autoware::motion_velocity_planner::obstacle_velocity_limiter::point_t;
25+
using autoware::motion_velocity_planner::obstacle_velocity_limiter::polygon_t;
2626

2727
point_t random_point()
2828
{

Diff for: planning/obstacle_velocity_limiter/package.xml renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<?xml version="1.0"?>
22
<package format="3">
3-
<name>obstacle_velocity_limiter</name>
3+
<name>autoware_motion_velocity_obstacle_velocity_limiter_module</name>
44
<version>0.1.0</version>
55
<description>Package to adjust velocities of a trajectory in order for the ride to feel safe</description>
66

@@ -11,6 +11,7 @@
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
1313

14+
<depend>autoware_motion_velocity_planner_common</depend>
1415
<depend>autoware_perception_msgs</depend>
1516
<depend>autoware_planning_msgs</depend>
1617
<depend>autoware_planning_test_manager</depend>
@@ -25,8 +26,8 @@
2526
<depend>motion_utils</depend>
2627
<depend>nav_msgs</depend>
2728
<depend>pcl_ros</depend>
29+
<depend>pluginlib</depend>
2830
<depend>rclcpp</depend>
29-
<depend>rclcpp_components</depend>
3031
<depend>sensor_msgs</depend>
3132
<depend>tf2_eigen</depend>
3233
<depend>tf2_geometry_msgs</depend>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
<library path="autoware_motion_velocity_obstacle_velocity_limiter_module">
2+
<class type="autoware::motion_velocity_planner::ObstacleVelocityLimiterModule" base_class_type="autoware::motion_velocity_planner::PluginModuleInterface"/>
3+
</library>

Diff for: planning/obstacle_velocity_limiter/src/debug.cpp renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.cpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -12,16 +12,18 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "obstacle_velocity_limiter/debug.hpp"
15+
#include "debug.hpp"
1616

17-
#include "obstacle_velocity_limiter/parameters.hpp"
18-
#include "obstacle_velocity_limiter/types.hpp"
17+
#include "parameters.hpp"
18+
#include "types.hpp"
1919

2020
#include <visualization_msgs/msg/marker_array.hpp>
2121

22-
namespace obstacle_velocity_limiter
22+
#include <algorithm>
23+
24+
namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
2325
{
24-
visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, const Float z)
26+
visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, const double z)
2527
{
2628
visualization_msgs::msg::Marker marker;
2729
marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
@@ -38,7 +40,7 @@ visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, co
3840
return marker;
3941
}
4042

41-
visualization_msgs::msg::Marker makePolygonMarker(const polygon_t & polygon, const Float z)
43+
visualization_msgs::msg::Marker makePolygonMarker(const polygon_t & polygon, const double z)
4244
{
4345
visualization_msgs::msg::Marker marker;
4446
marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
@@ -60,7 +62,7 @@ visualization_msgs::msg::MarkerArray makeDebugMarkers(
6062
const std::vector<multi_linestring_t> & adjusted_projections,
6163
const std::vector<polygon_t> & original_footprints,
6264
const std::vector<polygon_t> & adjusted_footprints, const ObstacleMasks & obstacle_masks,
63-
const Float marker_z)
65+
const double marker_z)
6466
{
6567
visualization_msgs::msg::MarkerArray debug_markers;
6668
auto original_projections_id_offset = 0;
@@ -182,4 +184,4 @@ visualization_msgs::msg::MarkerArray makeDebugMarkers(
182184
return debug_markers;
183185
}
184186

185-
} // namespace obstacle_velocity_limiter
187+
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter

Diff for: planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/debug.hpp renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.hpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -12,25 +12,25 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef OBSTACLE_VELOCITY_LIMITER__DEBUG_HPP_
16-
#define OBSTACLE_VELOCITY_LIMITER__DEBUG_HPP_
15+
#ifndef DEBUG_HPP_
16+
#define DEBUG_HPP_
1717

18-
#include "obstacle_velocity_limiter/obstacles.hpp"
19-
#include "obstacle_velocity_limiter/types.hpp"
18+
#include "obstacles.hpp"
19+
#include "types.hpp"
2020

2121
#include <visualization_msgs/msg/marker.hpp>
2222
#include <visualization_msgs/msg/marker_array.hpp>
2323

2424
#include <string>
2525
#include <vector>
2626

27-
namespace obstacle_velocity_limiter
27+
namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
2828
{
2929
/// @brief make the visualization Marker of the given linestring
3030
/// @param[in] ls linestring to turn into a marker
3131
/// @param[in] z z-value to use in the marker
3232
/// @return marker representing the linestring
33-
visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, const Float z);
33+
visualization_msgs::msg::Marker makeLinestringMarker(const linestring_t & ls, const double z);
3434

3535
/// @brief make debug marker array
3636
/// @param[in] obstacles obstacles
@@ -45,7 +45,7 @@ visualization_msgs::msg::MarkerArray makeDebugMarkers(
4545
const std::vector<multi_linestring_t> & adjusted_projections,
4646
const std::vector<polygon_t> & original_footprints,
4747
const std::vector<polygon_t> & adjusted_footprints, const ObstacleMasks & obstacle_masks,
48-
const Float marker_z);
48+
const double marker_z);
4949

50-
} // namespace obstacle_velocity_limiter
51-
#endif // OBSTACLE_VELOCITY_LIMITER__DEBUG_HPP_
50+
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
51+
#endif // DEBUG_HPP_

Diff for: planning/obstacle_velocity_limiter/src/distance.cpp renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/distance.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "obstacle_velocity_limiter/obstacles.hpp"
16-
17-
#include <obstacle_velocity_limiter/distance.hpp>
15+
#include "distance.hpp"
1816

1917
#include <boost/geometry.hpp>
2018
#include <boost/geometry/algorithms/detail/distance/interface.hpp>
@@ -24,7 +22,7 @@
2422
#include <algorithm>
2523
#include <limits>
2624

27-
namespace obstacle_velocity_limiter
25+
namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
2826
{
2927
namespace bg = boost::geometry;
3028

@@ -70,4 +68,4 @@ double arcDistance(const point_t & origin, const double heading, const point_t &
7068
std::acos((2 * squared_radius - (origin - target).squaredNorm()) / (2 * squared_radius));
7169
return std::sqrt(squared_radius) * angle;
7270
}
73-
} // namespace obstacle_velocity_limiter
71+
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter

Diff for: planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/distance.hpp renamed to planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/distance.hpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,19 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef OBSTACLE_VELOCITY_LIMITER__DISTANCE_HPP_
16-
#define OBSTACLE_VELOCITY_LIMITER__DISTANCE_HPP_
15+
#ifndef DISTANCE_HPP_
16+
#define DISTANCE_HPP_
1717

18-
#include "obstacle_velocity_limiter/obstacles.hpp"
19-
#include "obstacle_velocity_limiter/parameters.hpp"
20-
#include "obstacle_velocity_limiter/types.hpp"
18+
#include "obstacles.hpp"
19+
#include "parameters.hpp"
20+
#include "types.hpp"
2121

2222
#include <geometry_msgs/msg/vector3.hpp>
2323

2424
#include <optional>
2525
#include <vector>
2626

27-
namespace obstacle_velocity_limiter
27+
namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
2828
{
2929
/// @brief calculate the closest distance to a collision
3030
/// @param [in] projection forward projection line
@@ -43,6 +43,6 @@ std::optional<double> distanceToClosestCollision(
4343
/// @return distance from origin to target along a circle
4444
double arcDistance(const point_t & origin, const double heading, const point_t & target);
4545

46-
} // namespace obstacle_velocity_limiter
46+
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
4747

48-
#endif // OBSTACLE_VELOCITY_LIMITER__DISTANCE_HPP_
48+
#endif // DISTANCE_HPP_

0 commit comments

Comments
 (0)