Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Nov 9, 2023
1 parent fcb04ac commit b1e3c63
Showing 1 changed file with 75 additions and 82 deletions.
157 changes: 75 additions & 82 deletions planning/behavior_path_planner/test/test_objects_filtering.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,85 +60,78 @@ TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByVelocity)

TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByClass)
{
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_perception_msgs::msg::ObjectClassification;
using behavior_path_planner::utils::path_safety_checker::filterObjectsByClass;


PredictedObjects predicted_objects;
PredictedObject predicted_object[2];
PredictedObjects ans;
PredictedObjects part_ans[2];

ObjectClassification car_class[2];
car_class[0].label = ObjectClassification::CAR;
car_class[0].probability = 1.0;
car_class[1].label = ObjectClassification::TRUCK;
car_class[1].probability = 1.0;

ObjectTypesToCheck target_object_types;


//no objects case
filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, ans);


predicted_object[0].classification.push_back(car_class[0]);
part_ans[0].objects.push_back(predicted_object[0]);
predicted_objects.objects.push_back(predicted_object[0]);

predicted_object[1].classification.push_back(car_class[1]);
part_ans[1].objects.push_back(predicted_object[1]);
predicted_objects.objects.push_back(predicted_object[1]);


//no objects passes case
target_object_types.check_car = false;
target_object_types.check_truck = false;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, ans);

//all objects passes case
predicted_objects.objects.push_back(predicted_object[0]);
predicted_objects.objects.push_back(predicted_object[1]);

target_object_types.check_car = true;
target_object_types.check_truck = true;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
ans.objects.push_back(predicted_object[0]);
ans.objects.push_back(predicted_object[1]);

EXPECT_EQ(predicted_objects, ans);


//part of objects passes case
target_object_types.check_car = false;
target_object_types.check_truck = true;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, part_ans[1]);


}
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using behavior_path_planner::utils::path_safety_checker::filterObjectsByClass;

PredictedObjects predicted_objects;
PredictedObject predicted_object[2];
PredictedObjects ans;
PredictedObjects part_ans[2];

ObjectClassification car_class[2];
car_class[0].label = ObjectClassification::CAR;
car_class[0].probability = 1.0;
car_class[1].label = ObjectClassification::TRUCK;
car_class[1].probability = 1.0;

ObjectTypesToCheck target_object_types;

// no objects case
filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, ans);

predicted_object[0].classification.push_back(car_class[0]);
part_ans[0].objects.push_back(predicted_object[0]);
predicted_objects.objects.push_back(predicted_object[0]);

predicted_object[1].classification.push_back(car_class[1]);
part_ans[1].objects.push_back(predicted_object[1]);
predicted_objects.objects.push_back(predicted_object[1]);

// no objects passes case
target_object_types.check_car = false;
target_object_types.check_truck = false;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, ans);

// all objects passes case
predicted_objects.objects.push_back(predicted_object[0]);
predicted_objects.objects.push_back(predicted_object[1]);

target_object_types.check_car = true;
target_object_types.check_truck = true;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
ans.objects.push_back(predicted_object[0]);
ans.objects.push_back(predicted_object[1]);

EXPECT_EQ(predicted_objects, ans);

// part of objects passes case
target_object_types.check_car = false;
target_object_types.check_truck = true;
target_object_types.check_bus = false;
target_object_types.check_trailer = false;
target_object_types.check_bicycle = false;
target_object_types.check_unknown = false;
target_object_types.check_motorcycle = false;
target_object_types.check_pedestrian = false;

filterObjectsByClass(predicted_objects, target_object_types);
EXPECT_EQ(predicted_objects, part_ans[1]);
}

0 comments on commit b1e3c63

Please sign in to comment.