@@ -37,7 +37,9 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode(
37
37
: Node(" remaining_distance_time_calculator" , options),
38
38
is_graph_ready_{false },
39
39
has_received_route_{false },
40
- velocity_limit_{99.99 }
40
+ velocity_limit_{99.99 },
41
+ remaining_distance_{0.0 },
42
+ remaining_time_{0.0 }
41
43
{
42
44
using std::placeholders::_1;
43
45
@@ -101,46 +103,47 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit(
101
103
void RemainingDistanceTimeCalculatorNode::on_timer ()
102
104
{
103
105
if (is_graph_ready_ && has_received_route_) {
104
- double remaining_distance = calculate_remaining_distance ();
105
- double remaining_time = calculate_remaining_time (remaining_distance );
106
- publish_mission_remaining_distance_time (remaining_distance, remaining_time );
106
+ calculate_remaining_distance ();
107
+ calculate_remaining_time ();
108
+ publish_mission_remaining_distance_time ();
107
109
}
108
110
}
109
111
110
- double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance () const
112
+ void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance ()
111
113
{
112
- double remaining_distance = 0.0 ;
113
114
size_t index = 0 ;
114
115
115
116
lanelet::ConstLanelet current_lanelet;
116
117
if (!lanelet::utils::query::getClosestLanelet (
117
118
road_lanelets_, current_vehicle_pose_, ¤t_lanelet)) {
118
119
RCLCPP_WARN_STREAM (this ->get_logger (), " Failed to find current lanelet." );
119
120
120
- return 0.0 ;
121
+ return ;
121
122
}
122
123
123
124
lanelet::ConstLanelet goal_lanelet;
124
125
if (!lanelet::utils::query::getClosestLanelet (road_lanelets_, goal_pose_, &goal_lanelet)) {
125
126
RCLCPP_WARN_STREAM (this ->get_logger (), " Failed to find goal lanelet." );
126
127
127
- return 0.0 ;
128
+ return ;
128
129
}
129
130
130
131
const lanelet::Optional<lanelet::routing::Route> optional_route =
131
132
routing_graph_ptr_->getRoute (current_lanelet, goal_lanelet, 0 );
132
133
if (!optional_route) {
133
134
RCLCPP_WARN_STREAM (this ->get_logger (), " Failed to find proper route." );
134
135
135
- return 0.0 ;
136
+ return ;
136
137
}
137
138
138
139
lanelet::routing::LaneletPath remaining_shortest_path;
139
140
remaining_shortest_path = optional_route->shortestPath ();
140
141
142
+ remaining_distance_ = 0.0 ;
143
+
141
144
for (auto & llt : remaining_shortest_path) {
142
145
if (remaining_shortest_path.size () == 1 ) {
143
- remaining_distance +=
146
+ remaining_distance_ +=
144
147
tier4_autoware_utils::calcDistance2d (current_vehicle_pose_.position , goal_pose_.position );
145
148
break ;
146
149
}
@@ -150,33 +153,29 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const
150
153
lanelet::utils::getArcCoordinates ({llt}, current_vehicle_pose_);
151
154
double this_lanelet_length = lanelet::utils::getLaneletLength2d (llt);
152
155
153
- remaining_distance += this_lanelet_length - arc_coord.length ;
156
+ remaining_distance_ += this_lanelet_length - arc_coord.length ;
154
157
} else if (index == (remaining_shortest_path.size () - 1 )) {
155
158
lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates ({llt}, goal_pose_);
156
- remaining_distance += arc_coord.length ;
159
+ remaining_distance_ += arc_coord.length ;
157
160
} else {
158
- remaining_distance += lanelet::utils::getLaneletLength2d (llt);
161
+ remaining_distance_ += lanelet::utils::getLaneletLength2d (llt);
159
162
}
160
163
161
164
index ++;
162
165
}
163
-
164
- return remaining_distance;
165
166
}
166
167
167
- double RemainingDistanceTimeCalculatorNode::calculate_remaining_time (
168
- const double remaining_distance) const
168
+ void RemainingDistanceTimeCalculatorNode::calculate_remaining_time ()
169
169
{
170
- return remaining_distance / velocity_limit_;
170
+ remaining_time_ = remaining_distance_ / velocity_limit_;
171
171
}
172
172
173
- void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time (
174
- const double remaining_distance, const double remaining_time) const
173
+ void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time ()
175
174
{
176
175
MissionRemainingDistanceTime mission_remaining_distance_time;
177
176
178
- mission_remaining_distance_time.remaining_distance = remaining_distance ;
179
- mission_remaining_distance_time.remaining_time = remaining_time ;
177
+ mission_remaining_distance_time.remaining_distance = remaining_distance_ ;
178
+ mission_remaining_distance_time.remaining_time = remaining_time_ ;
180
179
pub_mission_remaining_distance_time_->publish (mission_remaining_distance_time);
181
180
}
182
181
0 commit comments