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

feat: port autoware_motion_velocity_planner_node to core #10293

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
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(autoware_motion_velocity_planner_node_universe)
project(autoware_motion_velocity_planner_node)

find_package(autoware_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,10 @@ This means that to stop before a wall, a stop point is inserted in the trajector

## Services

| Name | Type | Description |
| ------------------------- | ----------------------------------------------------------------- | ---------------------------- |
| `~/service/load_plugin` | autoware_motion_velocity_planner_node_universe::srv::LoadPlugin | To request loading a plugin |
| `~/service/unload_plugin` | autoware_motion_velocity_planner_node_universe::srv::UnloadPlugin | To request unloaded a plugin |
| Name | Type | Description |
| ------------------------- | -------------------------------------------------------- | ---------------------------- |
| `~/service/load_plugin` | autoware_motion_velocity_planner_node::srv::LoadPlugin | To request loading a plugin |
| `~/service/unload_plugin` | autoware_motion_velocity_planner_node::srv::UnloadPlugin | To request unloaded a plugin |

## Node parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
<arg name="motion_velocity_planner_param_path"/>
<arg name="motion_velocity_planner_out_of_lane_module_param_path"/>
<!-- <arg name="motion_velocity_planner_template_module_param_path"/> -->
<arg name="motion_velocity_planner_param_file" default="$(find-pkg-share autoware_motion_velocity_planner_node_universe)/config/motion_velocity_planner.param.yaml"/>
<arg name="motion_velocity_planner_param_file" default="$(find-pkg-share autoware_motion_velocity_planner_node)/config/motion_velocity_planner.param.yaml"/>

<node pkg="autoware_motion_velocity_planner_node_universe" exec="motion_velocity_planner_node_exe" name="motion_velocity_planner" output="screen">
<node pkg="autoware_motion_velocity_planner_node" exec="motion_velocity_planner_node_exe" name="motion_velocity_planner" output="screen">
<!-- topic remap -->
<remap from="~/input/trajectory" to="trajectory"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_internal_metric_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_motion_velocity_planner_common_universe</depend>
Expand All @@ -40,7 +42,6 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>
<depend>visualization_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include "planner_manager.hpp"

#include <autoware/motion_velocity_planner_common_universe/planner_data.hpp>
#include <autoware_motion_velocity_planner_node_universe/srv/load_plugin.hpp>
#include <autoware_motion_velocity_planner_node_universe/srv/unload_plugin.hpp>
#include <autoware_motion_velocity_planner_node/srv/load_plugin.hpp>
#include <autoware_motion_velocity_planner_node/srv/unload_plugin.hpp>
#include <autoware_utils/ros/logger_level_configure.hpp>
#include <autoware_utils/ros/polling_subscriber.hpp>
#include <autoware_utils/ros/published_time_publisher.hpp>
Expand Down Expand Up @@ -49,8 +49,8 @@
namespace autoware::motion_velocity_planner
{
using autoware_map_msgs::msg::LaneletMapBin;
using autoware_motion_velocity_planner_node_universe::srv::LoadPlugin;
using autoware_motion_velocity_planner_node_universe::srv::UnloadPlugin;
using autoware_motion_velocity_planner_node::srv::LoadPlugin;
using autoware_motion_velocity_planner_node::srv::UnloadPlugin;
using autoware_planning_msgs::msg::Trajectory;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace autoware::motion_velocity_planner

MotionVelocityPlannerManager::MotionVelocityPlannerManager()
: plugin_loader_(
"autoware_motion_velocity_planner_node_universe",
"autoware_motion_velocity_planner_node",
"autoware::motion_velocity_planner::PluginModuleInterface")
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_metric_msgs/msg/metric.hpp>
#include <autoware_internal_metric_msgs/msg/metric_array.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>
Expand All @@ -36,8 +36,8 @@
#include <string>
#include <vector>

using Metric = tier4_metric_msgs::msg::Metric;
using MetricArray = tier4_metric_msgs::msg::MetricArray;
using Metric = autoware_internal_metric_msgs::msg::Metric;
using MetricArray = autoware_internal_metric_msgs::msg::MetricArray;

namespace autoware::motion_velocity_planner
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ std::shared_ptr<MotionVelocityPlannerNode> generateNode()
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto motion_velocity_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node_universe");
ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node");
const auto velocity_smoother_dir =
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother");

Expand Down
Loading