Skip to content

Commit

Permalink
rename to perception_online_evaluator
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Feb 28, 2024
1 parent 5ec788f commit ae84790
Show file tree
Hide file tree
Showing 22 changed files with 78 additions and 78 deletions.

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(perception_evaluator)
project(perception_online_evaluator)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -17,7 +17,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED
)

rclcpp_components_register_node(${PROJECT_NAME}_node
PLUGIN "perception_diagnostics::PerceptionEvaluatorNode"
PLUGIN "perception_diagnostics::PerceptionOnlineEvaluatorNode"
EXECUTABLE ${PROJECT_NAME}
)

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
#define PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_

#include "perception_evaluator/stat.hpp"
#include "perception_online_evaluator/stat.hpp"

#include <autoware_auto_perception_msgs/msg/predicted_path.hpp>
#include <geometry_msgs/msg/pose.hpp>
Expand Down Expand Up @@ -50,4 +50,4 @@ std::vector<double> calcPredictedPathDeviation(
} // namespace metrics
} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
#define PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_

#include "perception_evaluator/stat.hpp"
#include "perception_online_evaluator/stat.hpp"

#include <iostream>
#include <string>
Expand Down Expand Up @@ -72,4 +72,4 @@ static struct CheckCorrectMaps
} // namespace details
} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
#define PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_

#include "perception_evaluator/metrics/deviation_metrics.hpp"
#include "perception_evaluator/metrics/metric.hpp"
#include "perception_evaluator/parameters.hpp"
#include "perception_evaluator/stat.hpp"
#include "perception_online_evaluator/metrics/deviation_metrics.hpp"
#include "perception_online_evaluator/metrics/metric.hpp"
#include "perception_online_evaluator/parameters.hpp"
#include "perception_online_evaluator/stat.hpp"

#include <rclcpp/time.hpp>

Expand Down Expand Up @@ -138,4 +138,4 @@ class MetricsCalculator

} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__PARAMETERS_HPP_
#define PERCEPTION_EVALUATOR__PARAMETERS_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_

#include "perception_evaluator/metrics/metric.hpp"
#include "perception_online_evaluator/metrics/metric.hpp"

#include <unordered_map>
#include <vector>
Expand Down Expand Up @@ -55,4 +55,4 @@ struct Parameters

} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__PARAMETERS_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
#define PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_

#include "perception_evaluator/metrics_calculator.hpp"
#include "perception_evaluator/parameters.hpp"
#include "perception_evaluator/stat.hpp"
#include "perception_online_evaluator/metrics_calculator.hpp"
#include "perception_online_evaluator/parameters.hpp"
#include "perception_online_evaluator/stat.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
Expand Down Expand Up @@ -46,11 +46,11 @@ using MarkerArray = visualization_msgs::msg::MarkerArray;
/**
* @brief Node for perception evaluation
*/
class PerceptionEvaluatorNode : public rclcpp::Node
class PerceptionOnlineEvaluatorNode : public rclcpp::Node
{
public:
explicit PerceptionEvaluatorNode(const rclcpp::NodeOptions & node_options);
~PerceptionEvaluatorNode();
explicit PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & node_options);
~PerceptionOnlineEvaluatorNode();

/**
* @brief callback on receiving a dynamic objects array
Expand Down Expand Up @@ -92,4 +92,4 @@ class PerceptionEvaluatorNode : public rclcpp::Node
};
} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#include <iostream>
#include <limits>

#ifndef PERCEPTION_EVALUATOR__STAT_HPP_
#define PERCEPTION_EVALUATOR__STAT_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_

namespace perception_diagnostics
{
Expand Down Expand Up @@ -90,4 +90,4 @@ std::ostream & operator<<(std::ostream & os, const Stat<T> & stat)

} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__STAT_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#define PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_

#include <vehicle_info_util/vehicle_info.hpp>

Expand Down Expand Up @@ -79,4 +79,4 @@ MarkerArray createDeviationLines(

} // namespace marker_utils

#endif // PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
#define PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_

#include "perception_evaluator/parameters.hpp"
#include "perception_online_evaluator/parameters.hpp"

#include <autoware_auto_perception_msgs/msg/object_classification.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_object.hpp>
Expand Down Expand Up @@ -125,4 +125,4 @@ void filterDeviationCheckObjects(

} // namespace perception_diagnostics

#endif // PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<arg name="input/twist" default="/localization/twist"/>

<node name="motion_evaluator" exec="motion_evaluator" pkg="perception_evaluator" output="screen">
<node name="motion_evaluator" exec="motion_evaluator" pkg="perception_online_evaluator" output="screen">
<remap from="~/input/twist" to="$(var input/twist)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>
<arg name="input/objects" default="/perception/object_recognition/objects"/>

<!-- perception evaluator -->
<group>
<node name="perception_online_evaluator" exec="perception_online_evaluator" pkg="perception_online_evaluator">
<param from="$(find-pkg-share perception_online_evaluator)/param/perception_online_evaluator.defaults.yaml"/>
<remap from="~/input/objects" to="$(var input/objects)"/>
<remap from="~/metrics" to="/diagnostic/perception_online_evaluator/metrics"/>
<remap from="~/markers" to="/diagnostic/perception_online_evaluator/markers"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>perception_evaluator</name>
<name>perception_online_evaluator</name>
<version>0.1.0</version>
<description>ROS 2 node for evaluating perception</description>
<maintainer email="[email protected]">Fumiya Watanabe</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "perception_evaluator/metrics/deviation_metrics.hpp"
#include "perception_online_evaluator/metrics/deviation_metrics.hpp"

#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/geometry/pose_deviation.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "perception_evaluator/metrics_calculator.hpp"
#include "perception_online_evaluator/metrics_calculator.hpp"

#include "motion_utils/trajectory/trajectory.hpp"
#include "perception_evaluator/utils/objects_filtering.hpp"
#include "perception_online_evaluator/utils/objects_filtering.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include <tier4_autoware_utils/ros/uuid_helper.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "perception_evaluator/perception_evaluator_node.hpp"
#include "perception_online_evaluator/perception_online_evaluator_node.hpp"

#include "perception_evaluator/utils/marker_utils.hpp"
#include "perception_online_evaluator/utils/marker_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/parameter.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
Expand All @@ -35,8 +35,8 @@

namespace perception_diagnostics
{
PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & node_options)
: Node("perception_evaluator", node_options),
PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & node_options)
: Node("perception_online_evaluator", node_options),
parameters_(std::make_shared<Parameters>()),
metrics_calculator_(parameters_)
{
Expand All @@ -46,7 +46,7 @@ PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & nod
google::InstallFailureSignalHandler();

objects_sub_ = create_subscription<PredictedObjects>(
"~/input/objects", 1, std::bind(&PerceptionEvaluatorNode::onObjects, this, _1));
"~/input/objects", 1, std::bind(&PerceptionOnlineEvaluatorNode::onObjects, this, _1));
metrics_pub_ = create_publisher<DiagnosticArray>("~/metrics", 1);
pub_marker_ = create_publisher<MarkerArray>("~/markers", 10);

Expand All @@ -57,25 +57,25 @@ PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & nod
initParameter();

set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&PerceptionEvaluatorNode::onParameter, this, std::placeholders::_1));
std::bind(&PerceptionOnlineEvaluatorNode::onParameter, this, std::placeholders::_1));

// Timer
initTimer(/*period_s=*/0.1);
}

PerceptionEvaluatorNode::~PerceptionEvaluatorNode()
PerceptionOnlineEvaluatorNode::~PerceptionOnlineEvaluatorNode()
{
}

void PerceptionEvaluatorNode::initTimer(double period_s)
void PerceptionOnlineEvaluatorNode::initTimer(double period_s)
{
const auto period_ns =
std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<double>(period_s));
timer_ = rclcpp::create_timer(
this, get_clock(), period_ns, std::bind(&PerceptionEvaluatorNode::onTimer, this));
this, get_clock(), period_ns, std::bind(&PerceptionOnlineEvaluatorNode::onTimer, this));
}

void PerceptionEvaluatorNode::onTimer()
void PerceptionOnlineEvaluatorNode::onTimer()
{
DiagnosticArray metrics_msg;
for (const Metric & metric : parameters_->metrics) {
Expand All @@ -98,7 +98,7 @@ void PerceptionEvaluatorNode::onTimer()
publishDebugMarker();
}

DiagnosticStatus PerceptionEvaluatorNode::generateDiagnosticStatus(
DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus(
const std::string metric, const Stat<double> & metric_stat) const
{
DiagnosticStatus status;
Expand All @@ -120,12 +120,12 @@ DiagnosticStatus PerceptionEvaluatorNode::generateDiagnosticStatus(
return status;
}

void PerceptionEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
{
metrics_calculator_.setPredictedObjects(*objects_msg);
}

void PerceptionEvaluatorNode::publishDebugMarker()
void PerceptionOnlineEvaluatorNode::publishDebugMarker()
{
using marker_utils::createColorFromString;
using marker_utils::createDeviationLines;
Expand Down Expand Up @@ -192,7 +192,7 @@ void PerceptionEvaluatorNode::publishDebugMarker()
pub_marker_->publish(marker);
}

rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode::onParameter(
rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParameter(
const std::vector<rclcpp::Parameter> & parameters)
{
using tier4_autoware_utils::updateParam;
Expand Down Expand Up @@ -280,7 +280,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode::onParameter(
return result;
}

void PerceptionEvaluatorNode::initParameter()
void PerceptionOnlineEvaluatorNode::initParameter()
{
using tier4_autoware_utils::getOrDeclareParameter;
using tier4_autoware_utils::updateParam;
Expand Down Expand Up @@ -344,4 +344,4 @@ void PerceptionEvaluatorNode::initParameter()
} // namespace perception_diagnostics

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(perception_diagnostics::PerceptionEvaluatorNode)
RCLCPP_COMPONENTS_REGISTER_NODE(perception_diagnostics::PerceptionOnlineEvaluatorNode)
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "perception_evaluator/utils/marker_utils.hpp"
#include "perception_online_evaluator/utils/marker_utils.hpp"

#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "perception_evaluator/utils/objects_filtering.hpp"
#include "perception_online_evaluator/utils/objects_filtering.hpp"

namespace perception_diagnostics
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,6 @@

<!-- perception evaluator -->
<group>
<include file="$(find-pkg-share perception_evaluator)/launch/perception_evaluator.launch.xml"/>
<include file="$(find-pkg-share perception_online_evaluator)/launch/perception_online_sevaluator.launch.xml"/>
</group>
</launch>
Loading

0 comments on commit ae84790

Please sign in to comment.