Struct MqttClient::Ros2MqttInterface
- Defined in File MqttClient.hpp 
Nested Relationships
This struct is a nested type of Class MqttClient.
Struct Documentation
- 
struct Ros2MqttInterface
- Struct containing variables related to a ROS2MQTT connection. - Public Members - 
rclcpp::GenericSubscription::SharedPtr subscriber
- generic ROS subscriber 
 - 
std::string msg_type
- message type of subscriber 
 - 
int queue_size = 1
- ROS subscriber queue size. 
 - 
bool is_stale = false
- whether a new generic publisher/subscriber is required 
 - 
std::optional<rclcpp::ReliabilityPolicy> reliability
 - 
std::optional<rclcpp::DurabilityPolicy> durability
 - 
struct mqtt_client::MqttClient::Ros2MqttInterface qos
 - 
struct mqtt_client::MqttClient::Ros2MqttInterface ros
- ROS-related variables. 
 - 
std::string topic
- MQTT topic. 
 - 
int qos = 0
- MQTT QoS value. 
 - 
bool retained = false
- whether to retain MQTT message 
 - 
struct mqtt_client::MqttClient::Ros2MqttInterface mqtt
- MQTT-related variables. 
 - 
bool fixed_type = false
- whether the published message type is specified explicitly 
 - 
bool primitive = false
- whether to publish as primitive message 
 - 
bool stamped = false
- whether to inject timestamp in MQTT message 
 
- 
rclcpp::GenericSubscription::SharedPtr subscriber