Class MqttClient

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

  • public rclcpp::Node

  • public mqtt::callback

  • public mqtt::iaction_listener

Class Documentation

class MqttClient : public rclcpp::Node, public virtual mqtt::callback, public virtual mqtt::iaction_listener

ROS Nodelet for sending and receiving ROS messages via MQTT.

The MqttClient enables connected ROS-based devices or robots to exchange ROS messages via an MQTT broker using the MQTT protocol. This works generically for any ROS message, i.e. there is no need to specify the ROS message type for ROS messages you wish to exchange via the MQTT broker.

Public Functions

explicit MqttClient(const rclcpp::NodeOptions &options)

Initializes node.

Parameters:

options[in] ROS node options

Protected Functions

void loadParameters()

Loads ROS parameters from parameter server.

bool loadParameter(const std::string &key, std::string &value)

Loads requested ROS parameter from parameter server.

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found

bool loadParameter(const std::string &key, std::string &value, const std::string &default_value)

Loads requested ROS parameter from parameter server, allows default value.

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

  • default_value[in] default value

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found or default was used

template<typename T>
bool loadParameter(const std::string &key, T &value)

Loads requested ROS parameter from parameter server.

Template Parameters:

T – type (one of int, double, bool)

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found

template<typename T>
bool loadParameter(const std::string &key, T &value, const T &default_value)

Loads requested ROS parameter from parameter server, allows default value.

Template Parameters:

T – type (one of int, double, bool)

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

  • default_value[in] default value

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found or default was used

template<typename T>
bool loadParameter(const std::string &key, std::vector<T> &value)

Loads requested ROS parameter from parameter server.

Template Parameters:

T – type (one of int, double, bool)

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found

template<typename T>
bool loadParameter(const std::string &key, std::vector<T> &value, const std::vector<T> &default_value)

Loads requested ROS parameter from parameter server, allows default value.

Template Parameters:

T – type (one of int, double, bool)

Parameters:
  • key[in] parameter name

  • value[out] variable where to store the retrieved parameter

  • default_value[in] default value

Returns:

true if parameter was successfully retrieved

Returns:

false if parameter was not found or default was used

std::filesystem::path resolvePath(const std::string &path_string)

Converts a string to a path object resolving paths relative to ROS_HOME.

Resolves relative to CWD, if ROS_HOME is not set. Returns empty path, if argument is empty.

Parameters:

path_string – (relative) path as string

Returns:

std::filesystem::path path variable

void setup()

Initializes broker connection and subscriptions.

std::optional<rclcpp::QoS> getCompatibleQoS(const std::string &ros_topic, const rclcpp::TopicEndpointInfo &tei, const Ros2MqttInterface &ros2mqtt) const

Get the resolved compatible QOS from the interface and the endpoint.

This uses the two endpoints to decide upon a compatible QoS, resolving any “auto” QoS settings

Parameters:
  • ros_topic – the ROS topic we are looking on

  • tei – Topic endpoint info

  • ros2mqtt – the ROS to MQTT interface spec

Returns:

The compatible QoS or nullopt if no compatible combination is found

std::vector<rclcpp::TopicEndpointInfo> getCandidatePublishers(const std::string &ros_topic, const Ros2MqttInterface &ros2mqtt) const

Get the candidate topic endpoints for subscription matching.

Parameters:

ros2mqtt – the ROS to MQTT interface spec

Returns:

The compatible QoS or nullopt if no compatible combination is found

void setupSubscriptions()

Setup any subscriptions we can.

These may be fixed type/QoS, or dynamically matched against active publisher

void setupPublishers()

Setup any publishers that we can.

void setupClient()

Sets up the client connection options and initializes the client object.

void connect()

Connects to the broker using the member client and options.

void ros2mqtt(const std::shared_ptr<rclcpp::SerializedMessage> &serialized_msg, const std::string &ros_topic)

Publishes a generic serialized ROS message to the MQTT broker.

Before publishing the ROS message to the MQTT broker, the ROS message type is extracted. This type information is also sent to the MQTT broker on a separate topic.

The MQTT payload for the actual ROS message carries the following:

  • 0 or 1 (indicating if timestamp is injected (=1))

  • serialized timestamp (optional)

  • serialized ROS message

Parameters:
  • serialized_msg – generic serialized ROS message

  • ros_topic – ROS topic where the message was published

void mqtt2ros(mqtt::const_message_ptr mqtt_msg, const rclcpp::Time &arrival_stamp)

Publishes a ROS message received via MQTT to ROS.

This utilizes the generic publisher stored for the MQTT topic on which the message was received. The publisher has to be configured to the ROS message type of the message. If the message carries an injected timestamp, the latency is computed and published.

The MQTT payload is expected to carry the following:

  • 0 or 1 (indicating if timestamp is injected (=1))

  • serialized timestamp (optional)

  • serialized ROS message

Parameters:
  • mqtt_msg – MQTT message

  • arrival_stamp – arrival timestamp used for latency computation

void mqtt2primitive(mqtt::const_message_ptr mqtt_msg)

Publishes a primitive message received via MQTT to ROS.

Parameters:

mqtt_msg – MQTT message

void mqtt2fixed(mqtt::const_message_ptr mqtt_msg)

Publishes a primitive message received via MQTT to ROS.

Parameters:

mqtt_msg – MQTT message

void connected(const std::string &cause) override

Callback for when the client has successfully connected to the broker.

Overrides mqtt::callback::connected(const std::string&).

Parameters:

cause

void connection_lost(const std::string &cause) override

Callback for when the client has lost connection to the broker.

Overrides mqtt::callback::connection_lost(const std::string&).

Parameters:

cause

bool isConnected()

Returns whether the client is connected to the broker.

Returns:

true if client is connected to the broker

Returns:

false if client is not connected to the broker

void isConnectedService(mqtt_client_interfaces::srv::IsConnected::Request::SharedPtr request, mqtt_client_interfaces::srv::IsConnected::Response::SharedPtr response)

ROS service returning whether the client is connected to the broker.

Parameters:
  • request – service request

  • response – service response

void newRos2MqttBridge(mqtt_client_interfaces::srv::NewRos2MqttBridge::Request::SharedPtr request, mqtt_client_interfaces::srv::NewRos2MqttBridge::Response::SharedPtr response)

ROS service that dynamically creates a ROS -> MQTT mapping.

Parameters:
  • request – service request

  • response – service response

void newMqtt2RosBridge(mqtt_client_interfaces::srv::NewMqtt2RosBridge::Request::SharedPtr request, mqtt_client_interfaces::srv::NewMqtt2RosBridge::Response::SharedPtr response)

ROS service that dynamically creates an MQTT -> ROS mapping.

Parameters:
  • request – service request

  • response – service response

void message_arrived(mqtt::const_message_ptr mqtt_msg) override

Callback for when the client receives a MQTT message from the broker.

Overrides mqtt::callback::message_arrived(mqtt::const_message_ptr). If the received MQTT message contains information about a ROS message type, the corresponding ROS publisher is configured. If the received MQTT message is a ROS message, the mqtt2ros conversion is called.

Parameters:

mqtt_msg – MQTT message

void delivery_complete(mqtt::delivery_token_ptr token) override

Callback for when delivery for a MQTT message has been completed.

Overrides mqtt::callback::delivery_complete(mqtt::delivery_token_ptr).

Parameters:

token – token tracking the message delivery

void on_success(const mqtt::token &token) override

Callback for when a MQTT action succeeds.

Overrides mqtt::iaction_listener::on_success(const mqtt::token&). Does nothing.

Parameters:

token – token tracking the action

void on_failure(const mqtt::token &token) override

Callback for when a MQTT action fails.

Overrides mqtt::iaction_listener::on_failure(const mqtt::token&). Logs error.

Parameters:

token – token tracking the action

Protected Attributes

rclcpp::TimerBase::SharedPtr check_subscriptions_timer_

Timer to repeatedly check active ROS topics for topics to subscribe.

rclcpp::Service<mqtt_client_interfaces::srv::IsConnected>::SharedPtr is_connected_service_

ROS Service server for providing connection status.

rclcpp::Service<mqtt_client_interfaces::srv::NewRos2MqttBridge>::SharedPtr new_ros2mqtt_bridge_service_

ROS Service server for providing dynamic ROS to MQTT mappings.

rclcpp::Service<mqtt_client_interfaces::srv::NewMqtt2RosBridge>::SharedPtr new_mqtt2ros_bridge_service_

ROS Service server for providing dynamic MQTT to ROS mappings.

bool is_connected_ = false

Status variable keeping track of connection status to broker.

BrokerConfig broker_config_

Broker parameters.

ClientConfig client_config_

Client parameters.

std::shared_ptr<mqtt::async_client> client_

MQTT client variable.

mqtt::connect_options connect_options_

MQTT client connection options.

std::map<std::string, Ros2MqttInterface> ros2mqtt_

ROS2MQTT connection variables sorted by ROS topic.

std::map<std::string, Mqtt2RosInterface> mqtt2ros_

MQTT2ROS connection variables sorted by MQTT topic.

uint32_t stamp_length_

Message length of a serialized builtin_interfaces::msg::Time message

Protected Static Attributes

static const std::string kRosMsgTypeMqttTopicPrefix

MQTT topic prefix under which ROS message type information is published.

Must contain trailing ‘/’.

static const std::string kLatencyRosTopicPrefix

ROS topic prefix under which ROS2MQTT2ROS latencies are published.

Must contain trailing ‘/’.

struct BrokerConfig

Struct containing broker parameters.

Public Members

std::string host

broker host

int port

broker port

std::string user

username

std::string pass

password

bool enabled

whether to connect via SSL/TLS

std::filesystem::path ca_certificate

public CA certificate trusted by client

struct mqtt_client::MqttClient::BrokerConfig tls

SSL/TLS-related variables.

struct ClientConfig

Struct containing client parameters.

Public Members

std::string id

client unique ID

bool enabled

whether client buffer is enabled

int size

client buffer size

std::filesystem::path directory

client buffer directory

struct mqtt_client::MqttClient::ClientConfig buffer

client buffer-related variables

std::string topic

last-will topic

std::string message

last-will message

int qos

last-will QoS value

bool retained

whether last-will is retained

struct mqtt_client::MqttClient::ClientConfig last_will

last-will-related variables

bool clean_session

whether client requests clean session

double keep_alive_interval

keep-alive interval

int max_inflight

maximum number of inflight messages

std::filesystem::path certificate

client certificate

std::filesystem::path key

client private keyfile

std::string password

decryption password for private key

int version

TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)

bool verify

Verify the client should conduct post-connect checks

bool server_cert_auth

whether to verify the server certificate

std::vector<std::string> alpn_protos

list of ALPN protocols

struct mqtt_client::MqttClient::ClientConfig tls

SSL/TLS-related variables.

struct Mqtt2RosInterface

Struct containing variables related to a MQTT2ROS connection.

Public Members

int qos = 0

MQTT QoS value.

struct mqtt_client::MqttClient::Mqtt2RosInterface mqtt

MQTT-related variables.

std::string topic

ROS topic.

std::string msg_type

message type of publisher

rclcpp::GenericPublisher::SharedPtr publisher

generic ROS publisher

rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr latency_publisher

ROS publisher for latency.

int queue_size = 1

ROS publisher queue size.

rclcpp::ReliabilityPolicy reliability = rclcpp::ReliabilityPolicy::SystemDefault
rclcpp::DurabilityPolicy durability = rclcpp::DurabilityPolicy::SystemDefault
struct mqtt_client::MqttClient::Mqtt2RosInterface qos
bool latched = false

whether to latch ROS message

bool is_stale = false

whether a new generic publisher/subscriber is required

struct mqtt_client::MqttClient::Mqtt2RosInterface ros

ROS-related variables.

bool fixed_type = false

whether the published ros message type is specified explicitly

bool primitive = false

whether to publish as primitive message (if coming from non-ROS MQTT client)

bool stamped = false

whether timestamp is injected

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