Skip to content

Commit ee08bc2

Browse files
author
Ahmed Ebrahim
committed
feat(remaining_dist_eta): handle cases when routing graph is not able to find proper route by maintaining last valid remaining dist and time
Signed-off-by: Ahmed Ebrahim <ahmed.ebrahim@leodrive.ai>
1 parent 68a8be7 commit ee08bc2

File tree

2 files changed

+27
-26
lines changed

2 files changed

+27
-26
lines changed

planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp

+21-22
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,9 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode(
3737
: Node("remaining_distance_time_calculator", options),
3838
is_graph_ready_{false},
3939
has_received_route_{false},
40-
velocity_limit_{99.99}
40+
velocity_limit_{99.99},
41+
remaining_distance_{0.0},
42+
remaining_time_{0.0}
4143
{
4244
using std::placeholders::_1;
4345

@@ -101,46 +103,47 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit(
101103
void RemainingDistanceTimeCalculatorNode::on_timer()
102104
{
103105
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();
107109
}
108110
}
109111

110-
double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const
112+
void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance()
111113
{
112-
double remaining_distance = 0.0;
113114
size_t index = 0;
114115

115116
lanelet::ConstLanelet current_lanelet;
116117
if (!lanelet::utils::query::getClosestLanelet(
117118
road_lanelets_, current_vehicle_pose_, &current_lanelet)) {
118119
RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find current lanelet.");
119120

120-
return 0.0;
121+
return;
121122
}
122123

123124
lanelet::ConstLanelet goal_lanelet;
124125
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet)) {
125126
RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find goal lanelet.");
126127

127-
return 0.0;
128+
return;
128129
}
129130

130131
const lanelet::Optional<lanelet::routing::Route> optional_route =
131132
routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0);
132133
if (!optional_route) {
133134
RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find proper route.");
134135

135-
return 0.0;
136+
return;
136137
}
137138

138139
lanelet::routing::LaneletPath remaining_shortest_path;
139140
remaining_shortest_path = optional_route->shortestPath();
140141

142+
remaining_distance_ = 0.0;
143+
141144
for (auto & llt : remaining_shortest_path) {
142145
if (remaining_shortest_path.size() == 1) {
143-
remaining_distance +=
146+
remaining_distance_ +=
144147
tier4_autoware_utils::calcDistance2d(current_vehicle_pose_.position, goal_pose_.position);
145148
break;
146149
}
@@ -150,33 +153,29 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const
150153
lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_);
151154
double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt);
152155

153-
remaining_distance += this_lanelet_length - arc_coord.length;
156+
remaining_distance_ += this_lanelet_length - arc_coord.length;
154157
} else if (index == (remaining_shortest_path.size() - 1)) {
155158
lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_);
156-
remaining_distance += arc_coord.length;
159+
remaining_distance_ += arc_coord.length;
157160
} else {
158-
remaining_distance += lanelet::utils::getLaneletLength2d(llt);
161+
remaining_distance_ += lanelet::utils::getLaneletLength2d(llt);
159162
}
160163

161164
index++;
162165
}
163-
164-
return remaining_distance;
165166
}
166167

167-
double RemainingDistanceTimeCalculatorNode::calculate_remaining_time(
168-
const double remaining_distance) const
168+
void RemainingDistanceTimeCalculatorNode::calculate_remaining_time()
169169
{
170-
return remaining_distance / velocity_limit_;
170+
remaining_time_ = remaining_distance_ / velocity_limit_;
171171
}
172172

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()
175174
{
176175
MissionRemainingDistanceTime mission_remaining_distance_time;
177176

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_;
180179
pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time);
181180
}
182181

planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,9 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
7878
bool has_received_route_;
7979
double velocity_limit_;
8080

81+
double remaining_distance_;
82+
double remaining_time_;
83+
8184
// Parameter
8285
NodeParam node_param_;
8386

@@ -91,18 +94,17 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
9194
/**
9295
* @brief calculate mission remaining distance
9396
*/
94-
double calculate_remaining_distance() const;
97+
void calculate_remaining_distance();
9598

9699
/**
97100
* @brief calculate mission remaining time
98101
*/
99-
double calculate_remaining_time(double remaining_distance) const;
102+
void calculate_remaining_time();
100103

101104
/**
102105
* @brief publish mission remaining distance and time
103106
*/
104-
void publish_mission_remaining_distance_time(
105-
double remaining_distance, double remaining_time) const;
107+
void publish_mission_remaining_distance_time();
106108
};
107109
} // namespace autoware::remaining_distance_time_calculator
108110
#endif // REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_

0 commit comments

Comments
 (0)