Struct BridgeConfig
Defined in File bridge_config.hpp
Struct Documentation
-
struct BridgeConfig
Public Functions
-
rclcpp::QoS PublisherQoS() const
Get the resolved QoS for publishers. It does not reflect QoS overrides.
-
rclcpp::QoS SubscriberQoS() const
Get the resolved QoS for subscribers. It does not reflect QoS overrides.
Public Members
-
std::string ros_type_name
The ROS message type (eg std_msgs/msg/String)
-
std::string ros_topic_name
The ROS topic name to bridge.
-
std::string gz_type_name
The Gazebo message type (eg ignition.msgs.String) Used with topic bridges.
-
std::string gz_topic_name
The Gazebo topic name to bridge.
-
BridgeDirection direction = kDefaultDirection
Connectivity of the bridge.
-
std::optional<size_t> subscriber_queue_size
Depth of the subscriber queue.
-
std::optional<size_t> publisher_queue_size
Depth of the publisher queue.
-
bool is_lazy = kDefaultLazy
Flag to change the “laziness” of the bridge.
-
std::optional<rclcpp::QoS> qos_profile
QoS profile (unresolved, might have wrong depth).
Note
Use PublisherQoS() and SubscriberQoS() to get the final QoS.
-
std::string service_name
The ROS service name (eg ~/get_parameters)
-
std::string gz_req_type_name
The ROS service type request.
-
std::string gz_rep_type_name
The ROS service type response.
-
rclcpp::QoS PublisherQoS() const