Skip to content

Commit d2d45f2

Browse files
Autumn60shmpwk
andauthored
refactor(goal_distance_calculator): narrow variable scopes and change to read topic by polling (#7434)
* delete unnecessary member Signed-off-by: Autumn60 <akiro.harada@tier4.jp> * replace rclcpp::Subscription to autoware_utils::InterProcessPollingSubscriber Signed-off-by: Autumn60 <akiro.harada@tier4.jp> * format by clang-format Signed-off-by: Autumn60 <akiro.harada@tier4.jp> * delete unnecessary callback func Signed-off-by: Autumn60 <akiro.harada@tier4.jp> * refactor goal_distance_calculator_node Signed-off-by: Autumn60 <akiro.harada@tier4.jp> * clang format Signed-off-by: Autumn60 <akiro.harada@tier4.jp> --------- Signed-off-by: Autumn60 <akiro.harada@tier4.jp> Co-authored-by: Autumn60 <akiro.harada@tier4.jp> Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com>
1 parent 5a539f4 commit d2d45f2

File tree

2 files changed

+33
-51
lines changed

2 files changed

+33
-51
lines changed

common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp

+5-13
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "goal_distance_calculator/goal_distance_calculator.hpp"
1919

2020
#include <autoware/universe_utils/ros/debug_publisher.hpp>
21+
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
2122
#include <autoware/universe_utils/ros/self_pose_listener.hpp>
2223
#include <rclcpp/rclcpp.hpp>
2324

@@ -44,34 +45,25 @@ class GoalDistanceCalculatorNode : public rclcpp::Node
4445

4546
private:
4647
// Subscriber
47-
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr sub_initial_pose_;
4848
autoware::universe_utils::SelfPoseListener self_pose_listener_;
49-
rclcpp::Subscription<autoware_planning_msgs::msg::LaneletRoute>::SharedPtr sub_route_;
50-
51-
// Data Buffer
52-
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
53-
autoware_planning_msgs::msg::LaneletRoute::SharedPtr route_;
54-
55-
// Callback
56-
void onRoute(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr & msg);
49+
autoware::universe_utils::InterProcessPollingSubscriber<autoware_planning_msgs::msg::LaneletRoute>
50+
sub_route_{this, "/planning/mission_planning/route"};
5751

5852
// Publisher
5953
autoware::universe_utils::DebugPublisher debug_publisher_;
6054

6155
// Timer
6256
rclcpp::TimerBase::SharedPtr timer_;
6357

64-
bool isDataReady();
65-
bool isDataTimeout();
58+
bool tryGetCurrentPose(geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose);
59+
bool tryGetRoute(autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route);
6660
void onTimer();
6761

6862
// Parameter
6963
NodeParam node_param_;
7064
Param param_;
7165

7266
// Core
73-
Input input_;
74-
Output output_;
7567
std::unique_ptr<GoalDistanceCalculator> goal_distance_calculator_;
7668
};
7769
} // namespace goal_distance_calculator

common/goal_distance_calculator/src/goal_distance_calculator_node.cpp

+28-38
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
3333
self_pose_listener_(this),
3434
debug_publisher_(this, "goal_distance_calculator")
3535
{
36-
using std::placeholders::_1;
37-
38-
static constexpr std::size_t queue_size = 1;
39-
rclcpp::QoS durable_qos(queue_size);
40-
durable_qos.transient_local();
41-
4236
// Node Parameter
4337
node_param_.update_rate = declare_parameter<double>("update_rate");
4438
node_param_.oneshot = declare_parameter<bool>("oneshot");
@@ -47,11 +41,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
4741
goal_distance_calculator_ = std::make_unique<GoalDistanceCalculator>();
4842
goal_distance_calculator_->setParam(param_);
4943

50-
// Subscriber
51-
sub_route_ = create_subscription<autoware_planning_msgs::msg::LaneletRoute>(
52-
"/planning/mission_planning/route", queue_size,
53-
[&](const autoware_planning_msgs::msg::LaneletRoute::SharedPtr msg_ptr) { route_ = msg_ptr; });
54-
5544
// Wait for first self pose
5645
self_pose_listener_.waitForFirstPose();
5746

@@ -62,53 +51,54 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
6251
goal_distance_calculator_ = std::make_unique<GoalDistanceCalculator>();
6352
}
6453

65-
bool GoalDistanceCalculatorNode::isDataReady()
54+
bool GoalDistanceCalculatorNode::tryGetCurrentPose(
55+
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose)
6656
{
67-
if (!current_pose_) {
68-
RCLCPP_INFO_THROTTLE(
69-
this->get_logger(), *this->get_clock(), 5000, "waiting for current_pose...");
70-
return false;
71-
}
72-
73-
if (!route_) {
74-
RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "waiting for route msg...");
75-
return false;
76-
}
77-
57+
auto current_pose_tmp = self_pose_listener_.getCurrentPose();
58+
if (!current_pose_tmp) return false;
59+
current_pose = current_pose_tmp;
7860
return true;
7961
}
8062

81-
bool GoalDistanceCalculatorNode::isDataTimeout()
63+
bool GoalDistanceCalculatorNode::tryGetRoute(
64+
autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route)
8265
{
83-
constexpr double th_pose_timeout = 1.0;
84-
const auto pose_time_diff = rclcpp::Time(current_pose_->header.stamp) - now();
85-
if (pose_time_diff.seconds() > th_pose_timeout) {
86-
RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "pose is timeout...");
87-
return true;
88-
}
89-
return false;
66+
auto route_tmp = sub_route_.takeData();
67+
if (!route_tmp) return false;
68+
route = route_tmp;
69+
return true;
9070
}
9171

9272
void GoalDistanceCalculatorNode::onTimer()
9373
{
94-
current_pose_ = self_pose_listener_.getCurrentPose();
74+
Input input = Input();
9575

96-
if (!isDataReady()) {
76+
if (!tryGetCurrentPose(input.current_pose)) {
77+
RCLCPP_INFO_THROTTLE(
78+
this->get_logger(), *this->get_clock(), 5000, "waiting for current_pose...");
9779
return;
9880
}
9981

100-
if (isDataTimeout()) {
82+
if (!tryGetRoute(input.route)) {
83+
RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "waiting for route msg...");
10184
return;
10285
}
10386

104-
input_.current_pose = current_pose_;
105-
input_.route = route_;
87+
// Check pose timeout
88+
{
89+
constexpr double th_pose_timeout = 1.0;
90+
const auto pose_time_diff = rclcpp::Time(input.current_pose->header.stamp) - now();
91+
if (pose_time_diff.seconds() > th_pose_timeout) {
92+
RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "pose is timeout...");
93+
return;
94+
}
95+
}
10696

107-
output_ = goal_distance_calculator_->update(input_);
97+
Output output = goal_distance_calculator_->update(input);
10898

10999
{
110100
using autoware::universe_utils::rad2deg;
111-
const auto & deviation = output_.goal_deviation;
101+
const auto & deviation = output.goal_deviation;
112102

113103
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
114104
"deviation/lateral", deviation.lateral);

0 commit comments

Comments
 (0)