Skip to content

Commit

Permalink
refactor: remove timer
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 ae84790 commit df0b9ef
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node
{
public:
explicit PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & node_options);
~PerceptionOnlineEvaluatorNode();
~PerceptionOnlineEvaluatorNode() {};

/**
* @brief callback on receiving a dynamic objects array
Expand All @@ -62,11 +62,6 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node
const std::string metric, const Stat<double> & metric_stat) const;

private:
// Timer
rclcpp::TimerBase::SharedPtr timer_;
void initTimer(double period_s);
void onTimer();

// Subscribers and publishers
rclcpp::Subscription<PredictedObjects>::SharedPtr objects_sub_;
rclcpp::Publisher<DiagnosticArray>::SharedPtr metrics_pub_;
Expand All @@ -86,6 +81,7 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node
// Metrics Calculator
MetricsCalculator metrics_calculator_;
std::deque<rclcpp::Time> stamps_;
void publishMetrics();

// Debug
void publishDebugMarker();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@

namespace perception_diagnostics
{
PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(const rclcpp::NodeOptions & 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 @@ -58,26 +59,13 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(const rclcpp::NodeO

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

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

PerceptionOnlineEvaluatorNode::~PerceptionOnlineEvaluatorNode()
{
}

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(&PerceptionOnlineEvaluatorNode::onTimer, this));
}

void PerceptionOnlineEvaluatorNode::onTimer()
void PerceptionOnlineEvaluatorNode::publishMetrics()
{
DiagnosticArray metrics_msg;

// calculate metrics
for (const Metric & metric : parameters_->metrics) {
const auto metric_stat_map = metrics_calculator_.calculate(Metric(metric));
if (!metric_stat_map.has_value()) {
Expand All @@ -91,6 +79,7 @@ void PerceptionOnlineEvaluatorNode::onTimer()
}
}

// publish metrics
if (!metrics_msg.status.empty()) {
metrics_msg.header.stamp = now();
metrics_pub_->publish(metrics_msg);
Expand Down Expand Up @@ -123,6 +112,7 @@ DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus(
void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
{
metrics_calculator_.setPredictedObjects(*objects_msg);
publishMetrics();
}

void PerceptionOnlineEvaluatorNode::publishDebugMarker()
Expand Down

0 comments on commit df0b9ef

Please sign in to comment.