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(autoware_planning_test_manager): porting autoware_planning_test_manager package from autoware.universe #203

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
11 changes: 11 additions & 0 deletions testing/autoware_planning_test_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_planning_test_manager)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(autoware_planning_test_manager SHARED
src/autoware_planning_test_manager.cpp
)

ament_auto_package()
92 changes: 92 additions & 0 deletions testing/autoware_planning_test_manager/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
# Autoware Planning Test Manager

## Background

In each node of the planning module, when exceptional input, such as unusual routes or significantly deviated ego-position, is given, the node may not be prepared for such input and could crash. As a result, debugging node crashes can be time-consuming. For example, if an empty trajectory is given as input and it was not anticipated during implementation, the node might crash due to the unaddressed exceptional input when changes are merged, during scenario testing or while the system is running on an actual vehicle.

## Purpose

The purpose is to provide a utility for implementing tests to ensure that node operates correctly when receiving exceptional input. By utilizing this utility and implementing tests for exceptional input, the purpose is to reduce bugs that are only discovered when actually running the system, by requiring measures for exceptional input before merging PRs.

## Features

### Confirmation of normal operation

For the test target node, confirm that the node operates correctly and publishes the required messages for subsequent nodes. To do this, test_node publish the necessary messages and confirm that the node's output is being published.

### Robustness confirmation for special inputs

After confirming normal operation, ensure that the test target node does not crash when given exceptional input. To do this, provide exceptional input from the test_node and confirm that the node does not crash.

(WIP)

## Usage

```cpp

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

// instantiate test_manager with PlanningInterfaceTestManager type
auto test_manager = std::make_shared<autoware::planning_test_manager::PlanningInterfaceTestManager>();

// get package directories for necessary configuration files
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto target_node_dir =
ament_index_cpp::get_package_share_directory("target_node");

// set arguments to get the config file
node_options.arguments(
{"--ros-args", "--params-file",
autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file",
autoware_planning_validator_dir + "/config/planning_validator.param.yaml"});

// instantiate the TargetNode with node_options
auto test_target_node = std::make_shared<TargetNode>(node_options);

// publish the necessary topics from test_manager second argument is topic name
test_manager->publishOdometry(test_target_node, "/localization/kinematic_state");
test_manager->publishMaxVelocity(
test_target_node, "velocity_smoother/input/external_velocity_limit_mps");

// set scenario_selector's input topic name(this topic is changed to test node)
test_manager->setTrajectoryInputTopicName("input/parking/trajectory");

// test with normal trajectory
ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node));

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

// test with trajectory input with empty/one point/overlapping point
ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node));

// shutdown ROS context
rclcpp::shutdown();
}
```

## Implemented tests

| Node | Test name | exceptional input | output | Exceptional input pattern |
| --------------------------- | ----------------------------------------------------------------------------------------- | ----------------- | -------------- | ------------------------------------------------------------------------------------- |
| autoware_planning_validator | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| velocity_smoother | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| obstacle_cruise_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| obstacle_stop_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| obstacle_velocity_limiter | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| path_optimizer | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
| scenario_selector | NodeTestWithExceptionTrajectoryLaneDrivingMode NodeTestWithExceptionTrajectoryParkingMode | trajectory | scenario | Empty, single point, path with duplicate points for scenarios:LANEDRIVING and PARKING |
| freespace_planner | NodeTestWithExceptionRoute | route | trajectory | Empty route |
| behavior_path_planner | NodeTestWithExceptionRoute NodeTestWithOffTrackEgoPose | route | route odometry | Empty route Off-lane ego-position |
| behavior_velocity_planner | NodeTestWithExceptionPathWithLaneID | path_with_lane_id | path | Empty path |

## Important Notes

During test execution, when launching a node, parameters are loaded from the parameter file within each package. Therefore, when adding parameters, it is necessary to add the required parameters to the parameter file in the target node package. This is to prevent the node from being unable to launch if there are missing parameters when retrieving them from the parameter file during node launch.

## Future extensions / Unimplemented parts

(WIP)
Original file line number Diff line number Diff line change
@@ -0,0 +1,121 @@
// Copyright 2023 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.

#ifndef AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
#define AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_

// since ASSERT_NO_THROW in gtest masks the exception message, redefine it.
#define ASSERT_NO_THROW_WITH_ERROR_MSG(statement) \
try { \
statement; \
SUCCEED(); \
} catch (const std::exception & e) { \
FAIL() << "Expected: " << #statement \
<< " doesn't throw an exception.\nActual: it throws. Error message: " << e.what() \
<< std::endl; \
} catch (...) { \
FAIL() << "Expected: " << #statement \
<< " doesn't throw an exception.\nActual: it throws. Error message is not available." \
<< std::endl; \
}

#include <autoware/component_interface_specs/planning.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>

#include <gtest/gtest.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

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

namespace autoware::planning_test_manager
{
class PlanningInterfaceTestManager
{
public:
PlanningInterfaceTestManager();

template <typename InputT>
void publishInput(

Check warning on line 56 in testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp

View check run for this annotation

Codecov / codecov/patch

testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp#L56

Added line #L56 was not covered by tests
const rclcpp::Node::SharedPtr target_node, const std::string & topic_name, const InputT & input,
const int repeat_count = 3) const
{
autoware::test_utils::publishToTargetNode(

Check warning on line 60 in testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp

View check run for this annotation

Codecov / codecov/patch

testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp#L60

Added line #L60 was not covered by tests
test_node_, target_node, topic_name, {}, input, repeat_count);
}

Check warning on line 62 in testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp

View check run for this annotation

Codecov / codecov/patch

testing/autoware_planning_test_manager/include/autoware/planning_test_manager/autoware_planning_test_manager.hpp#L62

Added line #L62 was not covered by tests

template <typename OutputT>
void subscribeOutput(const std::string & topic_name)
{
const auto qos = []() {
if constexpr (std::is_same_v<OutputT, autoware_planning_msgs::msg::Trajectory>) {
return rclcpp::QoS{1};
}
return rclcpp::QoS{10};
}();

test_output_subs_.push_back(test_node_->create_subscription<OutputT>(
topic_name, qos, [this](const typename OutputT::ConstSharedPtr) { received_topic_num_++; }));
}

void testWithNormalTrajectory(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);
void testWithAbnormalTrajectory(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithNormalRoute(rclcpp::Node::SharedPtr target_node, const std::string & topic_name);
void testWithAbnormalRoute(rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithBehaviorNormalRoute(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithNormalPathWithLaneId(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);
void testWithAbnormalPathWithLaneId(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithNormalPath(rclcpp::Node::SharedPtr target_node, const std::string & topic_name);
void testWithAbnormalPath(rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithOffTrackInitialPoses(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void testWithOffTrackOdometry(
rclcpp::Node::SharedPtr target_node, const std::string & topic_name);

void resetReceivedTopicNum() { received_topic_num_ = 0; }

size_t getReceivedTopicNum() const { return received_topic_num_; }

rclcpp::Node::SharedPtr getTestNode() const { return test_node_; }

private:
// Subscriber
std::vector<rclcpp::SubscriptionBase::SharedPtr> test_output_subs_;

// Node
rclcpp::Node::SharedPtr test_node_;

size_t received_topic_num_ = 0;
}; // class PlanningInterfaceTestManager

} // namespace autoware::planning_test_manager

#endif // AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
// 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.

#ifndef AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#define AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>
#include <autoware_utils/geometry/geometry.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <nav_msgs/msg/odometry.hpp>

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

namespace autoware_planning_test_manager::utils
{
using autoware::route_handler::RouteHandler;
using autoware_planning_msgs::msg::LaneletRoute;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using RouteSections = std::vector<autoware_planning_msgs::msg::LaneletSegment>;

inline Pose createPoseFromLaneID(
const lanelet::Id & lane_id, const std::string & package_name = "autoware_test_utils",
const std::string & map_filename = "lanelet2_map.osm")
{
auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename);
// create route_handler
auto route_handler = std::make_shared<RouteHandler>();
route_handler->setMap(map_bin_msg);

// get middle idx of the lanelet
const auto lanelet = route_handler->getLaneletsFromId(lane_id);
const auto center_line = lanelet.centerline();
const size_t middle_point_idx = std::floor(center_line.size() / 2.0);

// get middle position of the lanelet
geometry_msgs::msg::Point middle_pos;
middle_pos.x = center_line[middle_point_idx].x();
middle_pos.y = center_line[middle_point_idx].y();

// get next middle position of the lanelet
geometry_msgs::msg::Point next_middle_pos;
next_middle_pos.x = center_line[middle_point_idx + 1].x();
next_middle_pos.y = center_line[middle_point_idx + 1].y();

// calculate middle pose
geometry_msgs::msg::Pose middle_pose;
middle_pose.position = middle_pos;
const double yaw = autoware_utils::calc_azimuth_angle(middle_pos, next_middle_pos);
middle_pose.orientation = autoware_utils::create_quaternion_from_yaw(yaw);

return middle_pose;
}

// Function to create a route from given start and goal lanelet ids
// start pose and goal pose are set to the middle of the lanelet
inline LaneletRoute makeBehaviorRouteFromLaneId(
const int & start_lane_id, const int & goal_lane_id,
const std::string & package_name = "autoware_test_utils",
const std::string & map_filename = "lanelet2_map.osm")
{
LaneletRoute route;
route.header.frame_id = "map";
auto start_pose = createPoseFromLaneID(start_lane_id, package_name, map_filename);
auto goal_pose = createPoseFromLaneID(goal_lane_id, package_name, map_filename);
route.start_pose = start_pose;
route.goal_pose = goal_pose;

auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename);
// create route_handler
auto route_handler = std::make_shared<RouteHandler>();
route_handler->setMap(map_bin_msg);

LaneletRoute route_msg;
RouteSections route_sections;
lanelet::ConstLanelets all_route_lanelets;

// Plan the path between checkpoints (start and goal poses)
lanelet::ConstLanelets path_lanelets;
if (!route_handler->planPathLaneletsBetweenCheckpoints(start_pose, goal_pose, &path_lanelets)) {
return route_msg;
}

// Add all path_lanelets to all_route_lanelets
for (const auto & lane : path_lanelets) {
all_route_lanelets.push_back(lane);
}
// create local route sections
route_handler->setRouteLanelets(path_lanelets);
const auto local_route_sections = route_handler->createMapSegments(path_lanelets);
route_sections =
autoware::test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections);
for (const auto & route_section : route_sections) {
for (const auto & primitive : route_section.primitives) {
std::cerr << "primitive: " << primitive.id << std::endl;
}
std::cerr << "preferred_primitive id : " << route_section.preferred_primitive.id << std::endl;
}
route_handler->setRouteLanelets(all_route_lanelets);
route.segments = route_sections;

route.allow_modification = false;
return route;
}

inline Odometry makeInitialPoseFromLaneId(const lanelet::Id & lane_id)
{
Odometry current_odometry;
current_odometry.pose.pose = createPoseFromLaneID(lane_id);
current_odometry.header.frame_id = "map";

return current_odometry;
}

} // namespace autoware_planning_test_manager::utils
#endif // AUTOWARE__PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
// Copyright 2023 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.

// This file is kept for backwards compatibility. Should be removed in the future.
// Tracked by: https://github.com/autowarefoundation/autoware.core/issues/224

#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_

#include <autoware/planning_test_manager/autoware_planning_test_manager.hpp>

#endif // AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
Loading
Loading