Skip to content

Commit 63b6d90

Browse files
Improving stability of action feedback (#4225)
* Improving stability of feedback * Adding Nsv through poses
1 parent 6f5bb6b commit 63b6d90

File tree

2 files changed

+8
-2
lines changed

2 files changed

+8
-2
lines changed

nav2_bt_navigator/src/navigators/navigate_through_poses.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,10 @@ NavigateThroughPosesNavigator::onLoop()
123123
try {
124124
// Get current path points
125125
nav_msgs::msg::Path current_path;
126-
res = blackboard->get(path_blackboard_id_, current_path);
126+
if (!blackboard->get(path_blackboard_id_, current_path) || current_path.poses.size() == 0u) {
127+
// If no path set yet or not meaningful, can't compute ETA or dist remaining yet.
128+
throw std::exception();
129+
}
127130

128131
// Find the closest pose to current pose on global path
129132
auto find_closest_pose_idx =

nav2_bt_navigator/src/navigators/navigate_to_pose.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,10 @@ NavigateToPoseNavigator::onLoop()
126126
try {
127127
// Get current path points
128128
nav_msgs::msg::Path current_path;
129-
[[maybe_unused]] auto res = blackboard->get(path_blackboard_id_, current_path);
129+
if (!blackboard->get(path_blackboard_id_, current_path) || current_path.poses.size() == 0u) {
130+
// If no path set yet or not meaningful, can't compute ETA or dist remaining yet.
131+
throw std::exception();
132+
}
130133

131134
// Find the closest pose to current pose on global path
132135
auto find_closest_pose_idx =

0 commit comments

Comments
 (0)