Skip to content

Commit

Permalink
fix for main
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Aug 5, 2024
1 parent 842de07 commit 5411676
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "behaviortree_cpp_v3/action_node.h"
#include "behaviortree_cpp/action_node.h"
#include "nav2_msgs/srv/get_cost.hpp"

namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

#include "nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"
#include "nav2_costmap_2d/cost_values.hpp"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

Expand All @@ -31,7 +30,7 @@ RemoveInCollisionGoals::RemoveInCollisionGoals(
: BT::ActionNodeBase(name, conf),
initialized_(false),
which_costmap_("both"),
cost_threshold_(nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
cost_threshold_(253)
{}

void RemoveInCollisionGoals::initialize()
Expand Down

0 comments on commit 5411676

Please sign in to comment.