Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(tier4_state_rviz_plugin): change to read topic by polling #7492

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions common/tier4_state_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>qtbase5-dev</depend>
<depend>rclcpp</depend>
<depend>rviz_common</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_control_msgs</depend>
<depend>tier4_external_api_msgs</depend>
<depend>tier4_planning_msgs</depend>
Expand All @@ -29,6 +30,6 @@

<export>
<build_type>ament_cmake</build_type>
<rviz plugin="${prefix}/plugins/plugin_description.xml"/>
<rviz plugin="${prefix}/plugins/plugin_description.xml" />
</export>
</package>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@
#include <rclcpp/rclcpp.hpp>
#include <rviz_common/panel.hpp>

// Autoware
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/steering_factor_array.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
Expand Down Expand Up @@ -59,11 +62,21 @@ class VelocitySteeringFactorsPanel : public rviz_common::Panel
QTableWidget * velocity_factors_table_{nullptr};
QTableWidget * steering_factors_table_{nullptr};

rclcpp::Subscription<VelocityFactorArray>::SharedPtr sub_velocity_factors_;
rclcpp::Subscription<SteeringFactorArray>::SharedPtr sub_steering_factors_;
tier4_autoware_utils::InterProcessPollingSubscriber<VelocityFactorArray>::SharedPtr
sub_velocity_factors_;
tier4_autoware_utils::InterProcessPollingSubscriber<SteeringFactorArray>::SharedPtr
sub_steering_factors_;
// rclcpp::Subscription<VelocityFactorArray>::SharedPtr sub_velocity_factors_;
// rclcpp::Subscription<SteeringFactorArray>::SharedPtr sub_steering_factors_;

void onTimer();
void onVelocityFactors(const VelocityFactorArray::ConstSharedPtr msg);
void onSteeringFactors(const SteeringFactorArray::ConstSharedPtr msg);

// timer
rclcpp::TimerBase::SharedPtr timer_;

static constexpr double check_rate = 20.0; // [Hz]
};
} // namespace rviz_plugins

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
//

Check warning on line 1 in common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Code Duplication

The module contains 2 functions with similar structure: VelocitySteeringFactorsPanel::makeSteeringFactorsGroup,VelocitySteeringFactorsPanel::makeVelocityFactorsGroup. Avoid duplicated, aka copy-pasted, code inside the module. More duplication lowers the code health.
// Copyright 2023 TIER IV, Inc. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
Expand Down Expand Up @@ -90,13 +90,37 @@
raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

// Planning
sub_velocity_factors_ = raw_node_->create_subscription<VelocityFactorArray>(
"/api/planning/velocity_factors", 10,
std::bind(&VelocitySteeringFactorsPanel::onVelocityFactors, this, _1));
sub_velocity_factors_ =
tier4_autoware_utils::InterProcessPollingSubscriber<VelocityFactorArray>::create_subscription(
raw_node_.get(), "/api/planning/velocity_factors", 10);

sub_steering_factors_ = raw_node_->create_subscription<SteeringFactorArray>(
"/api/planning/steering_factors", 10,
std::bind(&VelocitySteeringFactorsPanel::onSteeringFactors, this, _1));
sub_steering_factors_ =
tier4_autoware_utils::InterProcessPollingSubscriber<SteeringFactorArray>::create_subscription(
raw_node_.get(), "/api/planning/steering_factors", 10);

// timer
auto on_timer = std::bind(&VelocitySteeringFactorsPanel::onTimer, this);
auto period = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(1.0 / check_rate));
timer_ = std::make_shared<rclcpp::GenericTimer<decltype(on_timer)>>(
raw_node_->get_clock(), period, std::move(on_timer),
raw_node_->get_node_base_interface()->get_context());
raw_node_->get_node_timers_interface()->add_timer(timer_, nullptr);
}

void VelocitySteeringFactorsPanel::onTimer()
{
// VelocityFactors
{
auto steering_factors = sub_steering_factors_->takeNewData();
if (steering_factors) onSteeringFactors(steering_factors);
}

// SteeringFactors
{
auto velocity_factors = sub_velocity_factors_->takeNewData();
if (velocity_factors) onVelocityFactors(velocity_factors);
}
}

void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray::ConstSharedPtr msg)
Expand Down
Loading