Skip to content

Commit

Permalink
CI crustify error fix
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Jul 20, 2023
1 parent d9257aa commit 029a5bf
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 9 deletions.
4 changes: 2 additions & 2 deletions perception/radar_object_tracker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<name>radar_object_tracker</name>
<version>0.0.0</version>
<description>Do tracking radar object</description>
<maintainer email="[email protected]">yoshiri</maintainer>
<maintainer email="[email protected]">Yoshi Ri</maintainer>
<maintainer email="[email protected]">Yukihiro Saito</maintainer>
<maintainer email="[email protected]">Satoshi Tanaka</maintainer>
<license>Apache License 2.0</license>
Expand All @@ -28,7 +28,7 @@
<depend>yaml-cpp</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
bool passed_gate = true;
// dist gate
if (passed_gate) {
if (max_dist < dist) passed_gate = false;
if (max_dist < dist) {
passed_gate = false;
}
pair_log_data["gate_name"] = "dist gate";
pair_log_data["gate_value"] = dist;
pair_log_data["gate_threshold"] = max_dist;
Expand All @@ -220,7 +222,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
const double max_area = max_area_matrix_(tracker_label, measurement_label);
const double min_area = min_area_matrix_(tracker_label, measurement_label);
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
if (area < min_area || max_area < area) passed_gate = false;
if (area < min_area || max_area < area) {
passed_gate = false;
}
pair_log_data["gate_name"] = "area gate";
pair_log_data["gate_value"] = area;
pair_log_data["gate_threshold"] = max_area;
Expand All @@ -231,8 +235,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
const double angle = getFormedYawAngle(
measurement_object.kinematics.pose_with_covariance.pose.orientation,
tracked_object.kinematics.pose_with_covariance.pose.orientation, false);
if (std::fabs(max_rad) < M_PI && std::fabs(max_rad) < std::fabs(angle))
if (std::fabs(max_rad) < M_PI && std::fabs(max_rad) < std::fabs(angle)) {
passed_gate = false;
}
pair_log_data["gate_name"] = "angle gate";
pair_log_data["gate_value"] = angle;
pair_log_data["gate_threshold"] = max_rad;
Expand All @@ -243,7 +248,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
measurement_object.kinematics.pose_with_covariance.pose.position,
tracked_object.kinematics.pose_with_covariance.pose.position,
getXYCovariance(tracked_object.kinematics.pose_with_covariance));
if (2.448 /*95%*/ <= mahalanobis_dist) passed_gate = false;
if (2.448 /*95%*/ <= mahalanobis_dist) {
passed_gate = false;
}
pair_log_data["gate_name"] = "mahalanobis dist gate";
pair_log_data["gate_value"] = mahalanobis_dist;
pair_log_data["gate_threshold"] = 2.448;
Expand All @@ -254,7 +261,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
const double min_union_iou_area = 1e-2;
const double iou = object_recognition_utils::get2dIoU(
measurement_object, tracked_object, min_union_iou_area);
if (iou < min_iou) passed_gate = false;
if (iou < min_iou) {
passed_gate = false;
}
pair_log_data["gate_name"] = "2d iou gate";
pair_log_data["gate_value"] = iou;
pair_log_data["gate_threshold"] = min_iou;
Expand All @@ -264,7 +273,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
if (passed_gate) {
pair_log_data["gate_name"] = "all gate passed";
score = (max_dist - std::min(dist, max_dist)) / max_dist;
if (score < score_threshold_) score = 0.0;
if (score < score_threshold_) {
score = 0.0;
}
}
pair_log_data["passed_gate"] = passed_gate;
pair_log_data["score"] = score;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,9 @@ void RadarObjectTrackerNode::onMeasurement(
}
std::shared_ptr<Tracker> tracker =
createNewTracker(transformed_objects.objects.at(i), measurement_time, *self_transform);
if (tracker) list_tracker_.push_back(tracker);
if (tracker) {
list_tracker_.push_back(tracker);
}
}

if (publish_timer_ == nullptr) {
Expand Down

0 comments on commit 029a5bf

Please sign in to comment.