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

refactor(multi_object_tracker): define motion model class #6587

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
1e43240
fix: define function to adjust object yaw angle for ekf update
technolojin Feb 29, 2024
b05e245
chore: refactoring
technolojin Feb 29, 2024
c5b8923
feat: update tracking offset to object position
technolojin Feb 29, 2024
67854be
fix: enlarge yaw noise when the orientation is unknown
technolojin Feb 29, 2024
7872045
fix: rearrange obj extension, noise model, observation vector length
technolojin Feb 29, 2024
1fd336a
chore: grouping part of codes
technolojin Mar 1, 2024
e7d99df
fix: separate object pre-process getUpdatingObject
technolojin Mar 1, 2024
1116da2
fix: bicycle tracker object preprocessing
technolojin Mar 1, 2024
31c69fe
feat: separated motion model class, not tested
technolojin Mar 4, 2024
80e3a7e
feat: add motion model
technolojin Mar 4, 2024
ff16d47
feat: replace tracker to motion model class
technolojin Mar 4, 2024
749c575
feat: normal vehicle tracker replace to motion model
technolojin Mar 5, 2024
f0bf549
feat: big vehicle tracker is replaced by motion model
technolojin Mar 5, 2024
990118b
feat: bicycle tracker replace by motion model
technolojin Mar 5, 2024
cbfbc16
chore: remove non-used members
technolojin Mar 5, 2024
10b1ba6
feat: add CTRV motion model and implement it to pedestrian tracker
technolojin Mar 5, 2024
aac22fc
chore: refactoring parameters
technolojin Mar 5, 2024
0f69b52
fix: object initialization
technolojin Mar 5, 2024
1590097
chore: grouping param setting
technolojin Mar 6, 2024
7cf0873
feat: create cv motion model, not tested
technolojin Mar 6, 2024
05adc6e
feat: implementing unknown tracker, process is dying
technolojin Mar 6, 2024
201f8ac
fix: align number precisions to double
technolojin Mar 6, 2024
f6d7d06
fix: resolve overflow issue by including proper header files
technolojin Mar 6, 2024
c0b706c
fix: missing twist cov
technolojin Mar 6, 2024
9d1a509
fix: limit too large dt on unknown tracker, set size gain to 0.1
technolojin Mar 6, 2024
d017983
fix: set parameter before init
technolojin Mar 7, 2024
5fc6f93
chore: fix init to initialize
technolojin Mar 7, 2024
09d7189
feat: motion model base class
technolojin Mar 7, 2024
ca4c32c
feat: common methods to the base class
technolojin Mar 7, 2024
76118a5
fix: access to state vector
technolojin Mar 7, 2024
35fd24a
fix: remove not-used tracker's last_update_time_ member
technolojin Mar 7, 2024
cd353d1
Revert "fix: remove not-used tracker's last_update_time_ member"
technolojin Mar 7, 2024
a0184eb
fix: header cleanup
technolojin Mar 8, 2024
98c3b25
fix: relocate motion models
technolojin Mar 8, 2024
c313d7b
fix: timestamp const
technolojin Mar 8, 2024
54e6248
fix: exception when object couldn't be predicted
technolojin Mar 8, 2024
0189ebb
fix: remove last_update_time_ member
technolojin Mar 8, 2024
61c3172
fix: set minimum size, to avoid iou error/overflow
technolojin Mar 8, 2024
42a2ef6
fix: rollback tracking size and offset algorithm
technolojin Mar 12, 2024
09201ea
fix: set minimum pedestrian size
technolojin Mar 12, 2024
72adba3
fix: adjust minimum sizes to 0.3m
technolojin Mar 12, 2024
08f3741
chore: cleanup unused members
technolojin Mar 13, 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
8 changes: 6 additions & 2 deletions perception/multi_object_tracker/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,12 @@ include_directories(
# Generate exe file
set(MULTI_OBJECT_TRACKER_SRC
src/multi_object_tracker_core.cpp
src/data_association/data_association.cpp
src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp
src/tracker/motion_model/motion_model_base.cpp
src/tracker/motion_model/bicycle_motion_model.cpp
src/tracker/motion_model/ctrv_motion_model.cpp
src/tracker/motion_model/cv_motion_model.cpp
src/tracker/model/tracker_base.cpp
src/tracker/model/big_vehicle_tracker.cpp
src/tracker/model/normal_vehicle_tracker.cpp
Expand All @@ -31,8 +37,6 @@ set(MULTI_OBJECT_TRACKER_SRC
src/tracker/model/pedestrian_and_bicycle_tracker.cpp
src/tracker/model/unknown_tracker.cpp
src/tracker/model/pass_through_tracker.cpp
src/data_association/data_association.cpp
src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp
)

ament_auto_add_library(multi_object_tracker_node SHARED
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_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>

Expand All @@ -30,55 +31,40 @@ class BicycleTracker : public Tracker
rclcpp::Logger logger_;

private:
KalmanFilter ekf_;
rclcpp::Time last_update_time_;
enum IDX { X = 0, Y = 1, YAW = 2, VEL = 3, SLIP = 4 };
struct EkfParams
{
char dim_x = 5;
float q_stddev_acc_long;
float q_stddev_acc_lat;
float q_stddev_yaw_rate_min;
float q_stddev_yaw_rate_max;
float q_cov_slip_rate_min;
float q_cov_slip_rate_max;
float q_max_slip_angle;
float p0_cov_vel;
float p0_cov_slip;
float r_cov_x;
float r_cov_y;
float r_cov_yaw;
float p0_cov_x;
float p0_cov_y;
float p0_cov_yaw;
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
} ekf_params_;

double max_vel_;
double max_slip_;
double lf_;
double lr_;
float z_;
double z_;

private:
struct BoundingBox
{
double length;
double width;
double height;
};
BoundingBox bounding_box_;
BoundingBox last_input_bounding_box_;

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

public:
BicycleTracker(
const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);

bool predict(const rclcpp::Time & time) override;
bool predict(const double dt, KalmanFilter & ekf) const;
bool measure(
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_auto_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,47 +20,28 @@
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_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>

class BigVehicleTracker : public Tracker
{
private:
autoware_auto_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;
int last_nearest_corner_index_;

private:
KalmanFilter ekf_;
rclcpp::Time last_update_time_;
enum IDX { X = 0, Y = 1, YAW = 2, VEL = 3, SLIP = 4 };
struct EkfParams
{
char dim_x = 5;
float q_stddev_acc_long;
float q_stddev_acc_lat;
float q_stddev_yaw_rate_min;
float q_stddev_yaw_rate_max;
float q_cov_slip_rate_min;
float q_cov_slip_rate_max;
float q_max_slip_angle;
float p0_cov_vel;
float p0_cov_slip;
float r_cov_x;
float r_cov_y;
float r_cov_yaw;
float r_cov_vel;
float p0_cov_x;
float p0_cov_y;
float p0_cov_yaw;
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
double r_cov_vel;
} ekf_params_;
double max_vel_;
double max_slip_;
double lf_;
double lr_;
float z_;
double velocity_deviation_threshold_;

private:
double z_;

struct BoundingBox
{
double length;
Expand All @@ -70,25 +51,41 @@
BoundingBox bounding_box_;
BoundingBox last_input_bounding_box_;
Eigen::Vector2d tracking_offset_;
int last_nearest_corner_index_;

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

public:
BigVehicleTracker(
const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);

bool predict(const rclcpp::Time & time) override;
bool predict(const double dt, KalmanFilter & ekf) const;
bool measure(
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_auto_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_auto_perception_msgs::msg::TrackedObject & object) const override;
double getMeasurementYaw(const autoware_auto_perception_msgs::msg::DetectedObject & object);
void setNearestCornerOrSurfaceIndex(const geometry_msgs::msg::Transform & self_transform);
virtual ~BigVehicleTracker() {}

private:
void setNearestCornerOrSurfaceIndex(const geometry_msgs::msg::Transform & self_transform)

Check warning on line 81 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp#L81

Added line #L81 was not covered by tests
{
Eigen::MatrixXd X_t(DIM, 1);

Check warning on line 83 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp#L83

Added line #L83 was not covered by tests
motion_model_.getStateVector(X_t);
last_nearest_corner_index_ = utils::getNearestCornerOrSurface(

Check warning on line 85 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp#L85

Added line #L85 was not covered by tests
X_t(IDX::X), X_t(IDX::Y), X_t(IDX::YAW), bounding_box_.width, bounding_box_.length,
self_transform);
}

Check warning on line 88 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp#L88

Added line #L88 was not covered by tests
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@
#ifndef MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_

#include "tracker_base.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>

Expand All @@ -28,42 +29,19 @@
private:
autoware_auto_perception_msgs::msg::DetectedObject object_;
rclcpp::Logger logger_;
int last_nearest_corner_index_;

private:
KalmanFilter ekf_;
rclcpp::Time last_update_time_;
enum IDX { X = 0, Y = 1, YAW = 2, VEL = 3, SLIP = 4 };

struct EkfParams
{
char dim_x = 5;
float q_stddev_acc_long;
float q_stddev_acc_lat;
float q_stddev_yaw_rate_min;
float q_stddev_yaw_rate_max;
float q_cov_slip_rate_min;
float q_cov_slip_rate_max;
float q_max_slip_angle;
float p0_cov_vel;
float p0_cov_slip;
float r_cov_x;
float r_cov_y;
float r_cov_yaw;
float r_cov_vel;
float p0_cov_x;
float p0_cov_y;
float p0_cov_yaw;
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
double r_cov_vel;
} ekf_params_;

double max_vel_;
double max_slip_;
double lf_;
double lr_;
float z_;
double velocity_deviation_threshold_;

private:
double z_;

struct BoundingBox
{
double length;
Expand All @@ -73,25 +51,41 @@
BoundingBox bounding_box_;
BoundingBox last_input_bounding_box_;
Eigen::Vector2d tracking_offset_;
int last_nearest_corner_index_;

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

public:
NormalVehicleTracker(
const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);

bool predict(const rclcpp::Time & time) override;
bool predict(const double dt, KalmanFilter & ekf) const;
bool measure(
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_auto_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
const rclcpp::Time & time,
autoware_auto_perception_msgs::msg::TrackedObject & object) const override;
void setNearestCornerOrSurfaceIndex(const geometry_msgs::msg::Transform & self_transform);
double getMeasurementYaw(const autoware_auto_perception_msgs::msg::DetectedObject & object);
virtual ~NormalVehicleTracker() {}

private:
void setNearestCornerOrSurfaceIndex(const geometry_msgs::msg::Transform & self_transform)

Check warning on line 81 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp#L81

Added line #L81 was not covered by tests
{
Eigen::MatrixXd X_t(DIM, 1);

Check warning on line 83 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp#L83

Added line #L83 was not covered by tests
motion_model_.getStateVector(X_t);
last_nearest_corner_index_ = utils::getNearestCornerOrSurface(

Check warning on line 85 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp#L85

Added line #L85 was not covered by tests
X_t(IDX::X), X_t(IDX::Y), X_t(IDX::YAW), bounding_box_.width, bounding_box_.length,
self_transform);
}

Check warning on line 88 in perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp#L88

Added line #L88 was not covered by tests
};

#endif // MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#define MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_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>

Expand All @@ -30,38 +31,15 @@ class PedestrianTracker : public Tracker
rclcpp::Logger logger_;

private:
KalmanFilter ekf_;
rclcpp::Time last_update_time_;
enum IDX {
X = 0,
Y = 1,
YAW = 2,
VX = 3,
WZ = 4,
};
struct EkfParams
{
char dim_x = 5;
float q_cov_x;
float q_cov_y;
float q_cov_yaw;
float q_cov_wz;
float q_cov_vx;
float p0_cov_vx;
float p0_cov_wz;
float r_cov_x;
float r_cov_y;
float r_cov_yaw;
float p0_cov_x;
float p0_cov_y;
float p0_cov_yaw;
double r_cov_x;
double r_cov_y;
double r_cov_yaw;
} ekf_params_;

double max_vx_;
double max_wz_;
float z_;
double z_;

private:
struct BoundingBox
{
double length;
Expand All @@ -76,16 +54,23 @@ class PedestrianTracker : public Tracker
BoundingBox bounding_box_;
Cylinder cylinder_;

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

public:
PedestrianTracker(
const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);

bool predict(const rclcpp::Time & time) override;
bool predict(const double dt, KalmanFilter & ekf) const;
bool measure(
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform) override;
autoware_auto_perception_msgs::msg::DetectedObject getUpdatingObject(
const autoware_auto_perception_msgs::msg::DetectedObject & object,
const geometry_msgs::msg::Transform & self_transform);
bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object);
bool getTrackedObject(
Expand Down
Loading
Loading