Skip to content

Commit

Permalink
feat(detection_by_tracker): add debug and modify existence_probability (
Browse files Browse the repository at this point in the history
#475)

* add debugger

Signed-off-by: Yukihiro Saito <[email protected]>

* change iou

Signed-off-by: Yukihiro Saito <[email protected]>
  • Loading branch information
yukkysaito authored Mar 10, 2022
1 parent 5dbea48 commit 84d3790
Show file tree
Hide file tree
Showing 3 changed files with 121 additions and 12 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
// Copyright 2021 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETECTION_BY_TRACKER__DEBUGGER_HPP_
#define DETECTION_BY_TRACKER__DEBUGGER_HPP_

#include <euclidean_cluster/euclidean_cluster.hpp>
#include <euclidean_cluster/utils.hpp>
#include <euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp>
#include <rclcpp/rclcpp.hpp>
#include <shape_estimation/shape_estimator.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>

#include <tf2/LinearMath/Transform.h>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <deque>
#include <memory>
#include <vector>

class Debugger
{
public:
explicit Debugger(rclcpp::Node * node)
{
initial_objects_pub_ =
node->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"debug/initial_objects", 1);
tracked_objects_pub_ =
node->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"debug/tracked_objects", 1);
merged_objects_pub_ =
node->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"debug/merged_objects", 1);
divided_objects_pub_ =
node->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"debug/divided_objects", 1);
}

~Debugger() {}
void publishInitialObjects(const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
{
initial_objects_pub_->publish(removeFeature(input));
}
void publishTrackedObjects(const autoware_auto_perception_msgs::msg::DetectedObjects & input)
{
tracked_objects_pub_->publish(input);
}
void publishMergedObjects(const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
{
merged_objects_pub_->publish(removeFeature(input));
}
void publishDividedObjects(const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
{
divided_objects_pub_->publish(removeFeature(input));
}

private:
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
initial_objects_pub_;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
tracked_objects_pub_;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
merged_objects_pub_;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
divided_objects_pub_;

autoware_auto_perception_msgs::msg::DetectedObjects removeFeature(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
{
autoware_auto_perception_msgs::msg::DetectedObjects objects;
objects.header = input.header;
for (const auto & feature_object : input.feature_objects) {
objects.objects.push_back(feature_object.object);
}
return objects;
}
};

#endif // DETECTION_BY_TRACKER__DEBUGGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef DETECTION_BY_TRACKER__DETECTION_BY_TRACKER_CORE_HPP_
#define DETECTION_BY_TRACKER__DETECTION_BY_TRACKER_CORE_HPP_

#include "detection_by_tracker/debugger.hpp"

#include <euclidean_cluster/euclidean_cluster.hpp>
#include <euclidean_cluster/utils.hpp>
#include <euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp>
Expand Down Expand Up @@ -69,6 +71,7 @@ class DetectionByTracker : public rclcpp::Node
TrackerHandler tracker_handler_;
std::shared_ptr<ShapeEstimator> shape_estimator_;
std::shared_ptr<euclidean_cluster::EuclideanClusterInterface> cluster_;
std::shared_ptr<Debugger> debugger_;

void onObjects(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg);
Expand Down
29 changes: 17 additions & 12 deletions perception/detection_by_tracker/src/detection_by_tracker_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,6 +215,7 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options)
shape_estimator_ = std::make_shared<ShapeEstimator>(true, true);
cluster_ = std::make_shared<euclidean_cluster::VoxelGridBasedEuclideanCluster>(
false, 10, 10000, 0.7, 0.3, 0);
debugger_ = std::make_shared<Debugger>(this);
}

void DetectionByTracker::onObjects(
Expand All @@ -224,34 +225,36 @@ void DetectionByTracker::onObjects(
detected_objects.header = input_msg->header;

// get objects from tracking module
autoware_auto_perception_msgs::msg::TrackedObjects tracked_objects;
autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects;
{
autoware_auto_perception_msgs::msg::TrackedObjects objects;
autoware_auto_perception_msgs::msg::TrackedObjects objects, transformed_objects;
const bool available_trackers =
tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects);
if (
!available_trackers ||
!transformTrackedObjects(objects, input_msg->header.frame_id, tf_buffer_, tracked_objects)) {
!transformTrackedObjects(
objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) {
objects_pub_->publish(detected_objects);
return;
}
// to simplify post processes, convert tracked_objects to DetectedObjects message.
tracked_objects = toDetectedObjects(transformed_objects);
}

// to simplify post processes, convert tracked_objects to DetectedObjects message.
autoware_auto_perception_msgs::msg::DetectedObjects tracked_objects_dt;
tracked_objects_dt = toDetectedObjects(tracked_objects);
debugger_->publishInitialObjects(*input_msg);
debugger_->publishTrackedObjects(tracked_objects);

// merge over segmented objects
tier4_perception_msgs::msg::DetectedObjectsWithFeature merged_objects;
autoware_auto_perception_msgs::msg::DetectedObjects no_found_tracked_objects;
mergeOverSegmentedObjects(
tracked_objects_dt, *input_msg, no_found_tracked_objects, merged_objects);
mergeOverSegmentedObjects(tracked_objects, *input_msg, no_found_tracked_objects, merged_objects);
debugger_->publishMergedObjects(merged_objects);

// divide under segmented objects
tier4_perception_msgs::msg::DetectedObjectsWithFeature divided_objects;
autoware_auto_perception_msgs::msg::DetectedObjects temp_no_found_tracked_objects;
divideUnderSegmentedObjects(
no_found_tracked_objects, *input_msg, temp_no_found_tracked_objects, divided_objects);
debugger_->publishDividedObjects(divided_objects);

// merge under/over segmented objects to build output objects
for (const auto & merged_object : merged_objects.feature_objects) {
Expand Down Expand Up @@ -387,8 +390,9 @@ float DetectionByTracker::optimizeUnderSegmentedObject(

// build output
highest_iou_object.object.classification = target_object.classification;
// TODO(yukkysaito): It is necessary to consider appropriate values in the future.
highest_iou_object.object.existence_probability = 0.1f;
highest_iou_object.object.existence_probability =
utils::get2dIoU(target_object, highest_iou_object.object);

output = highest_iou_object;
return highest_iou;
}
Expand Down Expand Up @@ -437,7 +441,6 @@ void DetectionByTracker::mergeOverSegmentedObjects(

// build output clusters
tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object;
feature_object.object.existence_probability = 0.1f;
feature_object.object.classification = tracked_object.classification;

bool is_shape_estimated = shape_estimator_->estimateShapeAndPose(
Expand All @@ -450,6 +453,8 @@ void DetectionByTracker::mergeOverSegmentedObjects(
continue;
}

feature_object.object.existence_probability =
utils::get2dIoU(tracked_object, feature_object.object);
setClusterInObjectWithFeature(in_cluster_objects.header, pcl_merged_cluster, feature_object);
out_objects.feature_objects.push_back(feature_object);
}
Expand Down

0 comments on commit 84d3790

Please sign in to comment.