12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #include " perception_evaluator/perception_evaluator_node .hpp"
15
+ #include " perception_online_evaluator/perception_online_evaluator_node .hpp"
16
16
17
- #include " perception_evaluator /utils/marker_utils.hpp"
17
+ #include " perception_online_evaluator /utils/marker_utils.hpp"
18
18
#include " tier4_autoware_utils/ros/marker_helper.hpp"
19
19
#include " tier4_autoware_utils/ros/parameter.hpp"
20
20
#include " tier4_autoware_utils/ros/update_param.hpp"
35
35
36
36
namespace perception_diagnostics
37
37
{
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),
40
40
parameters_ (std::make_shared<Parameters>()),
41
41
metrics_calculator_(parameters_)
42
42
{
@@ -46,7 +46,7 @@ PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & nod
46
46
google::InstallFailureSignalHandler ();
47
47
48
48
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));
50
50
metrics_pub_ = create_publisher<DiagnosticArray>(" ~/metrics" , 1 );
51
51
pub_marker_ = create_publisher<MarkerArray>(" ~/markers" , 10 );
52
52
@@ -57,25 +57,25 @@ PerceptionEvaluatorNode::PerceptionEvaluatorNode(const rclcpp::NodeOptions & nod
57
57
initParameter ();
58
58
59
59
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));
61
61
62
62
// Timer
63
63
initTimer (/* period_s=*/ 0.1 );
64
64
}
65
65
66
- PerceptionEvaluatorNode ::~PerceptionEvaluatorNode ()
66
+ PerceptionOnlineEvaluatorNode ::~PerceptionOnlineEvaluatorNode ()
67
67
{
68
68
}
69
69
70
- void PerceptionEvaluatorNode ::initTimer (double period_s)
70
+ void PerceptionOnlineEvaluatorNode ::initTimer (double period_s)
71
71
{
72
72
const auto period_ns =
73
73
std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<double >(period_s));
74
74
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 ));
76
76
}
77
77
78
- void PerceptionEvaluatorNode ::onTimer ()
78
+ void PerceptionOnlineEvaluatorNode ::onTimer ()
79
79
{
80
80
DiagnosticArray metrics_msg;
81
81
for (const Metric & metric : parameters_->metrics ) {
@@ -98,7 +98,7 @@ void PerceptionEvaluatorNode::onTimer()
98
98
publishDebugMarker ();
99
99
}
100
100
101
- DiagnosticStatus PerceptionEvaluatorNode ::generateDiagnosticStatus (
101
+ DiagnosticStatus PerceptionOnlineEvaluatorNode ::generateDiagnosticStatus (
102
102
const std::string metric, const Stat<double > & metric_stat) const
103
103
{
104
104
DiagnosticStatus status;
@@ -120,12 +120,12 @@ DiagnosticStatus PerceptionEvaluatorNode::generateDiagnosticStatus(
120
120
return status;
121
121
}
122
122
123
- void PerceptionEvaluatorNode ::onObjects (const PredictedObjects::ConstSharedPtr objects_msg)
123
+ void PerceptionOnlineEvaluatorNode ::onObjects (const PredictedObjects::ConstSharedPtr objects_msg)
124
124
{
125
125
metrics_calculator_.setPredictedObjects (*objects_msg);
126
126
}
127
127
128
- void PerceptionEvaluatorNode ::publishDebugMarker ()
128
+ void PerceptionOnlineEvaluatorNode ::publishDebugMarker ()
129
129
{
130
130
using marker_utils::createColorFromString;
131
131
using marker_utils::createDeviationLines;
@@ -192,7 +192,7 @@ void PerceptionEvaluatorNode::publishDebugMarker()
192
192
pub_marker_->publish (marker);
193
193
}
194
194
195
- rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode ::onParameter (
195
+ rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode ::onParameter (
196
196
const std::vector<rclcpp::Parameter> & parameters)
197
197
{
198
198
using tier4_autoware_utils::updateParam;
@@ -280,7 +280,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionEvaluatorNode::onParameter(
280
280
return result;
281
281
}
282
282
283
- void PerceptionEvaluatorNode ::initParameter ()
283
+ void PerceptionOnlineEvaluatorNode ::initParameter ()
284
284
{
285
285
using tier4_autoware_utils::getOrDeclareParameter;
286
286
using tier4_autoware_utils::updateParam;
@@ -344,4 +344,4 @@ void PerceptionEvaluatorNode::initParameter()
344
344
} // namespace perception_diagnostics
345
345
346
346
#include " rclcpp_components/register_node_macro.hpp"
347
- RCLCPP_COMPONENTS_REGISTER_NODE (perception_diagnostics::PerceptionEvaluatorNode )
347
+ RCLCPP_COMPONENTS_REGISTER_NODE (perception_diagnostics::PerceptionOnlineEvaluatorNode )
0 commit comments