|
| 1 | +// Copyright 2024 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +// |
| 15 | +// |
| 16 | + |
| 17 | +#include "multi_object_tracker/debugger.hpp" |
| 18 | + |
| 19 | +#include <memory> |
| 20 | + |
| 21 | +TrackerDebugger::TrackerDebugger(rclcpp::Node & node) |
| 22 | +: diagnostic_updater_(&node), |
| 23 | + node_(node), |
| 24 | + last_input_stamp_(node.now()), |
| 25 | + stamp_process_start_(node.now()), |
| 26 | + stamp_publish_output_(node.now()) |
| 27 | +{ |
| 28 | + // declare debug parameters to decide whether to publish debug topics |
| 29 | + loadParameters(); |
| 30 | + // initialize debug publishers |
| 31 | + if (debug_settings_.publish_processing_time) { |
| 32 | + processing_time_publisher_ = |
| 33 | + std::make_unique<tier4_autoware_utils::DebugPublisher>(&node_, "multi_object_tracker"); |
| 34 | + } |
| 35 | + |
| 36 | + if (debug_settings_.publish_tentative_objects) { |
| 37 | + debug_tentative_objects_pub_ = |
| 38 | + node_.create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>( |
| 39 | + "debug/tentative_objects", rclcpp::QoS{1}); |
| 40 | + } |
| 41 | + |
| 42 | + // initialize stop watch and diagnostics |
| 43 | + setupDiagnostics(); |
| 44 | +} |
| 45 | + |
| 46 | +void TrackerDebugger::setupDiagnostics() |
| 47 | +{ |
| 48 | + diagnostic_updater_.setHardwareID(node_.get_name()); |
| 49 | + diagnostic_updater_.add( |
| 50 | + "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); |
| 51 | + diagnostic_updater_.setPeriod(0.1); |
| 52 | +} |
| 53 | + |
| 54 | +void TrackerDebugger::loadParameters() |
| 55 | +{ |
| 56 | + try { |
| 57 | + debug_settings_.publish_processing_time = |
| 58 | + node_.declare_parameter<bool>("publish_processing_time"); |
| 59 | + debug_settings_.publish_tentative_objects = |
| 60 | + node_.declare_parameter<bool>("publish_tentative_objects"); |
| 61 | + debug_settings_.diagnostics_warn_delay = |
| 62 | + node_.declare_parameter<double>("diagnostics_warn_delay"); |
| 63 | + debug_settings_.diagnostics_error_delay = |
| 64 | + node_.declare_parameter<double>("diagnostics_error_delay"); |
| 65 | + } catch (const std::exception & e) { |
| 66 | + RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); |
| 67 | + debug_settings_.publish_processing_time = false; |
| 68 | + debug_settings_.publish_tentative_objects = false; |
| 69 | + debug_settings_.diagnostics_warn_delay = 0.5; |
| 70 | + debug_settings_.diagnostics_error_delay = 1.0; |
| 71 | + } |
| 72 | +} |
| 73 | + |
| 74 | +void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) |
| 75 | +{ |
| 76 | + const double delay = pipeline_latency_ms_; // [s] |
| 77 | + |
| 78 | + if (delay == 0.0) { |
| 79 | + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); |
| 80 | + } else if (delay < debug_settings_.diagnostics_warn_delay) { |
| 81 | + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable"); |
| 82 | + } else if (delay < debug_settings_.diagnostics_error_delay) { |
| 83 | + stat.summary( |
| 84 | + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold."); |
| 85 | + } else { |
| 86 | + stat.summary( |
| 87 | + diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold."); |
| 88 | + } |
| 89 | + |
| 90 | + stat.add("Detection delay", delay); |
| 91 | +} |
| 92 | + |
| 93 | +void TrackerDebugger::publishTentativeObjects( |
| 94 | + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const |
| 95 | +{ |
| 96 | + if (debug_settings_.publish_tentative_objects) { |
| 97 | + debug_tentative_objects_pub_->publish(tentative_objects); |
| 98 | + } |
| 99 | +} |
| 100 | + |
| 101 | +void TrackerDebugger::startMeasurementTime( |
| 102 | + const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp) |
| 103 | +{ |
| 104 | + last_input_stamp_ = measurement_header_stamp; |
| 105 | + stamp_process_start_ = now; |
| 106 | + if (debug_settings_.publish_processing_time) { |
| 107 | + double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3; |
| 108 | + processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 109 | + "debug/input_latency_ms", input_latency_ms); |
| 110 | + } |
| 111 | +} |
| 112 | + |
| 113 | +void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) |
| 114 | +{ |
| 115 | + const auto current_time = now; |
| 116 | + // pipeline latency: time from sensor measurement to publish |
| 117 | + pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; |
| 118 | + if (debug_settings_.publish_processing_time) { |
| 119 | + // processing time: time between input and publish |
| 120 | + double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3; |
| 121 | + // cycle time: time between two consecutive publish |
| 122 | + double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; |
| 123 | + // measurement to tracked-object time: time from the sensor measurement to the publishing object |
| 124 | + // time If there is not latency compensation, this value is zero |
| 125 | + double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; |
| 126 | + |
| 127 | + // starting from the measurement time |
| 128 | + processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 129 | + "debug/pipeline_latency_ms", pipeline_latency_ms_); |
| 130 | + processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 131 | + "debug/cyclic_time_ms", cyclic_time_ms); |
| 132 | + processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 133 | + "debug/processing_time_ms", processing_time_ms); |
| 134 | + processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 135 | + "debug/meas_to_tracked_object_ms", measurement_to_object_ms); |
| 136 | + } |
| 137 | + stamp_publish_output_ = current_time; |
| 138 | +} |
0 commit comments