Skip to content

Commit

Permalink
Merge pull request #8 from tier4/feature/speedup
Browse files Browse the repository at this point in the history
Feature/speedup
  • Loading branch information
OsamuSekino authored Mar 8, 2023
2 parents daead0a + 7f283c9 commit 14fa136
Showing 1 changed file with 5 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,9 @@ void MapAreaFilterComponent::objects_callback(const PredictedObjects::ConstShare
{
std::scoped_lock lock(mutex_);
objects_ptr_ = msg;

PredictedObjects out_objects;
if (filter_objects_by_area(out_objects)) filtered_objects_pub_->publish(out_objects);
}

bool MapAreaFilterComponent::load_areas_from_csv(const std::string & file_name)
Expand Down Expand Up @@ -277,16 +280,11 @@ void MapAreaFilterComponent::filter_points_by_area(

bool MapAreaFilterComponent::filter_objects_by_area(PredictedObjects & out_objects)
{
if (!objects_ptr_) {
if (!objects_ptr_.has_value() || objects_ptr_.get() == nullptr) {
return false;
}

if (objects_ptr_.get() == nullptr) {
return false;
}

PredictedObjects in_objects;
in_objects = *objects_ptr_.get();
const PredictedObjects in_objects = *objects_ptr_.get();
out_objects.header = in_objects.header;

for (const auto & object : in_objects.objects) {
Expand Down Expand Up @@ -374,9 +372,6 @@ void MapAreaFilterComponent::filter(
return;
}
output.header = input->header;

PredictedObjects out_objects;
if (filter_objects_by_area(out_objects)) filtered_objects_pub_->publish(out_objects);
}

rcl_interfaces::msg::SetParametersResult MapAreaFilterComponent::paramCallback(
Expand Down

0 comments on commit 14fa136

Please sign in to comment.