Skip to content

Commit

Permalink
Minor fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Aug 6, 2024
1 parent 384bccb commit 45b8a08
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 2 deletions.
3 changes: 3 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,9 @@ list(APPEND plugin_libs nav2_navigate_through_poses_action_bt_node)
add_library(nav2_remove_passed_goals_action_bt_node SHARED plugins/action/remove_passed_goals_action.cpp)
list(APPEND plugin_libs nav2_remove_passed_goals_action_bt_node)

add_library(nav2_remove_in_collision_goals_action_bt_node SHARED plugins/action/remove_in_collision_goals_action.cpp)
list(APPEND plugin_libs nav2_remove_in_collision_goals_action_bt_node)

add_library(nav2_get_pose_from_path_action_bt_node SHARED plugins/action/get_pose_from_path_action.cpp)
list(APPEND plugin_libs nav2_get_pose_from_path_action_bt_node)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ class RemoveInCollisionGoals : public BT::ActionNodeBase

rclcpp::Node::SharedPtr node_;
rclcpp::Client<nav2_msgs::srv::GetCost>::SharedPtr get_cost_client_;
std::string costmap_cost_service_;
bool initialized_;
std::string costmap_cost_service_;
bool use_footprint_;
double cost_threshold_;
std::chrono::milliseconds server_timeout_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ inline BT::NodeStatus RemoveInCollisionGoals::tick()

} // namespace nav2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::RemoveInCollisionGoals>("RemoveInCollisionGoals");
Expand Down

0 comments on commit 45b8a08

Please sign in to comment.