Skip to content

Commit

Permalink
chore: refactoring
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Jun 11, 2024
1 parent 1e05e5d commit d0c5f0e
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ void MultiObjectTracker::onTrigger()
{
const rclcpp::Time current_time = this->now();
// get objects from the input manager and run process
std::vector<std::pair<uint, DetectedObjects>> objects_list;
ObjectsList objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
if (!is_objects_ready) return;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ autoware_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatingObje

// OBJECT SHAPE MODEL
// convert to bounding box if input is convex shape
autoware_perception_msgs::msg::DetectedObject bbox_object;
autoware_perception_msgs::msg::DetectedObject bbox_object = object;
if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) {
if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) {
RCLCPP_WARN(
Expand All @@ -216,8 +216,8 @@ autoware_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatingObje
// UNCERTAINTY MODEL
if (!object.kinematics.has_position_covariance) {
// measurement noise covariance
float r_cov_x = static_cast<float>(ekf_params_.r_cov_x);
float r_cov_y = static_cast<float>(ekf_params_.r_cov_y);
auto r_cov_x = static_cast<float>(ekf_params_.r_cov_x);
auto r_cov_y = static_cast<float>(ekf_params_.r_cov_y);
const uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification);
if (label == autoware_perception_msgs::msg::ObjectClassification::CAR) {
// if label is changed, enlarge the measurement noise covariance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -217,8 +217,8 @@ autoware_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpdatingO
// UNCERTAINTY MODEL
if (!object.kinematics.has_position_covariance) {
// measurement noise covariance
float r_cov_x = static_cast<float>(ekf_params_.r_cov_x);
float r_cov_y = static_cast<float>(ekf_params_.r_cov_y);
auto r_cov_x = static_cast<float>(ekf_params_.r_cov_x);
auto r_cov_y = static_cast<float>(ekf_params_.r_cov_y);
const uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification);
if (utils::isLargeVehicleLabel(label)) {
// if label is changed, enlarge the measurement noise covariance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@
// CTRV : Constant Turn Rate and constant Velocity
using tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;

BicycleMotionModel::BicycleMotionModel()
: MotionModel(), logger_(rclcpp::get_logger("BicycleMotionModel"))
BicycleMotionModel::BicycleMotionModel() : logger_(rclcpp::get_logger("BicycleMotionModel"))
{
// Initialize motion parameters
setDefaultParams();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
// Constant Turn Rate and constant Velocity (CTRV) motion model
using tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;

CTRVMotionModel::CTRVMotionModel() : MotionModel(), logger_(rclcpp::get_logger("CTRVMotionModel"))
CTRVMotionModel::CTRVMotionModel() : logger_(rclcpp::get_logger("CTRVMotionModel"))
{
// Initialize motion parameters
setDefaultParams();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
// Constant Velocity (CV) motion model
using tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;

CVMotionModel::CVMotionModel() : MotionModel(), logger_(rclcpp::get_logger("CVMotionModel"))
CVMotionModel::CVMotionModel() : logger_(rclcpp::get_logger("CVMotionModel"))
{
// Initialize motion parameters
setDefaultParams();
Expand Down

0 comments on commit d0c5f0e

Please sign in to comment.