ROS Nodelet for sending and receiving ROS messages via MQTT. More...
#include <MqttClient.h>
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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () 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, Mqtt2RosInterface > | mqtt2ros_ |
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, Ros2MqttInterface > | ros2mqtt_ |
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... | |
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.
|
explicit |
Initializes node.
[in] | options | ROS node options |
Definition at line 144 of file MqttClient.ros2.cpp.
|
protected |
Connects to the broker using the member client and options.
Definition at line 472 of file MqttClient.cpp.
|
protected |
Connects to the broker using the member client and options.
|
overrideprotected |
Callback for when the client has successfully connected to the broker.
Overrides mqtt::callback::connected(const std::string&).
cause |
|
overrideprotected |
Callback for when the client has successfully connected to the broker.
Overrides mqtt::callback::connected(const std::string&).
cause |
Definition at line 801 of file MqttClient.cpp.
|
overrideprotected |
Callback for when the client has lost connection to the broker.
Overrides mqtt::callback::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&).
cause |
Definition at line 823 of file MqttClient.cpp.
|
overrideprotected |
Callback for when delivery for a MQTT message has been completed.
Overrides mqtt::callback::delivery_complete(mqtt::delivery_token_ptr).
token | token tracking the message delivery |
|
overrideprotected |
Callback for when delivery for a MQTT message has been completed.
Overrides mqtt::callback::delivery_complete(mqtt::delivery_token_ptr).
token | token tracking the message delivery |
Definition at line 931 of file MqttClient.cpp.
|
protected |
Returns whether the client is connected to the broker.
|
protected |
Returns whether the client is connected to the broker.
Definition at line 831 of file MqttClient.cpp.
|
protected |
ROS service returning whether the client is connected to the broker.
request | service request |
response | service response |
Definition at line 837 of file MqttClient.cpp.
|
protected |
ROS service returning whether the client is connected to the broker.
request | service request |
response | service response |
Definition at line 897 of file MqttClient.ros2.cpp.
|
protected |
Loads requested ROS parameter from parameter server.
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
Definition at line 339 of file MqttClient.cpp.
|
protected |
Loads requested ROS parameter from parameter server.
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
Definition at line 348 of file MqttClient.cpp.
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
|
protected |
Loads requested ROS parameter from parameter server.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
Definition at line 507 of file MqttClient.h.
|
protected |
Loads requested ROS parameter from parameter server.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
Definition at line 518 of file MqttClient.h.
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
|
protected |
Loads requested ROS parameter from parameter server.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
Definition at line 480 of file MqttClient.h.
|
protected |
Loads requested ROS parameter from parameter server.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
Definition at line 490 of file MqttClient.h.
|
protected |
Loads requested ROS parameter from parameter server, allows default value.
T | type (one of int, double, bool) |
[in] | key | parameter name |
[out] | value | variable where to store the retrieved parameter |
[in] | default_value | default value |
|
protected |
Loads ROS parameters from parameter server.
Definition at line 158 of file MqttClient.cpp.
|
protected |
Loads ROS parameters from parameter server.
|
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.
mqtt_msg | MQTT message |
|
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.
mqtt_msg | MQTT message |
Definition at line 846 of file MqttClient.cpp.
|
protected |
Publishes a primitive message received via MQTT to ROS.
Currently not implemented.
mqtt_msg | MQTT message |
|
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
mqtt_msg | MQTT message |
Definition at line 671 of file MqttClient.cpp.
|
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:
mqtt_msg | MQTT message |
arrival_stamp | arrival timestamp used for latency computation |
Definition at line 692 of file MqttClient.ros2.cpp.
|
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:
mqtt_msg | MQTT message |
arrival_stamp | arrival timestamp used for latency computation |
Definition at line 607 of file MqttClient.cpp.
|
overrideprotected |
Callback for when a MQTT action fails.
Overrides mqtt::iaction_listener::on_failure(const mqtt::token&). Logs error.
token | token tracking the action |
|
overrideprotected |
Callback for when a MQTT action fails.
Overrides mqtt::iaction_listener::on_failure(const mqtt::token&). Logs error.
token | token tracking the action |
Definition at line 940 of file MqttClient.cpp.
|
overrideprotected |
Callback for when a MQTT action succeeds.
Overrides mqtt::iaction_listener::on_success(const mqtt::token&). Does nothing.
token | token tracking the action |
|
overrideprotected |
Callback for when a MQTT action succeeds.
Overrides mqtt::iaction_listener::on_success(const mqtt::token&). Does nothing.
token | token tracking the action |
Definition at line 934 of file MqttClient.cpp.
|
overrideprotectedvirtual |
Initializes nodelet when nodelet is loaded.
Overrides nodelet::Nodelet::onInit().
Implements nodelet::Nodelet.
Definition at line 147 of file MqttClient.cpp.
|
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.
path_string | (relative) path as string |
Definition at line 365 of file MqttClient.cpp.
|
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.
path_string | (relative) path as string |
|
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:
serialized_msg | generic serialized ROS message |
ros_topic | ROS topic where the message was published |
Definition at line 573 of file MqttClient.ros2.cpp.
|
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:
ros_msg | generic ROS message |
ros_topic | ROS topic where the message was published |
Definition at line 490 of file MqttClient.cpp.
|
protected |
Initializes broker connection and subscriptions.
Definition at line 384 of file MqttClient.cpp.
|
protected |
Initializes broker connection and subscriptions.
|
protected |
Sets up the client connection options and initializes the client object.
Definition at line 410 of file MqttClient.cpp.
|
protected |
Sets up the client connection options and initializes the client object.
|
protected |
Checks all active ROS topics in order to set up generic subscribers.
Definition at line 460 of file MqttClient.ros2.cpp.
|
protected |
Broker parameters.
Definition at line 450 of file MqttClient.h.
|
protected |
Timer to repeatedly check active ROS topics for topics to subscribe.
Definition at line 427 of file MqttClient.ros2.hpp.
|
protected |
MQTT client variable.
Definition at line 460 of file MqttClient.h.
|
protected |
Client parameters.
Definition at line 455 of file MqttClient.h.
|
protected |
MQTT client connection options.
Definition at line 465 of file MqttClient.h.
|
protected |
Status variable keeping track of connection status to broker.
Definition at line 445 of file MqttClient.h.
|
protected |
ROS Service server for providing connection status.
Definition at line 433 of file MqttClient.ros2.hpp.
|
protected |
ROS Service server for providing connection status.
Definition at line 440 of file MqttClient.h.
|
staticprotected |
ROS topic prefix under which ROS2MQTT2ROS latencies are published.
Must contain trailing '/'.
Definition at line 425 of file MqttClient.h.
|
staticprotected |
MQTT topic prefix under which ROS message type information is published.
Must contain trailing '/'.
Definition at line 418 of file MqttClient.h.
|
protected |
MQTT2ROS connection variables sorted by MQTT topic.
Definition at line 475 of file MqttClient.h.
|
protected |
ROS node handle.
Definition at line 430 of file MqttClient.h.
|
protected |
Private ROS node handle.
Definition at line 435 of file MqttClient.h.
|
protected |
ROS2MQTT connection variables sorted by ROS topic.
Definition at line 470 of file MqttClient.h.
|
protected |
Message length of a serialized builtin_interfaces::msg::Time
message
Definition at line 473 of file MqttClient.ros2.hpp.