Skip to content

Commit

Permalink
refactor: update include paths for radar_object_tracker files
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Jun 24, 2024
1 parent 4885248 commit ee204c0
Show file tree
Hide file tree
Showing 21 changed files with 67 additions and 39 deletions.
2 changes: 1 addition & 1 deletion perception/radar_object_tracker/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@
#include <string>
#include <unordered_map>
#include <vector>

namespace autoware::radar_object_tracker
{
class DataAssociation
{
private:
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <unordered_map>
#include <vector>

namespace gnn_solver
namespace autoware::radar_object_tracker::gnn_solver
{
class GnnSolverInterface
{
Expand All @@ -30,6 +30,6 @@ class GnnSolverInterface
const std::vector<std::vector<double>> & cost, std::unordered_map<int, int> * direct_assignment,
std::unordered_map<int, int> * reverse_assignment) = 0;
};
} // namespace gnn_solver
} // namespace autoware::radar_object_tracker::gnn_solver

#endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__GNN_SOLVER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <unordered_map>
#include <vector>

namespace gnn_solver
namespace autoware::radar_object_tracker::gnn_solver
{
class MuSSP : public GnnSolverInterface
{
Expand All @@ -32,6 +32,6 @@ class MuSSP : public GnnSolverInterface
const std::vector<std::vector<double>> & cost, std::unordered_map<int, int> * direct_assignment,
std::unordered_map<int, int> * reverse_assignment) override;
};
} // namespace gnn_solver
} // namespace autoware::radar_object_tracker::gnn_solver

#endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__MU_SSP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <unordered_map>
#include <vector>

namespace gnn_solver
namespace autoware::radar_object_tracker::gnn_solver
{
class SSP : public GnnSolverInterface
{
Expand All @@ -32,6 +32,6 @@ class SSP : public GnnSolverInterface
const std::vector<std::vector<double>> & cost, std::unordered_map<int, int> * direct_assignment,
std::unordered_map<int, int> * reverse_assignment) override;
};
} // namespace gnn_solver
} // namespace autoware::radar_object_tracker::gnn_solver

#endif // AUTOWARE__RADAR_OBJECT_TRACKER__ASSOCIATION__SOLVER__SSP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@
#include <memory>
#include <string>

namespace autoware::radar_object_tracker
{
using autoware_map_msgs::msg::LaneletMapBin;
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
Expand Down Expand Up @@ -130,4 +132,6 @@ class RadarObjectTrackerNode : public rclcpp::Node
inline bool shouldTrackerPublish(const std::shared_ptr<const Tracker> tracker) const;
};

} // namespace autoware::radar_object_tracker

#endif // AUTOWARE__RADAR_OBJECT_TRACKER__RADAR_OBJECT_TRACKER_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@
#include "kalman_filter/kalman_filter.hpp"

#include <string>

namespace autoware::radar_object_tracker
{
using Label = autoware_perception_msgs::msg::ObjectClassification;
class ConstantTurnRateMotionTracker : public Tracker // means constant turn rate motion tracker
{
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@

#include <string>

namespace autoware::radar_object_tracker
{

using Label = autoware_perception_msgs::msg::ObjectClassification;
class LinearMotionTracker : public Tracker
{
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include <vector>

namespace autoware::radar_object_tracker
{
class Tracker
{
protected:
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include <string>
#include <utility>

namespace radar_object_tracker_utils
namespace autoware::radar_object_tracker::utils
{

boost::optional<geometry_msgs::msg::Transform> getTransformAnonymous(
Expand All @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,7 @@
#include <cmath>
#include <tuple>
#include <vector>

namespace utils
namespace autoware::radar_object_tracker::utils
{
enum MSG_COV_IDX {
X_X = 0,
Expand Down Expand Up @@ -79,6 +78,6 @@ enum MSG_COV_IDX {
Eigen::MatrixXd stackMatricesVertically(const std::vector<Eigen::MatrixXd> & matrices);
Eigen::MatrixXd stackMatricesDiagonally(const std::vector<Eigen::MatrixXd> & matrices);

} // namespace utils
} // namespace autoware::radar_object_tracker::utils

#endif // AUTOWARE__RADAR_OBJECT_TRACKER__UTILS__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ double getFormedYawAngle(
}
} // namespace

namespace autoware::radar_object_tracker
{
DataAssociation::DataAssociation(
std::vector<int> can_assign_vector, std::vector<double> max_dist_vector,
std::vector<double> max_area_vector, std::vector<double> min_area_vector,
Expand Down Expand Up @@ -292,3 +294,5 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(

return score_matrix;
}

} // namespace autoware::radar_object_tracker
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <unordered_map>
#include <vector>

namespace gnn_solver
namespace autoware::radar_object_tracker::gnn_solver
{
void MuSSP::maximizeLinearAssignment(
const std::vector<std::vector<double>> & cost, std::unordered_map<int, int> * direct_assignment,
Expand All @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <utility>
#include <vector>

namespace gnn_solver
namespace autoware::radar_object_tracker::gnn_solver
{
struct ResidualEdge
{
Expand Down Expand Up @@ -367,4 +367,4 @@ void SSP::maximizeLinearAssignment(
}
#endif
}
} // namespace gnn_solver
} // namespace autoware::radar_object_tracker::gnn_solver
16 changes: 10 additions & 6 deletions perception/radar_object_tracker/src/radar_object_tracker_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include <boost/optional.hpp>

Expand All @@ -38,6 +37,8 @@
#include <utility>
#include <vector>

namespace autoware::radar_object_tracker
{
using Label = autoware_perception_msgs::msg::ObjectClassification;

RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_options)
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -237,7 +238,7 @@ std::shared_ptr<Tracker> 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;
Expand Down Expand Up @@ -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: " <<
Expand Down Expand Up @@ -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_macro.hpp>

RCLCPP_COMPONENTS_REGISTER_NODE(RadarObjectTrackerNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::radar_object_tracker::RadarObjectTrackerNode)
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@

#include <yaml-cpp/yaml.h>

namespace autoware::radar_object_tracker
{
using Label = autoware_perception_msgs::msg::ObjectClassification;

// init static member variables
Expand Down Expand Up @@ -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)) {
Expand Down Expand Up @@ -622,3 +624,5 @@ bool ConstantTurnRateMotionTracker::getTrackedObject(

return true;
}

} // namespace autoware::radar_object_tracker
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@

#include <yaml-cpp/yaml.h>

namespace autoware::radar_object_tracker
{
using Label = autoware_perception_msgs::msg::ObjectClassification;

// initialize static parameter
Expand Down Expand Up @@ -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)) {
Expand Down Expand Up @@ -688,3 +690,4 @@ bool LinearMotionTracker::getTrackedObject(

return true;
}
} // namespace autoware::radar_object_tracker
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <algorithm>
#include <random>

namespace autoware::radar_object_tracker
{
Tracker::Tracker(
const rclcpp::Time & time,
const std::vector<autoware_perception_msgs::msg::ObjectClassification> & classification)
Expand Down Expand Up @@ -61,3 +63,4 @@ geometry_msgs::msg::PoseWithCovariance Tracker::getPoseWithCovariance(
getTrackedObject(time, object);
return object.kinematics.pose_with_covariance;
}
} // namespace autoware::radar_object_tracker
Original file line number Diff line number Diff line change
Expand Up @@ -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<geometry_msgs::msg::Transform> getTransformAnonymous(
Expand Down Expand Up @@ -151,4 +151,4 @@ bool hasValidVelocityDirectionToLanelet(
return false;
}

} // namespace radar_object_tracker_utils
} // namespace autoware::radar_object_tracker::utils
4 changes: 2 additions & 2 deletions perception/radar_object_tracker/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<Eigen::MatrixXd> & matrices)
Expand Down Expand Up @@ -68,4 +68,4 @@ Eigen::MatrixXd stackMatricesDiagonally(const std::vector<Eigen::MatrixXd> & mat
return result;
}

} // namespace utils
} // namespace autoware::radar_object_tracker::utils
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@

#include <gtest/gtest.h>

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)
Expand Down

0 comments on commit ee204c0

Please sign in to comment.