Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1217,7 +1217,7 @@ AmclNode::updateParametersCallback(
map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
map_topic_,
std::bind(&AmclNode::mapReceived, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(3));
}
}

Expand Down Expand Up @@ -1389,7 +1389,7 @@ AmclNode::initPubSub()
map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
map_topic_,
std::bind(&AmclNode::mapReceived, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(2));

RCLCPP_INFO(get_logger(), "Subscribed to map topic.");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class CostmapSubscriber
costmap_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::Costmap>(
parent, topic_name_,
std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(3));

costmap_update_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::CostmapUpdate>(
parent, topic_name_ + "_updates",
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void BinaryFilter::filterInfoCallback(
mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
mask_topic_,
std::bind(&BinaryFilter::maskCallback, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(3));
}

void BinaryFilter::maskCallback(
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ void KeepoutFilter::filterInfoCallback(
mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
mask_topic_,
std::bind(&KeepoutFilter::maskCallback, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(3));
}

void KeepoutFilter::maskCallback(
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ void SpeedFilter::filterInfoCallback(
mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
mask_topic_,
std::bind(&SpeedFilter::maskCallback, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS());
nav2::qos::LatchedSubscriptionQoS(3));
}

void SpeedFilter::maskCallback(
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ StaticLayer::onInitialize()

rclcpp::QoS map_qos = nav2::qos::StandardTopicQoS(); // initialize to default
if (map_subscribe_transient_local_) {
map_qos = nav2::qos::LatchedSubscriptionQoS();
map_qos = nav2::qos::LatchedSubscriptionQoS(3);
}

RCLCPP_INFO(
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void VoxelLayer::onInitialize()

if (publish_voxel_) {
voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
"voxel_grid", nav2::qos::LatchedPublisherQoS());
"voxel_grid", nav2::qos::LatchedPublisherQoS(1));
voxel_pub_->on_activate();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class LayerSubscriber
layer_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
topic_name,
std::bind(&LayerSubscriber::layerCallback, this, std::placeholders::_1),
nav2::qos::LatchedSubscriptionQoS(),
nav2::qos::LatchedSubscriptionQoS(3),
callback_group_);

executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ bool MapSaver::saveMapTopicToFile(

rclcpp::QoS map_qos = nav2::qos::StandardTopicQoS(); // initialize to default
if (map_subscribe_transient_local_) {
map_qos = nav2::qos::LatchedSubscriptionQoS();
map_qos = nav2::qos::LatchedSubscriptionQoS(3);
}

// Create new CallbackGroup for map_sub
Expand Down
3 changes: 2 additions & 1 deletion nav2_map_server/test/component/test_map_saver_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <string>
#include <memory>

#include "nav2_ros_common/qos_profiles.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav2_map_server/map_io.hpp"
#include "test_constants/test_constants.h"
Expand All @@ -41,7 +42,7 @@ class TestPublisher : public rclcpp::Node

map_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
"map",
rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
nav2::qos::LatchedPublisherQoS());
map_pub_->publish(msg);
}

Expand Down
1 change: 1 addition & 0 deletions nav2_map_server/test/map_saver_cli/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,5 @@ ament_add_gtest(test_map_saver_cli
target_link_libraries(test_map_saver_cli
rclcpp::rclcpp
${nav_msgs_TARGETS}
nav2_ros_common::nav2_ros_common
)
3 changes: 2 additions & 1 deletion nav2_map_server/test/map_saver_cli/test_map_saver_cli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <memory>
#include <utility>

#include "nav2_ros_common/qos_profiles.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"

Expand All @@ -34,7 +35,7 @@ TEST(MapSaverCLI, CLITest)

auto publisher = node->create_publisher<nav_msgs::msg::OccupancyGrid>(
"/map",
rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
nav2::qos::LatchedPublisherQoS());

auto msg = std::make_unique<nav_msgs::msg::OccupancyGrid>();
msg->header.frame_id = "map";
Expand Down
Loading