Skip to content
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

This file was deleted.

33 changes: 0 additions & 33 deletions planning/autoware_trajectory_safety_filter/plugins.xml

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_trajectory_safety_filter)
project(autoware_trajectory_validator)

find_package(autoware_cmake REQUIRED)
autoware_package()
pluginlib_export_plugin_description_file(autoware_trajectory_safety_filter plugins.xml)
pluginlib_export_plugin_description_file(autoware_trajectory_validator plugins.xml)

generate_parameter_library(${PROJECT_NAME}_param
param/parameter_struct.yaml
Expand All @@ -14,7 +14,7 @@ include_directories(
)

ament_auto_add_library(${PROJECT_NAME} SHARED
src/trajectory_safety_filter_node.cpp
src/trajectory_validator_node.cpp
)

target_link_libraries(${PROJECT_NAME}
Expand All @@ -26,19 +26,19 @@ target_compile_options(${PROJECT_NAME} PUBLIC
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::trajectory_safety_filter::TrajectorySafetyFilter"
PLUGIN "autoware::trajectory_validator::TrajectoryValidator"
EXECUTABLE ${PROJECT_NAME}_node
)

ament_auto_add_library(autoware_trajectory_safety_filter_plugins SHARED
src/filters/out_of_lane_filter.cpp
src/filters/collision_filter.cpp
src/filters/uncrossable_boundary_departure_filter.cpp
src/filters/vehicle_constraint_filter.cpp
src/filters/collision_check_filter.cpp
ament_auto_add_library(autoware_trajectory_validator_plugins SHARED
src/filters/safety/out_of_lane_filter.cpp
src/filters/safety/collision_filter.cpp
src/filters/safety/uncrossable_boundary_departure_filter.cpp
src/filters/safety/vehicle_constraint_filter.cpp
src/filters/safety/collision_check_filter.cpp
)

target_link_libraries(autoware_trajectory_safety_filter_plugins
target_link_libraries(autoware_trajectory_validator_plugins
${PROJECT_NAME}
)

Expand All @@ -54,7 +54,7 @@ if(BUILD_TESTING)
test/plugins/test_vehicle_constraint_filter.cpp
)
target_link_libraries(test_vehicle_constraint_filter
autoware_trajectory_safety_filter_plugins
autoware_trajectory_validator_plugins
)

ament_add_ros_isolated_gtest(test_constant_curvature
Expand All @@ -80,31 +80,31 @@ if(BUILD_TESTING)
# ==========================================
# 2. Dummy Plugin (Test Utility)
# ==========================================
pluginlib_export_plugin_description_file(autoware_trajectory_safety_filter
pluginlib_export_plugin_description_file(autoware_trajectory_validator
test/dummy_plugin/dummy_plugins.xml
)

ament_auto_add_library(dummy_safety_filter_plugin SHARED
test/dummy_plugin/dummy_safety_filter_plugin.cpp
ament_auto_add_library(dummy_validator_plugin SHARED
test/dummy_plugin/dummy_validator_plugin.cpp
)

target_link_libraries(dummy_safety_filter_plugin
target_link_libraries(dummy_validator_plugin
${PROJECT_NAME}
)

# ==========================================
# 3. Node Integration/Unit Tests
# ==========================================
ament_add_ros_isolated_gtest(test_trajectory_safety_filter_node
test/node/test_trajectory_safety_filter_node.cpp
ament_add_ros_isolated_gtest(test_trajectory_validator_node
test/node/test_trajectory_validator_node.cpp
)

target_link_libraries(test_trajectory_safety_filter_node
target_link_libraries(test_trajectory_validator_node
${PROJECT_NAME}
dummy_safety_filter_plugin
dummy_validator_plugin
)

ament_target_dependencies(test_trajectory_safety_filter_node
ament_target_dependencies(test_trajectory_validator_node
autoware_test_utils
)
endif()
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/**:
ros__parameters:
filter_names:
[
"autoware::trajectory_validator::plugin::OutOfLaneFilter",
"autoware::trajectory_validator::plugin::CollisionFilter",
"autoware::trajectory_validator::plugin::CollisionCheckFilter",
"autoware::trajectory_validator::plugin::UncrossableBoundaryDepartureFilter",
"autoware::trajectory_validator::plugin::VehicleConstraintFilter",
]
# available filters:
# "autoware::trajectory_validator::plugin::OutOfLaneFilter"
# "autoware::trajectory_validator::plugin::CollisionFilter"
# "autoware::trajectory_validator::plugin::CollisionCheckFilter"
# "autoware::trajectory_validator::plugin::UncrossableBoundaryDepartureFilter"
# "autoware::trajectory_validator::plugin::VehicleConstraintFilter"

out_of_lane:
time: 2.0
min_value: 0.0

collision:
time: 3.0
min_value: 2.0

collision_check:
pet_collision:
ego_braking_delay: 0.4
ego_assumed_acceleration: -5.0
collision_time_threshold: 0.0


vehicle_constraint:
max_speed: 16.7 # m/s
max_acceleration: 5.0 # m/s^2
max_deceleration: 5.0 # m/s^2 (positive but represents deceleration)
max_steering_angle: 0.8 # rad
max_steering_rate: 0.3 # rad/s
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTER_CONTEXT_HPP_
#define AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTER_CONTEXT_HPP_
#ifndef AUTOWARE__TRAJECTORY_VALIDATOR__FILTER_CONTEXT_HPP_
#define AUTOWARE__TRAJECTORY_VALIDATOR__FILTER_CONTEXT_HPP_

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
Expand All @@ -29,7 +29,7 @@
#include <string>
#include <unordered_map>

namespace autoware::trajectory_safety_filter
namespace autoware::trajectory_validator
{

// Base context that all filters can access
Expand All @@ -40,6 +40,6 @@ struct FilterContext
std::shared_ptr<lanelet::LaneletMap> lanelet_map;
autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr predicted_objects;
};
} // namespace autoware::trajectory_safety_filter
} // namespace autoware::trajectory_validator

#endif // AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTER_CONTEXT_HPP_
#endif // AUTOWARE__TRAJECTORY_VALIDATOR__FILTER_CONTEXT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_CHECK_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_CHECK_FILTER_HPP_
#ifndef AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_CHECK_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_CHECK_FILTER_HPP_

#include "autoware/trajectory_safety_filter/safety_filter_interface.hpp"
#include "autoware/trajectory_validator/validator_interface.hpp"

#include <autoware/motion_utils/trajectory/interpolation.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
Expand All @@ -33,7 +33,7 @@
#include <unordered_map>
#include <vector>

namespace autoware::trajectory_safety_filter::plugin
namespace autoware::trajectory_validator::plugin
{
using autoware_utils_geometry::Box2d;
using autoware_utils_geometry::MultiPoint2d;
Expand Down Expand Up @@ -106,7 +106,7 @@
private:
size_t getIndex(const double t) const
{
const auto it = std::lower_bound(times_.begin(), times_.end(), t);

Check warning on line 109 in planning/autoware_trajectory_validator/include/autoware/trajectory_validator/filters/safety/collision_check_filter.hpp

View check run for this annotation

SonarQubeCloud / SonarCloud Code Analysis

Replace with the version of "std::ranges::lower_bound" that takes a range.

See more on https://sonarcloud.io/project/issues?id=tier4_autoware.universe&issues=AZzQpWLk-bigFxr2hgB_&open=AZzQpWLk-bigFxr2hgB_&pullRequest=2752

if (it == times_.begin()) return 0;
if (it == times_.end()) return times_.size() - 1;
Expand All @@ -130,10 +130,10 @@
return pose_trajectory;
}

class CollisionCheckFilter : public SafetyFilterInterface
class CollisionCheckFilter : public ValidatorInterface
{
public:
CollisionCheckFilter() : SafetyFilterInterface("CollisionCheckFilter") {}
CollisionCheckFilter() : ValidatorInterface("CollisionCheckFilter") {}

tl::expected<void, std::string> is_feasible(
const TrajectoryPoints & traj_points, const FilterContext & context) override;
Expand All @@ -148,9 +148,9 @@
double ego_braking_delay{0.0};
double ego_assumed_acceleration{0.0}; // used for code test, not used in actual collision check
double collision_time_threshold{1.0}; // time threshold for PET collision check
} pet_collision_params_;

Check warning on line 151 in planning/autoware_trajectory_validator/include/autoware/trajectory_validator/filters/safety/collision_check_filter.hpp

View check run for this annotation

SonarQubeCloud / SonarCloud Code Analysis

Declare this variable in a separate statement.

See more on https://sonarcloud.io/project/issues?id=tier4_autoware.universe&issues=AZzQpWLk-bigFxr2hgCA&open=AZzQpWLk-bigFxr2hgCA&pullRequest=2752
};

} // namespace autoware::trajectory_safety_filter::plugin
} // namespace autoware::trajectory_validator::plugin

#endif // AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_CHECK_FILTER_HPP_
#endif // AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_CHECK_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_FILTER_HPP_
#ifndef AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_FILTER_HPP_

#include "autoware/trajectory_safety_filter/safety_filter_interface.hpp"
#include "autoware/trajectory_validator/validator_interface.hpp"

#include <rclcpp/duration.hpp>

Expand All @@ -26,7 +26,7 @@
#include <string>
#include <vector>

namespace autoware::trajectory_safety_filter::plugin
namespace autoware::trajectory_validator::plugin
{

// Parameters for CollisionFilter
Expand All @@ -36,10 +36,10 @@ struct CollisionParams
double min_ttc = 2.0; // seconds - minimum acceptable time to collision
};

class CollisionFilter : public SafetyFilterInterface
class CollisionFilter : public ValidatorInterface
{
public:
CollisionFilter() : SafetyFilterInterface("CollisionFilter") {}
CollisionFilter() : ValidatorInterface("CollisionFilter") {}

tl::expected<void, std::string> is_feasible(
const TrajectoryPoints & traj_points, const FilterContext & context) final;
Expand Down Expand Up @@ -71,6 +71,6 @@ class CollisionFilter : public SafetyFilterInterface
double time_from_start) const;
};

} // namespace autoware::trajectory_safety_filter::plugin
} // namespace autoware::trajectory_validator::plugin

#endif // AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__COLLISION_FILTER_HPP_
#endif // AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__COLLISION_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__OUT_OF_LANE_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__OUT_OF_LANE_FILTER_HPP_
#ifndef AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__OUT_OF_LANE_FILTER_HPP_
#define AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__OUT_OF_LANE_FILTER_HPP_

#include "autoware/trajectory_safety_filter/safety_filter_interface.hpp"
#include "autoware/trajectory_validator/validator_interface.hpp"

#include <autoware/boundary_departure_checker/boundary_departure_checker.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
Expand All @@ -28,7 +28,7 @@
#include <string>
#include <vector>

namespace autoware::trajectory_safety_filter::plugin
namespace autoware::trajectory_validator::plugin
{

// Parameters for OutOfLaneFilter
Expand All @@ -38,7 +38,7 @@ struct OutOfLaneParams
double min_value = 0.0; // meters - minimum distance to lane boundary
};

class OutOfLaneFilter : public SafetyFilterInterface
class OutOfLaneFilter : public ValidatorInterface
{
public:
OutOfLaneFilter();
Expand All @@ -55,6 +55,6 @@ class OutOfLaneFilter : public SafetyFilterInterface
std::unique_ptr<autoware::boundary_departure_checker::BoundaryDepartureChecker>
boundary_departure_checker_;
};
} // namespace autoware::trajectory_safety_filter::plugin
} // namespace autoware::trajectory_validator::plugin

#endif // AUTOWARE__TRAJECTORY_SAFETY_FILTER__FILTERS__OUT_OF_LANE_FILTER_HPP_
#endif // AUTOWARE__TRAJECTORY_VALIDATOR__FILTERS__SAFETY__OUT_OF_LANE_FILTER_HPP_
Loading
Loading