@@ -33,12 +33,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
33
33
self_pose_listener_ (this ),
34
34
debug_publisher_(this , " goal_distance_calculator" )
35
35
{
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
-
42
36
// Node Parameter
43
37
node_param_.update_rate = declare_parameter<double >(" update_rate" );
44
38
node_param_.oneshot = declare_parameter<bool >(" oneshot" );
@@ -47,11 +41,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
47
41
goal_distance_calculator_ = std::make_unique<GoalDistanceCalculator>();
48
42
goal_distance_calculator_->setParam (param_);
49
43
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
-
55
44
// Wait for first self pose
56
45
self_pose_listener_.waitForFirstPose ();
57
46
@@ -62,53 +51,54 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
62
51
goal_distance_calculator_ = std::make_unique<GoalDistanceCalculator>();
63
52
}
64
53
65
- bool GoalDistanceCalculatorNode::isDataReady ()
54
+ bool GoalDistanceCalculatorNode::tryGetCurrentPose (
55
+ geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose)
66
56
{
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;
78
60
return true ;
79
61
}
80
62
81
- bool GoalDistanceCalculatorNode::isDataTimeout ()
63
+ bool GoalDistanceCalculatorNode::tryGetRoute (
64
+ autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route)
82
65
{
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 ;
90
70
}
91
71
92
72
void GoalDistanceCalculatorNode::onTimer ()
93
73
{
94
- current_pose_ = self_pose_listener_. getCurrentPose ();
74
+ Input input = Input ();
95
75
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..." );
97
79
return ;
98
80
}
99
81
100
- if (isDataTimeout ()) {
82
+ if (!tryGetRoute (input.route )) {
83
+ RCLCPP_INFO_THROTTLE (this ->get_logger (), *this ->get_clock (), 5000 , " waiting for route msg..." );
101
84
return ;
102
85
}
103
86
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
+ }
106
96
107
- output_ = goal_distance_calculator_->update (input_ );
97
+ Output output = goal_distance_calculator_->update (input );
108
98
109
99
{
110
100
using autoware::universe_utils::rad2deg;
111
- const auto & deviation = output_ .goal_deviation ;
101
+ const auto & deviation = output .goal_deviation ;
112
102
113
103
debug_publisher_.publish <tier4_debug_msgs::msg::Float64Stamped>(
114
104
" deviation/lateral" , deviation.lateral );
0 commit comments