Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
5 changes: 3 additions & 2 deletions ros_gz_bridge/include/ros_gz_bridge/bridge_config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,8 +75,9 @@ struct BridgeConfig
/// \brief Depth of the publisher queue
std::optional<size_t> publisher_queue_size;

/// \brief Flag to change the "laziness" of the bridge
bool is_lazy = kDefaultLazy;
/// \brief Flag to change the "laziness" of the bridge.
/// When std::nullopt, the node-level lazy parameter is used as the default.
std::optional<bool> is_lazy;

/// \brief QoS profile (unresolved, might have wrong depth).
/// \note Use PublisherQoS() and SubscriberQoS() to get the final QoS.
Expand Down
2 changes: 1 addition & 1 deletion ros_gz_bridge/src/bridge_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ BridgeHandle::~BridgeHandle() = default;

bool BridgeHandle::IsLazy() const
{
return config_.is_lazy;
return config_.is_lazy.value_or(kDefaultLazy);
}

void BridgeHandle::Start()
Expand Down
1 change: 1 addition & 0 deletions ros_gz_bridge/src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,7 @@ int main(int argc, char * argv[])
return -1;
}
config.gz_type_name = arg;
config.is_lazy = lazy_subscription;
bridge_node->add_bridge(config);
}

Expand Down
10 changes: 7 additions & 3 deletions ros_gz_bridge/src/ros_gz_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ RosGzBridge::RosGzBridge(const rclcpp::NodeOptions & options)
// If it is defined, they are applied only if they are non-negative.
this->declare_parameter(prefix + "publisher_queue", -1);
this->declare_parameter(prefix + "subscriber_queue", -1);
this->declare_parameter(prefix + "lazy", false);
this->declare_parameter(prefix + "lazy", this->get_parameter("lazy").as_bool());
this->declare_parameter(prefix + "qos_profile", "");
} else {
const auto gz_req_type = this->declare_parameter(prefix + "gz_req_type_name",
Expand Down Expand Up @@ -126,6 +126,9 @@ void RosGzBridge::spin()
const std::string ros_ns = this->get_namespace();
const std::string ros_node_name = this->get_name();

bool lazy;
this->get_parameter("lazy", lazy);

// Add bridges from config file
if (!config_file.empty()) {
auto entries = readFromYamlFile(config_file);
Expand All @@ -134,6 +137,7 @@ void RosGzBridge::spin()
entry.gz_topic_name = rclcpp::expand_topic_or_service_name(
entry.gz_topic_name, ros_node_name, ros_ns, false);
}
entry.is_lazy = entry.is_lazy.value_or(lazy);
if (entry.service_name.empty()) {
this->add_bridge(entry);
} else {
Expand Down Expand Up @@ -258,7 +262,7 @@ void RosGzBridge::add_bridge(const BridgeConfig & config)
"Creating GZ->ROS Bridge: [%s (%s) -> %s (%s)] (Lazy %d)",
config.gz_topic_name.c_str(), config.gz_type_name.c_str(),
config.ros_topic_name.c_str(), config.ros_type_name.c_str(),
config.is_lazy);
config.is_lazy.value_or(kDefaultLazy));
handles_.push_back(
std::make_unique<ros_gz_bridge::BridgeHandleGzToRos>(
shared_from_this(), gz_node_,
Expand All @@ -273,7 +277,7 @@ void RosGzBridge::add_bridge(const BridgeConfig & config)
"Creating ROS->GZ Bridge: [%s (%s) -> %s (%s)] (Lazy %d)",
config.ros_topic_name.c_str(), config.ros_type_name.c_str(),
config.gz_topic_name.c_str(), config.gz_type_name.c_str(),
config.is_lazy);
config.is_lazy.value_or(kDefaultLazy));
handles_.push_back(
std::make_unique<ros_gz_bridge::BridgeHandleRosToGz>(
shared_from_this(), gz_node_,
Expand Down
16 changes: 8 additions & 8 deletions ros_gz_bridge/test/bridge_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ TEST_F(BridgeConfig, Minimum)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_FALSE(config.publisher_queue_size.has_value());
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(ros_gz_bridge::kDefaultLazy, config.is_lazy);
EXPECT_EQ(std::nullopt, config.is_lazy);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.PublisherQoS());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.SubscriberQoS());
Expand All @@ -94,7 +94,7 @@ TEST_F(BridgeConfig, Minimum)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_FALSE(config.publisher_queue_size.has_value());
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(ros_gz_bridge::kDefaultLazy, config.is_lazy);
EXPECT_EQ(std::nullopt, config.is_lazy);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.PublisherQoS());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.SubscriberQoS());
Expand All @@ -107,7 +107,7 @@ TEST_F(BridgeConfig, Minimum)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_FALSE(config.publisher_queue_size.has_value());
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(ros_gz_bridge::kDefaultLazy, config.is_lazy);
EXPECT_EQ(std::nullopt, config.is_lazy);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.PublisherQoS());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.SubscriberQoS());
Expand All @@ -120,7 +120,7 @@ TEST_F(BridgeConfig, Minimum)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_FALSE(config.publisher_queue_size.has_value());
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(ros_gz_bridge::kDefaultLazy, config.is_lazy);
EXPECT_EQ(std::nullopt, config.is_lazy);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.PublisherQoS());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(10u)), config.SubscriberQoS());
Expand All @@ -147,7 +147,7 @@ TEST_F(BridgeConfig, FullGz)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_EQ(6u, config.publisher_queue_size.value_or(0));
EXPECT_EQ(5u, config.subscriber_queue_size.value_or(0));
EXPECT_EQ(true, config.is_lazy);
EXPECT_EQ(std::optional<bool>(true), config.is_lazy);
EXPECT_EQ(ros_gz_bridge::BridgeDirection::ROS_TO_GZ, config.direction);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(6u)), config.PublisherQoS());
Expand All @@ -162,7 +162,7 @@ TEST_F(BridgeConfig, FullGz)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_EQ(20u, config.publisher_queue_size.value_or(0));
EXPECT_EQ(10u, config.subscriber_queue_size.value_or(0));
EXPECT_EQ(false, config.is_lazy);
EXPECT_EQ(std::optional<bool>(false), config.is_lazy);
EXPECT_EQ(ros_gz_bridge::BridgeDirection::GZ_TO_ROS, config.direction);
EXPECT_FALSE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::QoS(rclcpp::KeepLast(20u)), config.PublisherQoS());
Expand Down Expand Up @@ -191,7 +191,7 @@ TEST_F(BridgeConfig, QoSFullGz)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_FALSE(config.publisher_queue_size.has_value());
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(true, config.is_lazy);
EXPECT_EQ(std::optional<bool>(true), config.is_lazy);
EXPECT_EQ(ros_gz_bridge::BridgeDirection::ROS_TO_GZ, config.direction);
ASSERT_TRUE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::SensorDataQoS(), *config.qos_profile);
Expand All @@ -207,7 +207,7 @@ TEST_F(BridgeConfig, QoSFullGz)
EXPECT_EQ("ignition.msgs.StringMsg", config.gz_type_name);
EXPECT_EQ(20u, config.publisher_queue_size.value_or(0));
EXPECT_FALSE(config.subscriber_queue_size.has_value());
EXPECT_EQ(false, config.is_lazy);
EXPECT_EQ(std::optional<bool>(false), config.is_lazy);
EXPECT_EQ(ros_gz_bridge::BridgeDirection::GZ_TO_ROS, config.direction);
ASSERT_TRUE(config.qos_profile.has_value());
EXPECT_EQ(rclcpp::ClockQoS(), *config.qos_profile);
Expand Down
Loading