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(behavior_path_planner): common test functions #9963

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
Expand Up @@ -12,11 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp"

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>
#include "autoware/behavior_path_planner/test_utils.hpp"

#include <gtest/gtest.h>

Expand All @@ -25,84 +21,18 @@
#include <string>
#include <vector>

using autoware::behavior_path_planner::BehaviorPathPlannerNode;
using autoware::planning_test_manager::PlanningInterfaceTestManager;

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();

// set subscriber with topic name: behavior_path_planner → test_node_
test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path");

// set behavior_path_planner's input topic name(this topic is changed to test node)
test_manager->setRouteInputTopicName("behavior_path_planner/input/route");

test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry");

return test_manager;
}

std::shared_ptr<BehaviorPathPlannerNode> generateNode()
{
auto node_options = rclcpp::NodeOptions{};
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto behavior_path_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
const auto behavior_path_lane_change_module_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module");

std::vector<std::string> module_names;
module_names.emplace_back("autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager");

std::vector<rclcpp::Parameter> params;
params.emplace_back("launch_modules", module_names);
node_options.parameter_overrides(params);

autoware::test_utils::updateNodeOptions(
node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml",
autoware_test_utils_dir + "/config/test_nearest_search.param.yaml",
autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml",
behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml",
behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml",
behavior_path_planner_dir + "/config/scene_module_manager.param.yaml",
behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml",
ament_index_cpp::get_package_share_directory(
"autoware_behavior_path_static_obstacle_avoidance_module") +
"/config/static_obstacle_avoidance.param.yaml",
ament_index_cpp::get_package_share_directory(
"autoware_behavior_path_avoidance_by_lane_change_module") +
"/config/avoidance_by_lane_change.param.yaml"});

return std::make_shared<BehaviorPathPlannerNode>(node_options);
}

void publishMandatoryTopics(
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
std::shared_ptr<BehaviorPathPlannerNode> test_target_node)
{
// publish necessary topics from test_manager
test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry");
test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel");
test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception");
test_manager->publishOccupancyGrid(
test_target_node, "behavior_path_planner/input/occupancy_grid_map");
test_manager->publishLaneDrivingScenario(
test_target_node, "behavior_path_planner/input/scenario");
test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map");
test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap");
test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state");
test_manager->publishLateralOffset(
test_target_node, "behavior_path_planner/input/lateral_offset");
}
using autoware::behavior_path_planner::generateNode;
using autoware::behavior_path_planner::generateTestManager;
using autoware::behavior_path_planner::publishMandatoryTopics;

TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute)
{
rclcpp::init(0, nullptr);
auto test_manager = generateTestManager();
auto test_target_node = generateNode();

auto test_manager = generateTestManager();
auto test_target_node = generateNode(
{"lane_change", "static_obstacle_avoidance", "avoidance_by_lane_change"},
{"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"});
publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
Expand All @@ -119,7 +49,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
rclcpp::init(0, nullptr);

auto test_manager = generateTestManager();
auto test_target_node = generateNode();
auto test_target_node = generateNode(
{"lane_change", "static_obstacle_avoidance", "avoidance_by_lane_change"},
{"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"});
publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,87 +12,23 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp"

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>
#include "autoware/behavior_path_planner/test_utils.hpp"

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

using autoware::behavior_path_planner::BehaviorPathPlannerNode;
using autoware::planning_test_manager::PlanningInterfaceTestManager;

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();

// set subscriber with topic name: behavior_path_planner → test_node_
test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path");

// set behavior_path_planner's input topic name(this topic is changed to test node)
test_manager->setRouteInputTopicName("behavior_path_planner/input/route");

test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry");

return test_manager;
}

std::shared_ptr<BehaviorPathPlannerNode> generateNode()
{
auto node_options = rclcpp::NodeOptions{};
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto behavior_path_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");

std::vector<std::string> module_names;
module_names.emplace_back("autoware::behavior_path_planner::DynamicAvoidanceModuleManager");

std::vector<rclcpp::Parameter> params;
params.emplace_back("launch_modules", module_names);
node_options.parameter_overrides(params);

autoware::test_utils::updateNodeOptions(
node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml",
autoware_test_utils_dir + "/config/test_nearest_search.param.yaml",
autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml",
behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml",
behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml",
behavior_path_planner_dir + "/config/scene_module_manager.param.yaml",
ament_index_cpp::get_package_share_directory(
"autoware_behavior_path_dynamic_obstacle_avoidance_module") +
"/config/dynamic_obstacle_avoidance.param.yaml"});

return std::make_shared<BehaviorPathPlannerNode>(node_options);
}

void publishMandatoryTopics(
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
std::shared_ptr<BehaviorPathPlannerNode> test_target_node)
{
// publish necessary topics from test_manager
test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry");
test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel");
test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception");
test_manager->publishOccupancyGrid(
test_target_node, "behavior_path_planner/input/occupancy_grid_map");
test_manager->publishLaneDrivingScenario(
test_target_node, "behavior_path_planner/input/scenario");
test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map");
test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap");
test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state");
test_manager->publishLateralOffset(
test_target_node, "behavior_path_planner/input/lateral_offset");
}
using autoware::behavior_path_planner::generateNode;
using autoware::behavior_path_planner::generateTestManager;
using autoware::behavior_path_planner::publishMandatoryTopics;

TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute)
{
rclcpp::init(0, nullptr);
auto test_manager = generateTestManager();
auto test_target_node = generateNode();
auto test_target_node = generateNode(
{"dynamic_obstacle_avoidance"},
{"autoware::behavior_path_planner::DynamicObstacleAvoidanceModuleManager"});

publishMandatoryTopics(test_manager, test_target_node);

Expand All @@ -110,7 +46,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
rclcpp::init(0, nullptr);

auto test_manager = generateTestManager();
auto test_target_node = generateNode();
auto test_target_node = generateNode(
{"dynamic_obstacle_avoidance"},
{"autoware::behavior_path_planner::DynamicObstacleAvoidanceModuleManager"});
publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp"
#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp"
#include "autoware_test_utils/autoware_test_utils.hpp"
#include "autoware/behavior_path_planner/test_utils.hpp"

#include <gtest/gtest.h>

Expand All @@ -24,83 +21,19 @@
#include <string>
#include <vector>

using autoware::behavior_path_planner::BehaviorPathPlannerNode;
using autoware::planning_test_manager::PlanningInterfaceTestManager;

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();

// set subscriber with topic name: behavior_path_planner → test_node_
test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path");

// set behavior_path_planner's input topic name(this topic is changed to test node)
test_manager->setRouteInputTopicName("behavior_path_planner/input/route");

test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry");

return test_manager;
}

std::shared_ptr<BehaviorPathPlannerNode> generateNode()
{
auto node_options = rclcpp::NodeOptions{};
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto behavior_path_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
const auto behavior_path_lane_change_module_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module");

std::vector<std::string> module_names;
module_names.emplace_back(
"autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager");
module_names.emplace_back(
"autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager");

std::vector<rclcpp::Parameter> params;
params.emplace_back("launch_modules", module_names);
node_options.parameter_overrides(params);

autoware::test_utils::updateNodeOptions(
node_options, {
autoware_test_utils_dir + "/config/test_common.param.yaml",
autoware_test_utils_dir + "/config/test_nearest_search.param.yaml",
autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml",
behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml",
behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml",
behavior_path_planner_dir + "/config/scene_module_manager.param.yaml",
behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml",
});

return std::make_shared<BehaviorPathPlannerNode>(node_options);
}

void publishMandatoryTopics(
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
std::shared_ptr<BehaviorPathPlannerNode> test_target_node)
{
// publish necessary topics from test_manager
test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry");
test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel");
test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception");
test_manager->publishOccupancyGrid(
test_target_node, "behavior_path_planner/input/occupancy_grid_map");
test_manager->publishLaneDrivingScenario(
test_target_node, "behavior_path_planner/input/scenario");
test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map");
test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap");
test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state");
test_manager->publishLateralOffset(
test_target_node, "behavior_path_planner/input/lateral_offset");
}
using autoware::behavior_path_planner::generateNode;
using autoware::behavior_path_planner::generateTestManager;
using autoware::behavior_path_planner::publishMandatoryTopics;

TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute)
{
rclcpp::init(0, nullptr);
auto test_manager = generateTestManager();
auto test_target_node = generateNode();

auto test_manager = generateTestManager();
auto test_target_node = generateNode(
{"lane_change"},
{"autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager",
"autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"});
publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
Expand All @@ -117,7 +50,10 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
rclcpp::init(0, nullptr);

auto test_manager = generateTestManager();
auto test_target_node = generateNode();
auto test_target_node = generateNode(
{"lane_change"},
{"autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager",
"autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"});
publishMandatoryTopics(test_manager, test_target_node);

// test for normal trajectory
Expand Down
Loading
Loading