Skip to content

Commit fef9baf

Browse files
committed
fix
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 070bb2b commit fef9baf

File tree

7 files changed

+17
-47
lines changed

7 files changed

+17
-47
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ if(BUILD_TESTING)
1414
find_package(ament_lint_auto REQUIRED)
1515
ament_lint_auto_find_test_dependencies()
1616
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
17-
# test/test_crosswalk.cpp
17+
test/test_crosswalk.cpp
1818
test/test_node_interface.cpp
1919
)
2020
target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME})

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt

-17
Original file line numberDiff line numberDiff line change
@@ -2,14 +2,6 @@ cmake_minimum_required(VERSION 3.14)
22
project(autoware_behavior_velocity_planner)
33

44
find_package(autoware_cmake REQUIRED)
5-
find_package(rosidl_default_generators REQUIRED)
6-
7-
rosidl_generate_interfaces(
8-
${PROJECT_NAME}
9-
"srv/LoadPlugin.srv"
10-
"srv/UnloadPlugin.srv"
11-
DEPENDENCIES
12-
)
135

146
autoware_package()
157

@@ -24,15 +16,6 @@ rclcpp_components_register_node(${PROJECT_NAME}_lib
2416
EXECUTABLE ${PROJECT_NAME}_node
2517
)
2618

27-
if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
28-
rosidl_target_interfaces(${PROJECT_NAME}_lib
29-
${PROJECT_NAME} "rosidl_typesupport_cpp")
30-
else()
31-
rosidl_get_typesupport_target(
32-
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
33-
target_link_libraries(${PROJECT_NAME}_lib "${cpp_typesupport_target}")
34-
endif()
35-
3619
if(BUILD_TESTING)
3720
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
3821
test/test_node_interface.cpp

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp

+7-9
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,9 @@
2121

2222
#include <autoware/behavior_velocity_planner_common/planner_data.hpp>
2323
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
24-
#include <autoware_behavior_velocity_planner/srv/load_plugin.hpp>
25-
#include <autoware_behavior_velocity_planner/srv/unload_plugin.hpp>
2624
#include <rclcpp/rclcpp.hpp>
2725

26+
#include <autoware_internal_debug_msgs/srv/string.hpp>
2827
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
2928
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
3029
#include <autoware_planning_msgs/msg/path.hpp>
@@ -45,8 +44,6 @@
4544

4645
namespace autoware::behavior_velocity_planner
4746
{
48-
using autoware_behavior_velocity_planner::srv::LoadPlugin;
49-
using autoware_behavior_velocity_planner::srv::UnloadPlugin;
5047
using autoware_map_msgs::msg::LaneletMapBin;
5148
using tier4_planning_msgs::msg::VelocityLimit;
5249

@@ -125,13 +122,14 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
125122
BehaviorVelocityPlannerManager planner_manager_;
126123
bool is_driving_forward_{true};
127124

128-
rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
129-
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
125+
rclcpp::Service<autoware_internal_debug_msgs::srv::String>::SharedPtr srv_load_plugin_;
126+
rclcpp::Service<autoware_internal_debug_msgs::srv::String>::SharedPtr srv_unload_plugin_;
130127
void onUnloadPlugin(
131-
const UnloadPlugin::Request::SharedPtr request,
132-
const UnloadPlugin::Response::SharedPtr response);
128+
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
129+
const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response);
133130
void onLoadPlugin(
134-
const LoadPlugin::Request::SharedPtr request, const LoadPlugin::Response::SharedPtr response);
131+
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
132+
const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response);
135133

136134
// mutex for planner_data_
137135
std::mutex mutex_;

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml

+1-6
Original file line numberDiff line numberDiff line change
@@ -32,9 +32,8 @@
3232
<buildtool_depend>autoware_cmake</buildtool_depend>
3333
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
3434

35-
<build_depend>rosidl_default_generators</build_depend>
36-
3735
<depend>autoware_behavior_velocity_planner_common</depend>
36+
<depend>autoware_internal_debug_msgs</depend>
3837
<depend>autoware_lanelet2_extension</depend>
3938
<depend>autoware_map_msgs</depend>
4039
<depend>autoware_motion_utils</depend>
@@ -60,15 +59,11 @@
6059
<depend>tier4_v2x_msgs</depend>
6160
<depend>visualization_msgs</depend>
6261

63-
<exec_depend>rosidl_default_runtime</exec_depend>
64-
6562
<test_depend>ament_cmake_ros</test_depend>
6663
<test_depend>ament_lint_auto</test_depend>
6764
<test_depend>autoware_lint_common</test_depend>
6865
<!--<test_depend>autoware_behavior_velocity_template_module</test_depend>-->
6966

70-
<member_of_group>rosidl_interface_packages</member_of_group>
71-
7267
<export>
7368
<build_type>ament_cmake</build_type>
7469
</export>

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -70,9 +70,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
7070
this->create_subscription<tier4_planning_msgs::msg::PathWithLaneId>(
7171
"~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1));
7272

73-
srv_load_plugin_ = create_service<LoadPlugin>(
73+
srv_load_plugin_ = create_service<autoware_internal_debug_msgs::srv::String>(
7474
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
75-
srv_unload_plugin_ = create_service<UnloadPlugin>(
75+
srv_unload_plugin_ = create_service<autoware_internal_debug_msgs::srv::String>(
7676
"~/service/unload_plugin",
7777
std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2));
7878

@@ -112,19 +112,19 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
112112
}
113113

114114
void BehaviorVelocityPlannerNode::onLoadPlugin(
115-
const LoadPlugin::Request::SharedPtr request,
116-
[[maybe_unused]] const LoadPlugin::Response::SharedPtr response)
115+
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
116+
[[maybe_unused]] const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response)
117117
{
118118
std::unique_lock<std::mutex> lk(mutex_);
119-
planner_manager_.launchScenePlugin(*this, request->plugin_name);
119+
planner_manager_.launchScenePlugin(*this, request->data);
120120
}
121121

122122
void BehaviorVelocityPlannerNode::onUnloadPlugin(
123-
const UnloadPlugin::Request::SharedPtr request,
124-
[[maybe_unused]] const UnloadPlugin::Response::SharedPtr response)
123+
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
124+
[[maybe_unused]] const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response)
125125
{
126126
std::unique_lock<std::mutex> lk(mutex_);
127-
planner_manager_.removeScenePlugin(*this, request->plugin_name);
127+
planner_manager_.removeScenePlugin(*this, request->data);
128128
}
129129

130130
void BehaviorVelocityPlannerNode::onParam()

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/LoadPlugin.srv

-3
This file was deleted.

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv

-3
This file was deleted.

0 commit comments

Comments
 (0)