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(multi_object_tracker): tracker refactoring #7271

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
d6e50a9
feat: separate filters
technolojin Jun 6, 2024
24f66cd
fix: object validator to modular
technolojin Jun 7, 2024
c5eeaa5
fix: replace xyzrpy covariance index
technolojin May 30, 2024
68d9964
chore: refactor tracker class members
technolojin Jun 4, 2024
6a752a8
chore: refactor
technolojin Jun 4, 2024
a75daa8
chore: refactoring destructor
technolojin Jun 4, 2024
0f9089b
chore: refactoring getUpdatingObject
technolojin Jun 4, 2024
4b0e6cf
chore: refactoring object size checker
technolojin Jun 4, 2024
b963c09
fix: debugger delay calculation order is fixed
technolojin Jun 4, 2024
34057df
fix: bicycle size update bug fix
technolojin Jun 5, 2024
daa4e16
fix: renamed message package
technolojin Jun 5, 2024
8cf586a
chore: refactoring
technolojin Jun 10, 2024
74f08da
feat: object parameter class
technolojin Jun 10, 2024
80806ce
style(pre-commit): autofix
pre-commit-ci[bot] Jun 10, 2024
b316282
chore: refactor includes
technolojin Jun 13, 2024
9fb235c
feat: initial impl. of object model
technolojin Jun 13, 2024
cbb1a58
feat: impl. object model to bicycle, big, normal
technolojin Jun 13, 2024
cb895a9
feat: impl. object model to pedestrian
technolojin Jun 13, 2024
716d1b8
feat: impl. cont
technolojin Jun 13, 2024
2e86d09
style(pre-commit): autofix
pre-commit-ci[bot] Jun 13, 2024
9bdd911
chore: fix missing refactoring
technolojin Jun 13, 2024
ad97751
fix: align unit of angles, yaw rates
technolojin Jun 13, 2024
724dc8e
fix: rename tier4_autoware_utils to autoware_universe_utils
technolojin Jun 18, 2024
b63596d
fix: missing unit conversion
technolojin Jun 18, 2024
8cbb2f3
style(pre-commit): autofix
pre-commit-ci[bot] Jun 18, 2024
0f62e75
fix: sources
technolojin Jun 18, 2024
b139ffd
chore: Update include and import statements
technolojin Jun 19, 2024
0e84b4d
fix: unit convert bug
technolojin Jun 20, 2024
10fdb99
fix: update to autoware::universe_utils
technolojin Jun 20, 2024
3f20c98
fix: mis-implementation of process noise
technolojin Jun 20, 2024
893fdc5
Merge branch 'main' into feat/mot_tracker_refactoring
technolojin Jun 21, 2024
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 @@ -19,19 +19,20 @@
#ifndef MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_
#define MULTI_OBJECT_TRACKER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_

#include <list>
#include <memory>
#include <unordered_map>
#include <vector>

#define EIGEN_MPL2_ONLY

#include "multi_object_tracker/data_association/solver/gnn_solver.hpp"
#include "multi_object_tracker/tracker/tracker.hpp"

#include <Eigen/Core>
#include <Eigen/Geometry>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"

#include <list>
#include <memory>
#include <unordered_map>
#include <vector>

class DataAssociation
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,15 @@
#ifndef MULTI_OBJECT_TRACKER__DEBUGGER__DEBUG_OBJECT_HPP_
#define MULTI_OBJECT_TRACKER__DEBUGGER__DEBUG_OBJECT_HPP_

#include "autoware/universe_utils/ros/uuid_helper.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"

#include <autoware/universe_utils/ros/uuid_helper.hpp>
#include <rclcpp/rclcpp.hpp>

#include "unique_identifier_msgs/msg/uuid.hpp"
#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include "autoware_perception_msgs/msg/tracked_objects.hpp"
#include <geometry_msgs/msg/point.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <boost/functional/hash.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,16 +15,16 @@
#ifndef MULTI_OBJECT_TRACKER__DEBUGGER__DEBUGGER_HPP_
#define MULTI_OBJECT_TRACKER__DEBUGGER__DEBUGGER_HPP_

#include "autoware/universe_utils/ros/debug_publisher.hpp"
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
#include "multi_object_tracker/debugger/debug_object.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include "autoware_perception_msgs/msg/tracked_objects.hpp"
#include <geometry_msgs/msg/pose_stamped.hpp>

#include <list>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include "autoware_perception_msgs/msg/tracked_objects.hpp"
#include <geometry_msgs/msg/pose_stamped.hpp>

#include <tf2/LinearMath/Transform.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include "autoware_perception_msgs/msg/tracked_objects.hpp"

#include <list>
#include <map>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,24 +19,18 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
#include "multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp"

#include <kalman_filter/kalman_filter.hpp>
#include "multi_object_tracker/tracker/object_model/object_model.hpp"

class BicycleTracker : public Tracker
{
private:
autoware_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;

private:
struct EkfParams
{
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
} ekf_params_;
object_model::ObjectModel object_model_ = object_model::bicycle;

double z_;

Expand All @@ -48,9 +42,7 @@ class BicycleTracker : public Tracker
};
BoundingBox bounding_box_;

private:
BicycleMotionModel motion_model_;
const char DIM = motion_model_.DIM;
using IDX = BicycleMotionModel::IDX;

public:
Expand All @@ -63,15 +55,16 @@ class BicycleTracker : public Tracker
bool measure(
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_perception_msgs::msg::TrackedObject & object) const override;
virtual ~BicycleTracker() {}

private:
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform) const;
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,25 +19,19 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
#include "multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp"

#include <kalman_filter/kalman_filter.hpp>
#include "multi_object_tracker/tracker/object_model/object_model.hpp"

class BigVehicleTracker : public Tracker
{
private:
autoware_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;

private:
struct EkfParams
{
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
double r_cov_vel;
} ekf_params_;
object_model::ObjectModel object_model_ = object_model::big_vehicle;

double velocity_deviation_threshold_;

double z_;
Expand All @@ -51,9 +45,7 @@ class BigVehicleTracker : public Tracker
BoundingBox bounding_box_;
Eigen::Vector2d tracking_offset_;

private:
BicycleMotionModel motion_model_;
const char DIM = motion_model_.DIM;
using IDX = BicycleMotionModel::IDX;

public:
Expand All @@ -66,15 +58,16 @@ class BigVehicleTracker : public Tracker
bool measure(
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_perception_msgs::msg::TrackedObject & object) const override;
virtual ~BigVehicleTracker() {}

private:
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/big_vehicle_tracker.hpp"
#include "multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"

#include <kalman_filter/kalman_filter.hpp>
#include <rclcpp/time.hpp>

class MultipleVehicleTracker : public Tracker
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,25 +19,19 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
#include "multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp"

#include <kalman_filter/kalman_filter.hpp>
#include "multi_object_tracker/tracker/object_model/object_model.hpp"

class NormalVehicleTracker : public Tracker
{
private:
autoware_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;

private:
struct EkfParams
{
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
double r_cov_vel;
} ekf_params_;
object_model::ObjectModel object_model_ = object_model::normal_vehicle;

double velocity_deviation_threshold_;

double z_;
Expand All @@ -51,9 +45,7 @@ class NormalVehicleTracker : public Tracker
BoundingBox bounding_box_;
Eigen::Vector2d tracking_offset_;

private:
BicycleMotionModel motion_model_;
const char DIM = motion_model_.DIM;
using IDX = BicycleMotionModel::IDX;

public:
Expand All @@ -66,15 +58,16 @@ class NormalVehicleTracker : public Tracker
bool measure(
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_perception_msgs::msg::TrackedObject & object) const override;
virtual ~NormalVehicleTracker() {}

private:
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,9 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__PASS_THROUGH_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PASS_THROUGH_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "tracker_base.hpp"

#include <kalman_filter/kalman_filter.hpp>

class PassThroughTracker : public Tracker
{
private:
Expand All @@ -43,7 +42,6 @@ class PassThroughTracker : public Tracker
bool getTrackedObject(
const rclcpp::Time & time,
autoware_perception_msgs::msg::TrackedObject & object) const override;
virtual ~PassThroughTracker() {}
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__PASS_THROUGH_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,11 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/bicycle_tracker.hpp"
#include "multi_object_tracker/tracker/model/pedestrian_tracker.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"

#include <kalman_filter/kalman_filter.hpp>

class PedestrianAndBicycleTracker : public Tracker
{
private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_

#include "kalman_filter/kalman_filter.hpp"
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
#include "multi_object_tracker/tracker/motion_model/ctrv_motion_model.hpp"

#include <kalman_filter/kalman_filter.hpp>
#include "multi_object_tracker/tracker/object_model/object_model.hpp"

// cspell: ignore CTRV

Expand All @@ -32,13 +32,7 @@ class PedestrianTracker : public Tracker
autoware_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;

private:
struct EkfParams
{
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
} ekf_params_;
object_model::ObjectModel object_model_ = object_model::pedestrian;

double z_;

Expand All @@ -56,9 +50,7 @@ class PedestrianTracker : public Tracker
BoundingBox bounding_box_;
Cylinder cylinder_;

private:
CTRVMotionModel motion_model_;
const char DIM = motion_model_.DIM;
using IDX = CTRVMotionModel::IDX;

public:
Expand All @@ -71,15 +63,16 @@ class PedestrianTracker : public Tracker
bool measure(
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_perception_msgs::msg::TrackedObject & object) const override;
virtual ~PedestrianTracker() {}

private:
autoware_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform) const;
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@

#include "autoware_perception_msgs/msg/detected_object.hpp"
#include "autoware_perception_msgs/msg/tracked_object.hpp"
#include "geometry_msgs/msg/point.hpp"
#include "unique_identifier_msgs/msg/uuid.hpp"
#include <geometry_msgs/msg/point.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>

#include <vector>

Expand All @@ -54,7 +54,7 @@ class Tracker
const rclcpp::Time & time,
const std::vector<autoware_perception_msgs::msg::ObjectClassification> & classification,
const size_t & channel_size);
virtual ~Tracker() {}
virtual ~Tracker() = default;

void initializeExistenceProbabilities(
const uint & channel_index, const float & existence_probability);
Expand Down
Loading
Loading