Skip to content

Commit b5020ee

Browse files
committed
improvements
Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com>
1 parent e52ea5d commit b5020ee

File tree

2 files changed

+20
-8
lines changed

2 files changed

+20
-8
lines changed

nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,13 @@ void RemoveInCollisionGoals::on_tick()
5555
BT::NodeStatus RemoveInCollisionGoals::on_completion(
5656
std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response)
5757
{
58+
if (response->costs.size() != input_goals_.size()) {
59+
RCLCPP_ERROR(
60+
node_->get_logger(),
61+
"Received incorrect number of costs from GetCost service");
62+
return BT::NodeStatus::FAILURE;
63+
}
64+
5865
Goals valid_goal_poses;
5966
for (size_t i = 0; i < response->costs.size(); ++i) {
6067
if ((response->costs[i] == 255 && !consider_unknown_as_obstacle_) ||

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -837,14 +837,11 @@ void Costmap2DROS::getCostsCallback(
837837

838838
for (const auto & pose : request->poses) {
839839
geometry_msgs::msg::PoseStamped pose_transformed;
840-
transformPoseToGlobalFrame(pose, pose_transformed);
841-
bool in_bounds = costmap->worldToMap(
842-
pose_transformed.pose.position.x,
843-
pose_transformed.pose.position.y, mx, my);
844-
845-
if (!in_bounds) {
846-
response->costs.push_back(NO_INFORMATION);
847-
continue;
840+
if (!transformPoseToGlobalFrame(pose, pose_transformed)) {
841+
response->costs.clear();
842+
RCLCPP_ERROR(
843+
get_logger(), "Failed to transform, returning empty costs");
844+
return;
848845
}
849846
double yaw = tf2::getYaw(pose_transformed.pose.orientation);
850847

@@ -866,6 +863,14 @@ void Costmap2DROS::getCostsCallback(
866863
pose_transformed.pose.position.x,
867864
pose_transformed.pose.position.y);
868865

866+
bool in_bounds = costmap->worldToMap(
867+
pose_transformed.pose.position.x,
868+
pose_transformed.pose.position.y, mx, my);
869+
870+
if (!in_bounds) {
871+
response->costs.push_back(LETHAL_OBSTACLE);
872+
continue;
873+
}
869874
// Get the cost at the map coordinates
870875
response->costs.push_back(static_cast<float>(costmap->getCost(mx, my)));
871876
}

0 commit comments

Comments
 (0)