From ee204c039c87b9dfeff0667d917c5c7fd044714f Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 24 Jun 2024 17:42:49 +0900 Subject: [PATCH] refactor: update include paths for radar_object_tracker files Signed-off-by: Taekjin LEE --- perception/radar_object_tracker/CMakeLists.txt | 2 +- .../association/data_association.hpp | 5 +++-- .../association/solver/gnn_solver_interface.hpp | 4 ++-- .../association/solver/mu_ssp.hpp | 4 ++-- .../association/solver/ssp.hpp | 4 ++-- .../radar_object_tracker_node.hpp | 4 ++++ .../model/constant_turn_rate_motion_tracker.hpp | 5 +++-- .../tracker/model/linear_motion_tracker.hpp | 5 ++++- .../tracker/model/tracker_base.hpp | 4 +++- .../utils/radar_object_tracker_utils.hpp | 4 ++-- .../radar_object_tracker/utils/utils.hpp | 5 ++--- .../src/association/data_association.cpp | 4 ++++ .../mu_successive_shortest_path_wrapper.cpp | 4 ++-- .../association/ssp/successive_shortest_path.cpp | 4 ++-- .../src/radar_object_tracker_node.cpp | 16 ++++++++++------ .../model/constant_turn_rate_motion_tracker.cpp | 10 +++++++--- .../src/tracker/model/linear_motion_tracker.cpp | 9 ++++++--- .../src/tracker/model/tracker_base.cpp | 3 +++ .../src/utils/radar_object_tracker_utils.cpp | 4 ++-- .../radar_object_tracker/src/utils/utils.cpp | 4 ++-- .../test/test_radar_object_tracker_utils.cpp | 2 +- 21 files changed, 67 insertions(+), 39 deletions(-) diff --git a/perception/radar_object_tracker/CMakeLists.txt b/perception/radar_object_tracker/CMakeLists.txt index 813f35bad0789..d5afbc06cce28 100644 --- a/perception/radar_object_tracker/CMakeLists.txt +++ b/perception/radar_object_tracker/CMakeLists.txt @@ -43,7 +43,7 @@ target_link_libraries(${PROJECT_NAME} ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "RadarObjectTrackerNode" + PLUGIN "autoware::radar_object_tracker::RadarObjectTrackerNode" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/data_association.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/data_association.hpp index 3b6b2bcb9eb19..f19dd71164d44 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/data_association.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/data_association.hpp @@ -35,7 +35,8 @@ #include #include #include - +namespace autoware::radar_object_tracker +{ class DataAssociation { private: @@ -63,5 +64,5 @@ class DataAssociation const std::string & file_name); virtual ~DataAssociation() {} }; - +} // namespace autoware::radar_object_tracker #endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__DATA_ASSOCIATION_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/gnn_solver_interface.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/gnn_solver_interface.hpp index 587ea6692da87..6244cfd29be1e 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/gnn_solver_interface.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/gnn_solver_interface.hpp @@ -18,7 +18,7 @@ #include #include -namespace gnn_solver +namespace autoware::radar_object_tracker::gnn_solver { class GnnSolverInterface { @@ -30,6 +30,6 @@ class GnnSolverInterface const std::vector> & cost, std::unordered_map * direct_assignment, std::unordered_map * reverse_assignment) = 0; }; -} // namespace gnn_solver +} // namespace autoware::radar_object_tracker::gnn_solver #endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__GNN_SOLVER_INTERFACE_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/mu_ssp.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/mu_ssp.hpp index 4567f1f50a439..bbbb3f9b14999 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/mu_ssp.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/mu_ssp.hpp @@ -20,7 +20,7 @@ #include #include -namespace gnn_solver +namespace autoware::radar_object_tracker::gnn_solver { class MuSSP : public GnnSolverInterface { @@ -32,6 +32,6 @@ class MuSSP : public GnnSolverInterface const std::vector> & cost, std::unordered_map * direct_assignment, std::unordered_map * reverse_assignment) override; }; -} // namespace gnn_solver +} // namespace autoware::radar_object_tracker::gnn_solver #endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__MU_SSP_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/ssp.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/ssp.hpp index 61a2bfa21dfef..b32a76f6d7774 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/ssp.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/association/solver/ssp.hpp @@ -20,7 +20,7 @@ #include #include -namespace gnn_solver +namespace autoware::radar_object_tracker::gnn_solver { class SSP : public GnnSolverInterface { @@ -32,6 +32,6 @@ class SSP : public GnnSolverInterface const std::vector> & cost, std::unordered_map * direct_assignment, std::unordered_map * reverse_assignment) override; }; -} // namespace gnn_solver +} // namespace autoware::radar_object_tracker::gnn_solver #endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__SSP_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/radar_object_tracker_node.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/radar_object_tracker_node.hpp index b69d88c14bd53..77487fffc7267 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/radar_object_tracker_node.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/radar_object_tracker_node.hpp @@ -49,6 +49,8 @@ #include #include +namespace autoware::radar_object_tracker +{ using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; @@ -130,4 +132,6 @@ class RadarObjectTrackerNode : public rclcpp::Node inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; }; +} // namespace autoware::radar_object_tracker + #endif // AUTOWARE__RADAR_OBJECT_TRACKER__RADAR_OBJECT_TRACKER_NODE_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp index 7bc262672e74d..6ae9cb021da1a 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp @@ -19,7 +19,8 @@ #include "kalman_filter/kalman_filter.hpp" #include - +namespace autoware::radar_object_tracker +{ using Label = autoware_perception_msgs::msg::ObjectClassification; class ConstantTurnRateMotionTracker : public Tracker // means constant turn rate motion tracker { @@ -107,5 +108,5 @@ class ConstantTurnRateMotionTracker : public Tracker // means constant turn rat autoware_perception_msgs::msg::TrackedObject & object) const override; virtual ~ConstantTurnRateMotionTracker() {} }; - +} // namespace autoware::radar_object_tracker #endif // AUTOWARE__RADAR_OBJECT_TRACKER__TRACKER__MODEL__CONSTANT_TURN_RATE_MOTION_TRACKER_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/linear_motion_tracker.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/linear_motion_tracker.hpp index 35a1fed3409d1..2e7247c908f4b 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/linear_motion_tracker.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/linear_motion_tracker.hpp @@ -20,6 +20,9 @@ #include +namespace autoware::radar_object_tracker +{ + using Label = autoware_perception_msgs::msg::ObjectClassification; class LinearMotionTracker : public Tracker { @@ -110,5 +113,5 @@ class LinearMotionTracker : public Tracker autoware_perception_msgs::msg::TrackedObject & object) const override; virtual ~LinearMotionTracker() {} }; - +} // namespace autoware::radar_object_tracker #endif // AUTOWARE__RADAR_OBJECT_TRACKER__TRACKER__MODEL__LINEAR_MOTION_TRACKER_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/tracker_base.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/tracker_base.hpp index 96aa9ac7c08d2..f106bc0a3d2fd 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/tracker_base.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/tracker/model/tracker_base.hpp @@ -33,6 +33,8 @@ #include +namespace autoware::radar_object_tracker +{ class Tracker { protected: @@ -92,5 +94,5 @@ class Tracker const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const = 0; virtual bool predict(const rclcpp::Time & time) = 0; }; - +} // namespace autoware::radar_object_tracker #endif // AUTOWARE__RADAR_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/radar_object_tracker_utils.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/radar_object_tracker_utils.hpp index 743db51188fed..b8d2f1f4d44ef 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/radar_object_tracker_utils.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/radar_object_tracker_utils.hpp @@ -46,7 +46,7 @@ #include #include -namespace radar_object_tracker_utils +namespace autoware::radar_object_tracker::utils { boost::optional getTransformAnonymous( @@ -71,6 +71,6 @@ bool hasValidVelocityDirectionToLanelet( const autoware_perception_msgs::msg::TrackedObject & object, const lanelet::ConstLanelets & lanelets, const double max_lateral_velocity); -} // namespace radar_object_tracker_utils +} // namespace autoware::radar_object_tracker::utils #endif // AUTOWARE__RADAR_OBJECT_TRACKER__UTILS__RADAR_OBJECT_TRACKER_UTILS_HPP_ diff --git a/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/utils.hpp b/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/utils.hpp index b4c2b9cdfc470..667cc34226681 100644 --- a/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/utils.hpp +++ b/perception/radar_object_tracker/include/autoware/radar_object_tracker/utils/utils.hpp @@ -33,8 +33,7 @@ #include #include #include - -namespace utils +namespace autoware::radar_object_tracker::utils { enum MSG_COV_IDX { X_X = 0, @@ -79,6 +78,6 @@ enum MSG_COV_IDX { Eigen::MatrixXd stackMatricesVertically(const std::vector & matrices); Eigen::MatrixXd stackMatricesDiagonally(const std::vector & matrices); -} // namespace utils +} // namespace autoware::radar_object_tracker::utils #endif // AUTOWARE__RADAR_OBJECT_TRACKER__UTILS__UTILS_HPP_ diff --git a/perception/radar_object_tracker/src/association/data_association.cpp b/perception/radar_object_tracker/src/association/data_association.cpp index 78f2aaaa6b349..087e632235988 100644 --- a/perception/radar_object_tracker/src/association/data_association.cpp +++ b/perception/radar_object_tracker/src/association/data_association.cpp @@ -69,6 +69,8 @@ double getFormedYawAngle( } } // namespace +namespace autoware::radar_object_tracker +{ DataAssociation::DataAssociation( std::vector can_assign_vector, std::vector max_dist_vector, std::vector max_area_vector, std::vector min_area_vector, @@ -292,3 +294,5 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( return score_matrix; } + +} // namespace autoware::radar_object_tracker diff --git a/perception/radar_object_tracker/src/association/mu_ssp/mu_successive_shortest_path_wrapper.cpp b/perception/radar_object_tracker/src/association/mu_ssp/mu_successive_shortest_path_wrapper.cpp index cb8a2967208c5..2a238b7b41513 100644 --- a/perception/radar_object_tracker/src/association/mu_ssp/mu_successive_shortest_path_wrapper.cpp +++ b/perception/radar_object_tracker/src/association/mu_ssp/mu_successive_shortest_path_wrapper.cpp @@ -24,7 +24,7 @@ #include #include -namespace gnn_solver +namespace autoware::radar_object_tracker::gnn_solver { void MuSSP::maximizeLinearAssignment( const std::vector> & cost, std::unordered_map * direct_assignment, @@ -38,4 +38,4 @@ void MuSSP::maximizeLinearAssignment( // Solve DA by muSSP solve_muSSP(cost, direct_assignment, reverse_assignment); } -} // namespace gnn_solver +} // namespace autoware::radar_object_tracker::gnn_solver diff --git a/perception/radar_object_tracker/src/association/ssp/successive_shortest_path.cpp b/perception/radar_object_tracker/src/association/ssp/successive_shortest_path.cpp index a5cfa65a4ca2d..28f4ca7820694 100644 --- a/perception/radar_object_tracker/src/association/ssp/successive_shortest_path.cpp +++ b/perception/radar_object_tracker/src/association/ssp/successive_shortest_path.cpp @@ -22,7 +22,7 @@ #include #include -namespace gnn_solver +namespace autoware::radar_object_tracker::gnn_solver { struct ResidualEdge { @@ -367,4 +367,4 @@ void SSP::maximizeLinearAssignment( } #endif } -} // namespace gnn_solver +} // namespace autoware::radar_object_tracker::gnn_solver diff --git a/perception/radar_object_tracker/src/radar_object_tracker_node.cpp b/perception/radar_object_tracker/src/radar_object_tracker_node.cpp index cbe8183500fcc..9005411066c6c 100644 --- a/perception/radar_object_tracker/src/radar_object_tracker_node.cpp +++ b/perception/radar_object_tracker/src/radar_object_tracker_node.cpp @@ -22,7 +22,6 @@ #include #include #include -#include #include @@ -38,6 +37,8 @@ #include #include +namespace autoware::radar_object_tracker +{ using Label = autoware_perception_msgs::msg::ObjectClassification; RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_options) @@ -141,7 +142,7 @@ void RadarObjectTrackerNode::onMap(const LaneletMapBin::ConstSharedPtr msg) void RadarObjectTrackerNode::onMeasurement( const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { - const auto self_transform = radar_object_tracker_utils::getTransformAnonymous( + const auto self_transform = autoware::radar_object_tracker::utils::getTransformAnonymous( tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); if (!self_transform) { return; @@ -237,7 +238,7 @@ std::shared_ptr RadarObjectTrackerNode::createNewTracker( void RadarObjectTrackerNode::onTimer() { rclcpp::Time current_time = this->now(); - const auto self_transform = radar_object_tracker_utils::getTransformAnonymous( + const auto self_transform = autoware::radar_object_tracker::utils::getTransformAnonymous( tf_buffer_, world_frame_id_, "base_link", current_time); if (!self_transform) { return; @@ -284,14 +285,14 @@ void RadarObjectTrackerNode::mapBasedNoiseFilter( for (auto itr = list_tracker.begin(); itr != list_tracker.end(); ++itr) { autoware_perception_msgs::msg::TrackedObject object; (*itr)->getTrackedObject(time, object); - const auto closest_lanelets = radar_object_tracker_utils::getClosestValidLanelets( + const auto closest_lanelets = autoware::radar_object_tracker::utils::getClosestValidLanelets( object, lanelet_map_ptr_, max_distance_from_lane_, max_angle_diff_from_lane_); // 1. If the object is not close to any lanelet, delete the tracker const bool no_closest_lanelet = closest_lanelets.empty(); // 2. If the object velocity direction is not close to the lanelet direction, delete the tracker const bool is_velocity_direction_close_to_lanelet = - radar_object_tracker_utils::hasValidVelocityDirectionToLanelet( + autoware::radar_object_tracker::utils::hasValidVelocityDirectionToLanelet( object, closest_lanelets, max_lateral_velocity_); if (no_closest_lanelet || !is_velocity_direction_close_to_lanelet) { // std::cout << "object removed due to map based noise filter" << " no close lanelet: " << @@ -422,5 +423,8 @@ void RadarObjectTrackerNode::publish(const rclcpp::Time & time) const // Publish tracked_objects_pub_->publish(output_msg); } +} // namespace autoware::radar_object_tracker + +#include -RCLCPP_COMPONENTS_REGISTER_NODE(RadarObjectTrackerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::radar_object_tracker::RadarObjectTrackerNode) diff --git a/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp index 176ca2ca34465..3703ba1fb5905 100644 --- a/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp +++ b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp @@ -42,6 +42,8 @@ #include +namespace autoware::radar_object_tracker +{ using Label = autoware_perception_msgs::msg::ObjectClassification; // init static member variables @@ -442,9 +444,9 @@ bool ConstantTurnRateMotionTracker::measureWithPose( } // stacking matrices vertically or diagonally - const auto C = utils::stackMatricesVertically(C_list); - const auto Y = utils::stackMatricesVertically(Y_list); - const auto R = utils::stackMatricesDiagonally(R_block_list); + const auto C = autoware::radar_object_tracker::utils::stackMatricesVertically(C_list); + const auto Y = autoware::radar_object_tracker::utils::stackMatricesVertically(Y_list); + const auto R = autoware::radar_object_tracker::utils::stackMatricesDiagonally(R_block_list); // 4. EKF update if (!ekf_.update(Y, C, R)) { @@ -622,3 +624,5 @@ bool ConstantTurnRateMotionTracker::getTrackedObject( return true; } + +} // namespace autoware::radar_object_tracker diff --git a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp index a693c584a96a3..8819880943f99 100644 --- a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp +++ b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp @@ -43,6 +43,8 @@ #include +namespace autoware::radar_object_tracker +{ using Label = autoware_perception_msgs::msg::ObjectClassification; // initialize static parameter @@ -468,9 +470,9 @@ bool LinearMotionTracker::measureWithPose( // Eigen::MatrixXd R = Eigen::MatrixXd::Zero(row_number, row_number); // stacking matrices vertically or diagonally - const auto C = utils::stackMatricesVertically(C_list); - const auto Y = utils::stackMatricesVertically(Y_list); - const auto R = utils::stackMatricesDiagonally(R_block_list); + const auto C = autoware::radar_object_tracker::utils::stackMatricesVertically(C_list); + const auto Y = autoware::radar_object_tracker::utils::stackMatricesVertically(Y_list); + const auto R = autoware::radar_object_tracker::utils::stackMatricesDiagonally(R_block_list); // 4. EKF update if (!ekf_.update(Y, C, R)) { @@ -688,3 +690,4 @@ bool LinearMotionTracker::getTrackedObject( return true; } +} // namespace autoware::radar_object_tracker diff --git a/perception/radar_object_tracker/src/tracker/model/tracker_base.cpp b/perception/radar_object_tracker/src/tracker/model/tracker_base.cpp index 15742c5a191e7..1d47125abe930 100644 --- a/perception/radar_object_tracker/src/tracker/model/tracker_base.cpp +++ b/perception/radar_object_tracker/src/tracker/model/tracker_base.cpp @@ -21,6 +21,8 @@ #include #include +namespace autoware::radar_object_tracker +{ Tracker::Tracker( const rclcpp::Time & time, const std::vector & classification) @@ -61,3 +63,4 @@ geometry_msgs::msg::PoseWithCovariance Tracker::getPoseWithCovariance( getTrackedObject(time, object); return object.kinematics.pose_with_covariance; } +} // namespace autoware::radar_object_tracker diff --git a/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp index 5fa3c91e3a3d9..7ad3e127ebd96 100644 --- a/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp +++ b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp @@ -14,7 +14,7 @@ #include "autoware/radar_object_tracker/utils/radar_object_tracker_utils.hpp" -namespace radar_object_tracker_utils +namespace autoware::radar_object_tracker::utils { boost::optional getTransformAnonymous( @@ -151,4 +151,4 @@ bool hasValidVelocityDirectionToLanelet( return false; } -} // namespace radar_object_tracker_utils +} // namespace autoware::radar_object_tracker::utils diff --git a/perception/radar_object_tracker/src/utils/utils.cpp b/perception/radar_object_tracker/src/utils/utils.cpp index 199a32ee0c9fa..63aebdd2f03ae 100644 --- a/perception/radar_object_tracker/src/utils/utils.cpp +++ b/perception/radar_object_tracker/src/utils/utils.cpp @@ -14,7 +14,7 @@ #include "autoware/radar_object_tracker/utils/utils.hpp" -namespace utils +namespace autoware::radar_object_tracker::utils { // concatenate matrices vertically Eigen::MatrixXd stackMatricesVertically(const std::vector & matrices) @@ -68,4 +68,4 @@ Eigen::MatrixXd stackMatricesDiagonally(const std::vector & mat return result; } -} // namespace utils +} // namespace autoware::radar_object_tracker::utils diff --git a/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp b/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp index 9f35e31641638..7505fd69859d6 100644 --- a/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp +++ b/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp @@ -16,8 +16,8 @@ #include +using autoware::radar_object_tracker::utils::checkCloseLaneletCondition; using autoware_perception_msgs::msg::TrackedObject; -using radar_object_tracker_utils::checkCloseLaneletCondition; // helper function to create a dummy straight lanelet lanelet::Lanelet createDummyStraightLanelet(double length, double width)