Skip to content

Commit e70dd88

Browse files
committed
rename to perception_online_evaluator
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 0133088 commit e70dd88

22 files changed

+78
-78
lines changed

evaluator/perception_evaluator/launch/perception_evaluator.launch.xml

-13
This file was deleted.

evaluator/perception_evaluator/CMakeLists.txt evaluator/perception_online_evaluator/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
cmake_minimum_required(VERSION 3.14)
2-
project(perception_evaluator)
2+
project(perception_online_evaluator)
33

44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
@@ -17,7 +17,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED
1717
)
1818

1919
rclcpp_components_register_node(${PROJECT_NAME}_node
20-
PLUGIN "perception_diagnostics::PerceptionEvaluatorNode"
20+
PLUGIN "perception_diagnostics::PerceptionOnlineEvaluatorNode"
2121
EXECUTABLE ${PROJECT_NAME}
2222
)
2323

evaluator/perception_evaluator/include/perception_evaluator/metrics/deviation_metrics.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
16-
#define PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
1717

18-
#include "perception_evaluator/stat.hpp"
18+
#include "perception_online_evaluator/stat.hpp"
1919

2020
#include <autoware_auto_perception_msgs/msg/predicted_path.hpp>
2121
#include <geometry_msgs/msg/pose.hpp>
@@ -50,4 +50,4 @@ std::vector<double> calcPredictedPathDeviation(
5050
} // namespace metrics
5151
} // namespace perception_diagnostics
5252

53-
#endif // PERCEPTION_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_
53+
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_

evaluator/perception_evaluator/include/perception_evaluator/metrics/metric.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
16-
#define PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_
1717

18-
#include "perception_evaluator/stat.hpp"
18+
#include "perception_online_evaluator/stat.hpp"
1919

2020
#include <iostream>
2121
#include <string>
@@ -72,4 +72,4 @@ static struct CheckCorrectMaps
7272
} // namespace details
7373
} // namespace perception_diagnostics
7474

75-
#endif // PERCEPTION_EVALUATOR__METRICS__METRIC_HPP_
75+
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_

evaluator/perception_evaluator/include/perception_evaluator/metrics_calculator.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
16-
#define PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_
1717

18-
#include "perception_evaluator/metrics/deviation_metrics.hpp"
19-
#include "perception_evaluator/metrics/metric.hpp"
20-
#include "perception_evaluator/parameters.hpp"
21-
#include "perception_evaluator/stat.hpp"
18+
#include "perception_online_evaluator/metrics/deviation_metrics.hpp"
19+
#include "perception_online_evaluator/metrics/metric.hpp"
20+
#include "perception_online_evaluator/parameters.hpp"
21+
#include "perception_online_evaluator/stat.hpp"
2222

2323
#include <rclcpp/time.hpp>
2424

@@ -138,4 +138,4 @@ class MetricsCalculator
138138

139139
} // namespace perception_diagnostics
140140

141-
#endif // PERCEPTION_EVALUATOR__METRICS_CALCULATOR_HPP_
141+
#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_

evaluator/perception_evaluator/include/perception_evaluator/parameters.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/parameters.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__PARAMETERS_HPP_
16-
#define PERCEPTION_EVALUATOR__PARAMETERS_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_
1717

18-
#include "perception_evaluator/metrics/metric.hpp"
18+
#include "perception_online_evaluator/metrics/metric.hpp"
1919

2020
#include <unordered_map>
2121
#include <vector>
@@ -55,4 +55,4 @@ struct Parameters
5555

5656
} // namespace perception_diagnostics
5757

58-
#endif // PERCEPTION_EVALUATOR__PARAMETERS_HPP_
58+
#endif // PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_

evaluator/perception_evaluator/include/perception_evaluator/perception_evaluator_node.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
16-
#define PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_
1717

18-
#include "perception_evaluator/metrics_calculator.hpp"
19-
#include "perception_evaluator/parameters.hpp"
20-
#include "perception_evaluator/stat.hpp"
18+
#include "perception_online_evaluator/metrics_calculator.hpp"
19+
#include "perception_online_evaluator/parameters.hpp"
20+
#include "perception_online_evaluator/stat.hpp"
2121
#include "rclcpp/rclcpp.hpp"
2222
#include "tf2_ros/buffer.h"
2323
#include "tf2_ros/transform_listener.h"
@@ -46,11 +46,11 @@ using MarkerArray = visualization_msgs::msg::MarkerArray;
4646
/**
4747
* @brief Node for perception evaluation
4848
*/
49-
class PerceptionEvaluatorNode : public rclcpp::Node
49+
class PerceptionOnlineEvaluatorNode : public rclcpp::Node
5050
{
5151
public:
52-
explicit PerceptionEvaluatorNode(const rclcpp::NodeOptions & node_options);
53-
~PerceptionEvaluatorNode();
52+
explicit PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & node_options);
53+
~PerceptionOnlineEvaluatorNode();
5454

5555
/**
5656
* @brief callback on receiving a dynamic objects array
@@ -92,4 +92,4 @@ class PerceptionEvaluatorNode : public rclcpp::Node
9292
};
9393
} // namespace perception_diagnostics
9494

95-
#endif // PERCEPTION_EVALUATOR__PERCEPTION_EVALUATOR_NODE_HPP_
95+
#endif // PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_

evaluator/perception_evaluator/include/perception_evaluator/stat.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/stat.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#include <iostream>
1616
#include <limits>
1717

18-
#ifndef PERCEPTION_EVALUATOR__STAT_HPP_
19-
#define PERCEPTION_EVALUATOR__STAT_HPP_
18+
#ifndef PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_
19+
#define PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_
2020

2121
namespace perception_diagnostics
2222
{
@@ -90,4 +90,4 @@ std::ostream & operator<<(std::ostream & os, const Stat<T> & stat)
9090

9191
} // namespace perception_diagnostics
9292

93-
#endif // PERCEPTION_EVALUATOR__STAT_HPP_
93+
#endif // PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_

evaluator/perception_evaluator/include/perception_evaluator/utils/marker_utils.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
16-
#define PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
1717

1818
#include <vehicle_info_util/vehicle_info.hpp>
1919

@@ -79,4 +79,4 @@ MarkerArray createDeviationLines(
7979

8080
} // namespace marker_utils
8181

82-
#endif // PERCEPTION_EVALUATOR__UTILS__MARKER_UTILS_HPP_
82+
#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_

evaluator/perception_evaluator/include/perception_evaluator/utils/objects_filtering.hpp evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/objects_filtering.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
16-
#define PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
15+
#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
16+
#define PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
1717

18-
#include "perception_evaluator/parameters.hpp"
18+
#include "perception_online_evaluator/parameters.hpp"
1919

2020
#include <autoware_auto_perception_msgs/msg/object_classification.hpp>
2121
#include <autoware_auto_perception_msgs/msg/predicted_object.hpp>
@@ -125,4 +125,4 @@ void filterDeviationCheckObjects(
125125

126126
} // namespace perception_diagnostics
127127

128-
#endif // PERCEPTION_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
128+
#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<launch>
22
<arg name="input/twist" default="/localization/twist"/>
33

4-
<node name="motion_evaluator" exec="motion_evaluator" pkg="perception_evaluator" output="screen">
4+
<node name="motion_evaluator" exec="motion_evaluator" pkg="perception_online_evaluator" output="screen">
55
<remap from="~/input/twist" to="$(var input/twist)"/>
66
</node>
77
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
<launch>
2+
<arg name="input/objects" default="/perception/object_recognition/objects"/>
3+
4+
<!-- perception evaluator -->
5+
<group>
6+
<node name="perception_online_evaluator" exec="perception_online_evaluator" pkg="perception_online_evaluator">
7+
<param from="$(find-pkg-share perception_online_evaluator)/param/perception_online_evaluator.defaults.yaml"/>
8+
<remap from="~/input/objects" to="$(var input/objects)"/>
9+
<remap from="~/metrics" to="/diagnostic/perception_online_evaluator/metrics"/>
10+
<remap from="~/markers" to="/diagnostic/perception_online_evaluator/markers"/>
11+
</node>
12+
</group>
13+
</launch>

evaluator/perception_evaluator/package.xml evaluator/perception_online_evaluator/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
4-
<name>perception_evaluator</name>
4+
<name>perception_online_evaluator</name>
55
<version>0.1.0</version>
66
<description>ROS 2 node for evaluating perception</description>
77
<maintainer email="fumiya.watanabe@tier4.jp">Fumiya Watanabe</maintainer>

evaluator/perception_evaluator/src/metrics/deviation_metrics.cpp evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "perception_evaluator/metrics/deviation_metrics.hpp"
15+
#include "perception_online_evaluator/metrics/deviation_metrics.hpp"
1616

1717
#include "tier4_autoware_utils/geometry/geometry.hpp"
1818
#include "tier4_autoware_utils/geometry/pose_deviation.hpp"

evaluator/perception_evaluator/src/metrics_calculator.cpp evaluator/perception_online_evaluator/src/metrics_calculator.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "perception_evaluator/metrics_calculator.hpp"
15+
#include "perception_online_evaluator/metrics_calculator.hpp"
1616

1717
#include "motion_utils/trajectory/trajectory.hpp"
18-
#include "perception_evaluator/utils/objects_filtering.hpp"
18+
#include "perception_online_evaluator/utils/objects_filtering.hpp"
1919
#include "tier4_autoware_utils/geometry/geometry.hpp"
2020

2121
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

evaluator/perception_evaluator/src/perception_evaluator_node.cpp evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp

+16-16
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "perception_evaluator/perception_evaluator_node.hpp"
15+
#include "perception_online_evaluator/perception_online_evaluator_node.hpp"
1616

17-
#include "perception_evaluator/utils/marker_utils.hpp"
17+
#include "perception_online_evaluator/utils/marker_utils.hpp"
1818
#include "tier4_autoware_utils/ros/marker_helper.hpp"
1919
#include "tier4_autoware_utils/ros/parameter.hpp"
2020
#include "tier4_autoware_utils/ros/update_param.hpp"
@@ -35,8 +35,8 @@
3535

3636
namespace perception_diagnostics
3737
{
38-
PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & node_options)
39-
: Node("perception_evaluator", node_options),
38+
PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & node_options)
39+
: Node("perception_online_evaluator", node_options),
4040
parameters_(std::make_shared<Parameters>()),
4141
metrics_calculator_(parameters_)
4242
{
@@ -46,7 +46,7 @@ PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & nod
4646
google::InstallFailureSignalHandler();
4747

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

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

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

6262
// Timer
6363
initTimer(/*period_s=*/0.1);
6464
}
6565

66-
PerceptionEvaluatorNode::~PerceptionEvaluatorNode()
66+
PerceptionOnlineEvaluatorNode::~PerceptionOnlineEvaluatorNode()
6767
{
6868
}
6969

70-
void PerceptionEvaluatorNode::initTimer(double period_s)
70+
void PerceptionOnlineEvaluatorNode::initTimer(double period_s)
7171
{
7272
const auto period_ns =
7373
std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<double>(period_s));
7474
timer_ = rclcpp::create_timer(
75-
this, get_clock(), period_ns, std::bind(&PerceptionEvaluatorNode::onTimer, this));
75+
this, get_clock(), period_ns, std::bind(&PerceptionOnlineEvaluatorNode::onTimer, this));
7676
}
7777

78-
void PerceptionEvaluatorNode::onTimer()
78+
void PerceptionOnlineEvaluatorNode::onTimer()
7979
{
8080
DiagnosticArray metrics_msg;
8181
for (const Metric & metric : parameters_->metrics) {
@@ -98,7 +98,7 @@ void PerceptionEvaluatorNode::onTimer()
9898
publishDebugMarker();
9999
}
100100

101-
DiagnosticStatus PerceptionEvaluatorNode::generateDiagnosticStatus(
101+
DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus(
102102
const std::string metric, const Stat<double> & metric_stat) const
103103
{
104104
DiagnosticStatus status;
@@ -120,12 +120,12 @@ DiagnosticStatus PerceptionEvaluatorNode::generateDiagnosticStatus(
120120
return status;
121121
}
122122

123-
void PerceptionEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
123+
void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
124124
{
125125
metrics_calculator_.setPredictedObjects(*objects_msg);
126126
}
127127

128-
void PerceptionEvaluatorNode::publishDebugMarker()
128+
void PerceptionOnlineEvaluatorNode::publishDebugMarker()
129129
{
130130
using marker_utils::createColorFromString;
131131
using marker_utils::createDeviationLines;
@@ -192,7 +192,7 @@ void PerceptionEvaluatorNode::publishDebugMarker()
192192
pub_marker_->publish(marker);
193193
}
194194

195-
rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode::onParameter(
195+
rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParameter(
196196
const std::vector<rclcpp::Parameter> & parameters)
197197
{
198198
using tier4_autoware_utils::updateParam;
@@ -280,7 +280,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode::onParameter(
280280
return result;
281281
}
282282

283-
void PerceptionEvaluatorNode::initParameter()
283+
void PerceptionOnlineEvaluatorNode::initParameter()
284284
{
285285
using tier4_autoware_utils::getOrDeclareParameter;
286286
using tier4_autoware_utils::updateParam;
@@ -344,4 +344,4 @@ void PerceptionEvaluatorNode::initParameter()
344344
} // namespace perception_diagnostics
345345

346346
#include "rclcpp_components/register_node_macro.hpp"
347-
RCLCPP_COMPONENTS_REGISTER_NODE(perception_diagnostics::PerceptionEvaluatorNode)
347+
RCLCPP_COMPONENTS_REGISTER_NODE(perception_diagnostics::PerceptionOnlineEvaluatorNode)

evaluator/perception_evaluator/src/utils/marker_utils.cpp evaluator/perception_online_evaluator/src/utils/marker_utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "perception_evaluator/utils/marker_utils.hpp"
15+
#include "perception_online_evaluator/utils/marker_utils.hpp"
1616

1717
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
1818
#include "tier4_autoware_utils/geometry/geometry.hpp"

evaluator/perception_evaluator/src/utils/objects_filtering.cpp evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "perception_evaluator/utils/objects_filtering.hpp"
15+
#include "perception_online_evaluator/utils/objects_filtering.hpp"
1616

1717
namespace perception_diagnostics
1818
{

launch/tier4_perception_launch/launch/perception.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -250,6 +250,6 @@
250250

251251
<!-- perception evaluator -->
252252
<group>
253-
<include file="$(find-pkg-share perception_evaluator)/launch/perception_evaluator.launch.xml"/>
253+
<include file="$(find-pkg-share perception_online_evaluator)/launch/perception_online_sevaluator.launch.xml"/>
254254
</group>
255255
</launch>

0 commit comments

Comments
 (0)