Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
mqtt_client::MqttClient Class Reference

ROS Nodelet for sending and receiving ROS messages via MQTT. More...

#include <MqttClient.h>

Inheritance diagram for mqtt_client::MqttClient:
Inheritance graph
[legend]

Classes

struct  BrokerConfig
 Struct containing broker parameters. More...
 
struct  ClientConfig
 Struct containing client parameters. More...
 
struct  Mqtt2RosInterface
 Struct containing variables related to a MQTT2ROS connection. More...
 
struct  Ros2MqttInterface
 Struct containing variables related to a ROS2MQTT connection. More...
 

Public Member Functions

 MqttClient (const rclcpp::NodeOptions &options)
 Initializes node. More...
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

void connect ()
 Connects to the broker using the member client and options. More...
 
void connect ()
 Connects to the broker using the member client and options. More...
 
void connected (const std::string &cause) override
 Callback for when the client has successfully connected to the broker. More...
 
void connected (const std::string &cause) override
 Callback for when the client has successfully connected to the broker. More...
 
void connection_lost (const std::string &cause) override
 Callback for when the client has lost connection to the broker. More...
 
void connection_lost (const std::string &cause) override
 Callback for when the client has lost connection to the broker. More...
 
void delivery_complete (mqtt::delivery_token_ptr token) override
 Callback for when delivery for a MQTT message has been completed. More...
 
void delivery_complete (mqtt::delivery_token_ptr token) override
 Callback for when delivery for a MQTT message has been completed. More...
 
bool isConnected ()
 Returns whether the client is connected to the broker. More...
 
bool isConnected ()
 Returns whether the client is connected to the broker. More...
 
bool isConnectedService (mqtt_client_interfaces::IsConnected::Request &request, mqtt_client_interfaces::IsConnected::Response &response)
 ROS service returning whether the client is connected to the broker. More...
 
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. More...
 
bool loadParameter (const std::string &key, std::string &value)
 Loads requested ROS parameter from parameter server. More...
 
bool loadParameter (const std::string &key, std::string &value)
 Loads requested ROS parameter from parameter server. More...
 
bool loadParameter (const std::string &key, std::string &value, const std::string &default_value)
 Loads requested ROS parameter from parameter server, allows default value. More...
 
bool loadParameter (const std::string &key, std::string &value, const std::string &default_value)
 Loads requested ROS parameter from parameter server, allows default value. More...
 
template<typename T >
bool loadParameter (const std::string &key, std::vector< T > &value)
 Loads requested ROS parameter from parameter server. More...
 
template<typename T >
bool loadParameter (const std::string &key, std::vector< T > &value)
 Loads requested ROS parameter from parameter server. More...
 
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. More...
 
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. More...
 
template<typename T >
bool loadParameter (const std::string &key, T &value)
 Loads requested ROS parameter from parameter server. More...
 
template<typename T >
bool loadParameter (const std::string &key, T &value)
 Loads requested ROS parameter from parameter server. More...
 
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. More...
 
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. More...
 
void loadParameters ()
 Loads ROS parameters from parameter server. More...
 
void loadParameters ()
 Loads ROS parameters from parameter server. More...
 
void message_arrived (mqtt::const_message_ptr mqtt_msg) override
 Callback for when the client receives a MQTT message from the broker. More...
 
void message_arrived (mqtt::const_message_ptr mqtt_msg) override
 Callback for when the client receives a MQTT message from the broker. More...
 
void mqtt2primitive (mqtt::const_message_ptr mqtt_msg)
 Publishes a primitive message received via MQTT to ROS. More...
 
void mqtt2primitive (mqtt::const_message_ptr mqtt_msg)
 Publishes a primitive message received via MQTT to ROS. More...
 
void mqtt2ros (mqtt::const_message_ptr mqtt_msg, const rclcpp::Time &arrival_stamp)
 Publishes a ROS message received via MQTT to ROS. More...
 
void mqtt2ros (mqtt::const_message_ptr mqtt_msg, const ros::WallTime &arrival_stamp=ros::WallTime::now())
 Publishes a ROS message received via MQTT to ROS. More...
 
void on_failure (const mqtt::token &token) override
 Callback for when a MQTT action fails. More...
 
void on_failure (const mqtt::token &token) override
 Callback for when a MQTT action fails. More...
 
void on_success (const mqtt::token &token) override
 Callback for when a MQTT action succeeds. More...
 
void on_success (const mqtt::token &token) override
 Callback for when a MQTT action succeeds. More...
 
virtual void onInit () override
 Initializes nodelet when nodelet is loaded. More...
 
std::filesystem::path resolvePath (const std::string &path_string)
 Converts a string to a path object resolving paths relative to ROS_HOME. More...
 
std::filesystem::path resolvePath (const std::string &path_string)
 Converts a string to a path object resolving paths relative to ROS_HOME. More...
 
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. More...
 
void ros2mqtt (const topic_tools::ShapeShifter::ConstPtr &ros_msg, const std::string &ros_topic)
 Serializes and publishes a generic ROS message to the MQTT broker. More...
 
void setup ()
 Initializes broker connection and subscriptions. More...
 
void setup ()
 Initializes broker connection and subscriptions. More...
 
void setupClient ()
 Sets up the client connection options and initializes the client object. More...
 
void setupClient ()
 Sets up the client connection options and initializes the client object. More...
 
void setupSubscriptions ()
 Checks all active ROS topics in order to set up generic subscribers. More...
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

BrokerConfig broker_config_
 Broker parameters. More...
 
rclcpp::TimerBase::SharedPtr check_subscriptions_timer_
 Timer to repeatedly check active ROS topics for topics to subscribe. More...
 
std::shared_ptr< mqtt::async_client > client_
 MQTT client variable. More...
 
ClientConfig client_config_
 Client parameters. More...
 
mqtt::connect_options connect_options_
 MQTT client connection options. More...
 
bool is_connected_ = false
 Status variable keeping track of connection status to broker. More...
 
rclcpp::Service< mqtt_client_interfaces::srv::IsConnected >::SharedPtr is_connected_service_
 ROS Service server for providing connection status. More...
 
ros::ServiceServer is_connected_service_
 ROS Service server for providing connection status. More...
 
std::map< std::string, Mqtt2RosInterfacemqtt2ros_
 MQTT2ROS connection variables sorted by MQTT topic. More...
 
ros::NodeHandle node_handle_
 ROS node handle. More...
 
ros::NodeHandle private_node_handle_
 Private ROS node handle. More...
 
std::map< std::string, Ros2MqttInterfaceros2mqtt_
 ROS2MQTT connection variables sorted by ROS topic. More...
 
uint32_t stamp_length_
 

Static Protected Attributes

static const std::string kLatencyRosTopicPrefix = "latencies/"
 ROS topic prefix under which ROS2MQTT2ROS latencies are published. More...
 
static const std::string kRosMsgTypeMqttTopicPrefix
 MQTT topic prefix under which ROS message type information is published. More...
 

Detailed Description

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.

Definition at line 58 of file MqttClient.h.

Constructor & Destructor Documentation

◆ MqttClient()

mqtt_client::MqttClient::MqttClient ( const rclcpp::NodeOptions &  options)
explicit

Initializes node.

Parameters
[in]optionsROS node options

Definition at line 144 of file MqttClient.ros2.cpp.

Member Function Documentation

◆ connect() [1/2]

void mqtt_client::MqttClient::connect ( )
protected

Connects to the broker using the member client and options.

Definition at line 472 of file MqttClient.cpp.

◆ connect() [2/2]

void mqtt_client::MqttClient::connect ( )
protected

Connects to the broker using the member client and options.

◆ connected() [1/2]

void mqtt_client::MqttClient::connected ( const std::string &  cause)
overrideprotected

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

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

Parameters
cause

◆ connected() [2/2]

void mqtt_client::MqttClient::connected ( const std::string &  cause)
overrideprotected

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

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

Parameters
cause

Definition at line 801 of file MqttClient.cpp.

◆ connection_lost() [1/2]

void mqtt_client::MqttClient::connection_lost ( const std::string &  cause)
overrideprotected

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

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

Parameters
cause

◆ connection_lost() [2/2]

void mqtt_client::MqttClient::connection_lost ( const std::string &  cause)
overrideprotected

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

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

Parameters
cause

Definition at line 823 of file MqttClient.cpp.

◆ delivery_complete() [1/2]

void mqtt_client::MqttClient::delivery_complete ( mqtt::delivery_token_ptr  token)
overrideprotected

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

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

Parameters
tokentoken tracking the message delivery

◆ delivery_complete() [2/2]

void mqtt_client::MqttClient::delivery_complete ( mqtt::delivery_token_ptr  token)
overrideprotected

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

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

Parameters
tokentoken tracking the message delivery

Definition at line 931 of file MqttClient.cpp.

◆ isConnected() [1/2]

bool mqtt_client::MqttClient::isConnected ( )
protected

Returns whether the client is connected to the broker.

Returns
true if client is connected to the broker
false if client is not connected to the broker

◆ isConnected() [2/2]

bool mqtt_client::MqttClient::isConnected ( )
protected

Returns whether the client is connected to the broker.

Returns
true if client is connected to the broker
false if client is not connected to the broker

Definition at line 831 of file MqttClient.cpp.

◆ isConnectedService() [1/2]

bool mqtt_client::MqttClient::isConnectedService ( mqtt_client_interfaces::IsConnected::Request &  request,
mqtt_client_interfaces::IsConnected::Response &  response 
)
protected

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

Parameters
requestservice request
responseservice response
Returns
true always
false never

Definition at line 837 of file MqttClient.cpp.

◆ isConnectedService() [2/2]

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

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

Parameters
requestservice request
responseservice response

Definition at line 897 of file MqttClient.ros2.cpp.

◆ loadParameter() [1/12]

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

Loads requested ROS parameter from parameter server.

Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

Definition at line 339 of file MqttClient.cpp.

◆ loadParameter() [2/12]

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

Loads requested ROS parameter from parameter server.

Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

◆ loadParameter() [3/12]

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

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

Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

Definition at line 348 of file MqttClient.cpp.

◆ loadParameter() [4/12]

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

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

Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

◆ loadParameter() [5/12]

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

Loads requested ROS parameter from parameter server.

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

Definition at line 507 of file MqttClient.h.

◆ loadParameter() [6/12]

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

Loads requested ROS parameter from parameter server.

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

◆ loadParameter() [7/12]

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

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

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

Definition at line 518 of file MqttClient.h.

◆ loadParameter() [8/12]

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

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

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

◆ loadParameter() [9/12]

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

Loads requested ROS parameter from parameter server.

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

Definition at line 480 of file MqttClient.h.

◆ loadParameter() [10/12]

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

Loads requested ROS parameter from parameter server.

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
Returns
true if parameter was successfully retrieved
false if parameter was not found

◆ loadParameter() [11/12]

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

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

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

Definition at line 490 of file MqttClient.h.

◆ loadParameter() [12/12]

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

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

Template Parameters
Ttype (one of int, double, bool)
Parameters
[in]keyparameter name
[out]valuevariable where to store the retrieved parameter
[in]default_valuedefault value
Returns
true if parameter was successfully retrieved
false if parameter was not found or default was used

◆ loadParameters() [1/2]

void mqtt_client::MqttClient::loadParameters ( )
protected

Loads ROS parameters from parameter server.

Definition at line 158 of file MqttClient.cpp.

◆ loadParameters() [2/2]

void mqtt_client::MqttClient::loadParameters ( )
protected

Loads ROS parameters from parameter server.

◆ message_arrived() [1/2]

void mqtt_client::MqttClient::message_arrived ( mqtt::const_message_ptr  mqtt_msg)
overrideprotected

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_msgMQTT message

◆ message_arrived() [2/2]

void mqtt_client::MqttClient::message_arrived ( mqtt::const_message_ptr  mqtt_msg)
overrideprotected

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_msgMQTT message

Definition at line 846 of file MqttClient.cpp.

◆ mqtt2primitive() [1/2]

void mqtt_client::MqttClient::mqtt2primitive ( mqtt::const_message_ptr  mqtt_msg)
protected

Publishes a primitive message received via MQTT to ROS.

Currently not implemented.

Parameters
mqtt_msgMQTT message

◆ mqtt2primitive() [2/2]

void mqtt_client::MqttClient::mqtt2primitive ( mqtt::const_message_ptr  mqtt_msg)
protected

Publishes a primitive message received via MQTT to ROS.

This tries to interpret the raw MQTT message as a bool, int, or float value in the given order before falling back to string. The message is then published as a corresponding primitive ROS message. This utilizes the ShapeShifter stored for the MQTT topic on which the message was received. The ShapeShifter is dynamically configured to the appropriate ROS message type.

The following mappings from primitive type to ROS message type hold: bool: std_msgs/Bool int: std_msgs/Int32 float: std_msgs/Float32 string: std_msgs/String

Parameters
mqtt_msgMQTT message

Definition at line 671 of file MqttClient.cpp.

◆ mqtt2ros() [1/2]

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

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_msgMQTT message
arrival_stamparrival timestamp used for latency computation

Definition at line 692 of file MqttClient.ros2.cpp.

◆ mqtt2ros() [2/2]

void mqtt_client::MqttClient::mqtt2ros ( mqtt::const_message_ptr  mqtt_msg,
const ros::WallTime arrival_stamp = ros::WallTime::now() 
)
protected

Publishes a ROS message received via MQTT to ROS.

This utilizes the ShapeShifter stored for the MQTT topic on which the message was received. The ShapeShifter 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_msgMQTT message
arrival_stamparrival timestamp used for latency computation

Definition at line 607 of file MqttClient.cpp.

◆ on_failure() [1/2]

void mqtt_client::MqttClient::on_failure ( const mqtt::token &  token)
overrideprotected

Callback for when a MQTT action fails.

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

Parameters
tokentoken tracking the action

◆ on_failure() [2/2]

void mqtt_client::MqttClient::on_failure ( const mqtt::token &  token)
overrideprotected

Callback for when a MQTT action fails.

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

Parameters
tokentoken tracking the action

Definition at line 940 of file MqttClient.cpp.

◆ on_success() [1/2]

void mqtt_client::MqttClient::on_success ( const mqtt::token &  token)
overrideprotected

Callback for when a MQTT action succeeds.

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

Parameters
tokentoken tracking the action

◆ on_success() [2/2]

void mqtt_client::MqttClient::on_success ( const mqtt::token &  token)
overrideprotected

Callback for when a MQTT action succeeds.

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

Parameters
tokentoken tracking the action

Definition at line 934 of file MqttClient.cpp.

◆ onInit()

void mqtt_client::MqttClient::onInit ( )
overrideprotectedvirtual

Initializes nodelet when nodelet is loaded.

Overrides nodelet::Nodelet::onInit().

Implements nodelet::Nodelet.

Definition at line 147 of file MqttClient.cpp.

◆ resolvePath() [1/2]

std::filesystem::path mqtt_client::MqttClient::resolvePath ( const std::string &  path_string)
protected

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

Definition at line 365 of file MqttClient.cpp.

◆ resolvePath() [2/2]

std::filesystem::path mqtt_client::MqttClient::resolvePath ( const std::string &  path_string)
protected

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

◆ ros2mqtt() [1/2]

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

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_msggeneric serialized ROS message
ros_topicROS topic where the message was published

Definition at line 573 of file MqttClient.ros2.cpp.

◆ ros2mqtt() [2/2]

void mqtt_client::MqttClient::ros2mqtt ( const topic_tools::ShapeShifter::ConstPtr ros_msg,
const std::string &  ros_topic 
)
protected

Serializes and publishes a generic ROS message to the MQTT broker.

Before serializing the ROS message and publishing it to the MQTT broker, metadata on 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
ros_msggeneric ROS message
ros_topicROS topic where the message was published

Definition at line 490 of file MqttClient.cpp.

◆ setup() [1/2]

void mqtt_client::MqttClient::setup ( )
protected

Initializes broker connection and subscriptions.

Definition at line 384 of file MqttClient.cpp.

◆ setup() [2/2]

void mqtt_client::MqttClient::setup ( )
protected

Initializes broker connection and subscriptions.

◆ setupClient() [1/2]

void mqtt_client::MqttClient::setupClient ( )
protected

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

Definition at line 410 of file MqttClient.cpp.

◆ setupClient() [2/2]

void mqtt_client::MqttClient::setupClient ( )
protected

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

◆ setupSubscriptions()

void mqtt_client::MqttClient::setupSubscriptions ( )
protected

Checks all active ROS topics in order to set up generic subscribers.

Definition at line 460 of file MqttClient.ros2.cpp.

Member Data Documentation

◆ broker_config_

BrokerConfig mqtt_client::MqttClient::broker_config_
protected

Broker parameters.

Definition at line 450 of file MqttClient.h.

◆ check_subscriptions_timer_

rclcpp::TimerBase::SharedPtr mqtt_client::MqttClient::check_subscriptions_timer_
protected

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

Definition at line 427 of file MqttClient.ros2.hpp.

◆ client_

std::shared_ptr< mqtt::async_client > mqtt_client::MqttClient::client_
protected

MQTT client variable.

Definition at line 460 of file MqttClient.h.

◆ client_config_

ClientConfig mqtt_client::MqttClient::client_config_
protected

Client parameters.

Definition at line 455 of file MqttClient.h.

◆ connect_options_

mqtt::connect_options mqtt_client::MqttClient::connect_options_
protected

MQTT client connection options.

Definition at line 465 of file MqttClient.h.

◆ is_connected_

bool mqtt_client::MqttClient::is_connected_ = false
protected

Status variable keeping track of connection status to broker.

Definition at line 445 of file MqttClient.h.

◆ is_connected_service_ [1/2]

rclcpp::Service<mqtt_client_interfaces::srv::IsConnected>::SharedPtr mqtt_client::MqttClient::is_connected_service_
protected

ROS Service server for providing connection status.

Definition at line 433 of file MqttClient.ros2.hpp.

◆ is_connected_service_ [2/2]

ros::ServiceServer mqtt_client::MqttClient::is_connected_service_
protected

ROS Service server for providing connection status.

Definition at line 440 of file MqttClient.h.

◆ kLatencyRosTopicPrefix

const std::string mqtt_client::MqttClient::kLatencyRosTopicPrefix = "latencies/"
staticprotected

ROS topic prefix under which ROS2MQTT2ROS latencies are published.

Must contain trailing '/'.

Definition at line 425 of file MqttClient.h.

◆ kRosMsgTypeMqttTopicPrefix

const std::string mqtt_client::MqttClient::kRosMsgTypeMqttTopicPrefix
staticprotected
Initial value:
=
"mqtt_client/ros_msg_type/"

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

Must contain trailing '/'.

Definition at line 418 of file MqttClient.h.

◆ mqtt2ros_

std::map< std::string, Mqtt2RosInterface > mqtt_client::MqttClient::mqtt2ros_
protected

MQTT2ROS connection variables sorted by MQTT topic.

Definition at line 475 of file MqttClient.h.

◆ node_handle_

ros::NodeHandle mqtt_client::MqttClient::node_handle_
protected

ROS node handle.

Definition at line 430 of file MqttClient.h.

◆ private_node_handle_

ros::NodeHandle mqtt_client::MqttClient::private_node_handle_
protected

Private ROS node handle.

Definition at line 435 of file MqttClient.h.

◆ ros2mqtt_

std::map< std::string, Ros2MqttInterface > mqtt_client::MqttClient::ros2mqtt_
protected

ROS2MQTT connection variables sorted by ROS topic.

Definition at line 470 of file MqttClient.h.

◆ stamp_length_

uint32_t mqtt_client::MqttClient::stamp_length_
protected

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

Definition at line 473 of file MqttClient.ros2.hpp.


The documentation for this class was generated from the following files:


mqtt_client
Author(s): Lennart Reiher , Bastian Lampe , Christian Wende
autogenerated on Thu Oct 5 2023 02:09:10