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(behavior_velocity_crosswalk): add node test #9763

Closed
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
Expand Up @@ -15,6 +15,7 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_crosswalk.cpp
test/test_node_interface.cpp
)
target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME})
endif()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_behavior_velocity_planner</depend>
<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_grid_map_utils</depend>
<depend>autoware_internal_debug_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <autoware/behavior_velocity_planner/test_utils.hpp>

#include <gtest/gtest.h>

#include <cmath>
#include <memory>
#include <string>
#include <vector>

namespace autoware::behavior_velocity_planner
{
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
{
rclcpp::init(0, nullptr);
auto test_manager = autoware::behavior_velocity_planner::generateTestManager();
auto test_target_node = autoware::behavior_velocity_planner::generateNode({});

autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node);

// test with nominal path_with_lane_id
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
EXPECT_GE(test_manager->getReceivedTopicNum(), 1);

// test with empty path_with_lane_id
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node));
rclcpp::shutdown();
}

TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
{
rclcpp::init(0, nullptr);

const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{
"crosswalk", "autoware::behavior_velocity_planner::CrosswalkModulePlugin"}};

auto test_manager = autoware::behavior_velocity_planner::generateTestManager();
auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec);
autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));

// make sure behavior_path_planner is running
EXPECT_GE(test_manager->getReceivedTopicNum(), 1);

ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node));

rclcpp::shutdown();
}
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,6 @@ cmake_minimum_required(VERSION 3.14)
project(autoware_behavior_velocity_planner)

find_package(autoware_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(
${PROJECT_NAME}
"srv/LoadPlugin.srv"
"srv/UnloadPlugin.srv"
DEPENDENCIES
)

autoware_package()

Expand All @@ -24,15 +16,6 @@ rclcpp_components_register_node(${PROJECT_NAME}_lib
EXECUTABLE ${PROJECT_NAME}_node
)

if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
rosidl_target_interfaces(${PROJECT_NAME}_lib
${PROJECT_NAME} "rosidl_typesupport_cpp")
else()
rosidl_get_typesupport_target(
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(${PROJECT_NAME}_lib "${cpp_typesupport_target}")
endif()

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_node_interface.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,9 @@

#include <autoware/behavior_velocity_planner_common/planner_data.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <autoware_behavior_velocity_planner/srv/load_plugin.hpp>
#include <autoware_behavior_velocity_planner/srv/unload_plugin.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/srv/string.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/path.hpp>
Expand All @@ -45,8 +44,6 @@

namespace autoware::behavior_velocity_planner
{
using autoware_behavior_velocity_planner::srv::LoadPlugin;
using autoware_behavior_velocity_planner::srv::UnloadPlugin;
using autoware_map_msgs::msg::LaneletMapBin;
using tier4_planning_msgs::msg::VelocityLimit;

Expand Down Expand Up @@ -125,13 +122,14 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
BehaviorVelocityPlannerManager planner_manager_;
bool is_driving_forward_{true};

rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
rclcpp::Service<autoware_internal_debug_msgs::srv::String>::SharedPtr srv_load_plugin_;
rclcpp::Service<autoware_internal_debug_msgs::srv::String>::SharedPtr srv_unload_plugin_;
void onUnloadPlugin(
const UnloadPlugin::Request::SharedPtr request,
const UnloadPlugin::Response::SharedPtr response);
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response);
void onLoadPlugin(
const LoadPlugin::Request::SharedPtr request, const LoadPlugin::Response::SharedPtr response);
const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request,
const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response);

// mutex for planner_data_
std::mutex mutex_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,8 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -60,15 +59,11 @@
<depend>tier4_v2x_msgs</depend>
<depend>visualization_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<!--<test_depend>autoware_behavior_velocity_template_module</test_depend>-->

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,9 +70,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
this->create_subscription<tier4_planning_msgs::msg::PathWithLaneId>(
"~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1));

srv_load_plugin_ = create_service<LoadPlugin>(
srv_load_plugin_ = create_service<autoware_internal_debug_msgs::srv::String>(
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
srv_unload_plugin_ = create_service<UnloadPlugin>(
srv_unload_plugin_ = create_service<autoware_internal_debug_msgs::srv::String>(
"~/service/unload_plugin",
std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2));

Expand Down Expand Up @@ -112,19 +112,19 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
}

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

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

void BehaviorVelocityPlannerNode::onParam()
Expand Down

This file was deleted.

This file was deleted.

Loading