Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
toggle on
Signed-off-by: Steve Macenski <stevenmacenski@gmail.com>
  • Loading branch information
SteveMacenski committed Jun 24, 2025
commit 20c0be74c93e420bf9c5e3e8d052393fb2734faa
2 changes: 2 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ target_link_libraries(${library_name} PUBLIC
${sensor_msgs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
nav2_ros_common::nav2_ros_common
)

add_library(nav2_compute_path_to_pose_action_bt_node SHARED plugins/action/compute_path_to_pose_action.cpp)
Expand Down Expand Up @@ -264,6 +265,7 @@ foreach(bt_plugin ${plugin_libs})
tf2_ros::tf2_ros
${std_msgs_TARGETS}
${std_srvs_TARGETS}
nav2_ros_common::nav2_ros_common
)
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
endforeach()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <chrono>

#include "behaviortree_cpp/action_node.h"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_ros_common/lifecycle_node.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ typename nav2::Subscription<MessageT>::SharedPtr create_subscription(
const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
{
bool allow_parameter_qos_overrides = nav2::declare_or_get_parameter(
node, "allow_parameter_qos_overrides", false);
node, "allow_parameter_qos_overrides", true);

auto params_interface = node->get_node_parameters_interface();
auto topics_interface = node->get_node_topics_interface();
Expand Down Expand Up @@ -229,7 +229,7 @@ typename nav2::Publisher<MessageT>::SharedPtr create_publisher(
const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
{
bool allow_parameter_qos_overrides = nav2::declare_or_get_parameter(
node, "allow_parameter_qos_overrides", false);
node, "allow_parameter_qos_overrides", true);
using PublisherT = nav2::Publisher<MessageT>;
auto pub = rclcpp::create_publisher<MessageT, std::allocator<void>, PublisherT>(
*node,
Expand Down
12 changes: 5 additions & 7 deletions nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,12 +281,10 @@ void SmacPlannerHybrid::configure(
}

// Initialize costmap downsampler
if (_downsample_costmap && _downsampling_factor > 1) {
_costmap_downsampler = std::make_unique<CostmapDownsampler>();
std::string topic_name = "downsampled_costmap";
_costmap_downsampler->on_configure(
node, _global_frame, topic_name, _costmap, _downsampling_factor);
}
_costmap_downsampler = std::make_unique<CostmapDownsampler>();
std::string topic_name = "downsampled_costmap";
_costmap_downsampler->on_configure(
node, _global_frame, topic_name, _costmap, _downsampling_factor);

_raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan");

Expand Down Expand Up @@ -391,7 +389,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(

// Downsample costmap, if required
nav2_costmap_2d::Costmap2D * costmap = _costmap;
if (_costmap_downsampler) {
if (_downsample_costmap && _downsampling_factor > 1) {
costmap = _costmap_downsampler->downsample(_downsampling_factor);
_collision_checker.setCostmap(costmap);
}
Expand Down
Loading