Go to the documentation of this file.
35 #define FMT_HEADER_ONLY
36 #include <fmt/format.h>
37 #include <mqtt_client_interfaces/srv/is_connected.hpp>
38 #include <mqtt/async_client.h>
39 #include <rclcpp/rclcpp.hpp>
40 #include <rclcpp/serialization.hpp>
41 #include <std_msgs/msg/float64.hpp>
59 class MqttClient :
public rclcpp::Node,
60 public virtual mqtt::callback,
61 public virtual mqtt::iaction_listener {
69 explicit MqttClient(
const rclcpp::NodeOptions& options);
86 bool loadParameter(
const std::string& key, std::string& value);
99 bool loadParameter(
const std::string& key, std::string& value,
113 template <
typename T>
129 template <
typename T>
143 template <
typename T>
144 bool loadParameter(
const std::string& key, std::vector<T>& value);
159 template <
typename T>
173 std::filesystem::path
resolvePath(
const std::string& path_string);
212 const std::shared_ptr<rclcpp::SerializedMessage>& serialized_msg,
213 const std::string& ros_topic);
231 void mqtt2ros(mqtt::const_message_ptr mqtt_msg,
232 const rclcpp::Time& arrival_stamp);
251 void connected(
const std::string& cause)
override;
277 mqtt_client_interfaces::srv::IsConnected::Request::SharedPtr request,
278 mqtt_client_interfaces::srv::IsConnected::Response::SharedPtr
response);
310 void on_success(
const mqtt::token& token)
override;
320 void on_failure(
const mqtt::token& token)
override;
326 struct BrokerConfig {
333 std::filesystem::path
341 struct ClientConfig {
359 std::filesystem::path
key;
371 struct Ros2MqttInterface {
373 rclcpp::GenericSubscription::SharedPtr
390 struct Mqtt2RosInterface {
398 rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr
432 rclcpp::Service<mqtt_client_interfaces::srv::IsConnected>::SharedPtr
453 std::shared_ptr<mqtt::async_client>
client_;
463 std::map<std::string, Ros2MqttInterface>
ros2mqtt_;
468 std::map<std::string, Mqtt2RosInterface>
mqtt2ros_;
477 template <
typename T>
479 bool found = get_parameter(key, value);
481 RCLCPP_DEBUG(get_logger(),
"Retrieved parameter '%s' = '%s'", key.c_str(),
482 std::to_string(value).c_str());
487 template <
typename T>
489 const T& default_value) {
490 bool found = get_parameter_or(key, value, default_value);
492 RCLCPP_WARN(get_logger(),
"Parameter '%s' not set, defaulting to '%s'",
493 key.c_str(), std::to_string(default_value).c_str());
495 RCLCPP_DEBUG(get_logger(),
"Retrieved parameter '%s' = '%s'", key.c_str(),
496 std::to_string(value).c_str());
501 template <
typename T>
504 const bool found = get_parameter(key, value);
506 RCLCPP_WARN(get_logger(),
"Retrieved parameter '%s' = '[%s]'", key.c_str(),
507 fmt::format(
"{}", fmt::join(value,
", ")).c_str());
512 template <
typename T>
514 const std::vector<T>& default_value)
516 const bool found = get_parameter_or(key, value, default_value);
518 RCLCPP_WARN(get_logger(),
"Parameter '%s' not set, defaulting to '%s'",
519 key.c_str(), fmt::format(
"{}", fmt::join(value,
", ")).c_str());
521 RCLCPP_DEBUG(get_logger(),
"Retrieved parameter '%s' = '%s'", key.c_str(),
522 fmt::format(
"{}", fmt::join(value,
", ")).c_str());
535 template <
typename T>
537 rclcpp::SerializedMessage& serialized_msg) {
539 rclcpp::Serialization<T> serializer;
540 serializer.serialize_message(&msg, &serialized_msg);
552 template <
typename T>
556 rclcpp::Serialization<T> serializer;
557 serializer.deserialize_message(&serialized_msg, &msg);
int qos
last-will QoS value
int size
client buffer size
const std::string response
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.
struct mqtt_client::MqttClient::Ros2MqttInterface::@4 ros
ROS-related variables.
std::string password
decryption password for private key
rclcpp::GenericSubscription::SharedPtr subscriber
generic ROS subscriber
void setupClient()
Sets up the client connection options and initializes the client object.
void on_success(const mqtt::token &token) override
Callback for when a MQTT action succeeds.
std::filesystem::path resolvePath(const std::string &path_string)
Converts a string to a path object resolving paths relative to ROS_HOME.
Struct containing client parameters.
rclcpp::Service< mqtt_client_interfaces::srv::IsConnected >::SharedPtr is_connected_service_
ROS Service server for providing connection status.
void mqtt2primitive(mqtt::const_message_ptr mqtt_msg)
Publishes a primitive message received via MQTT to ROS.
std::string msg_type
message type of subscriber
void on_failure(const mqtt::token &token) override
Callback for when a MQTT action fails.
struct mqtt_client::MqttClient::Mqtt2RosInterface::@6 mqtt
MQTT-related variables.
void delivery_complete(mqtt::delivery_token_ptr token) override
Callback for when delivery for a MQTT message has been completed.
bool is_connected_
Status variable keeping track of connection status to broker.
rclcpp::TimerBase::SharedPtr check_subscriptions_timer_
Timer to repeatedly check active ROS topics for topics to subscribe.
std::filesystem::path key
client private keyfile
int max_inflight
maximum number of inflight messages
struct mqtt_client::MqttClient::ClientConfig::@1 buffer
client buffer-related variables
bool loadParameter(const std::string &key, std::string &value)
Loads requested ROS parameter from parameter server.
ClientConfig client_config_
Client parameters.
struct mqtt_client::MqttClient::ClientConfig::@3 tls
SSL/TLS-related variables.
std::shared_ptr< mqtt::async_client > client_
MQTT client variable.
std::string message
last-will message
int version
TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options....
std::string msg_type
message type of publisher
std::string topic
last-will topic
static const std::string kRosMsgTypeMqttTopicPrefix
MQTT topic prefix under which ROS message type information is published.
bool clean_session
whether client requests clean session
rclcpp::Publisher< std_msgs::msg::Float64 >::SharedPtr latency_publisher
ROS publisher for latency.
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.
struct mqtt_client::MqttClient::ClientConfig::@2 last_will
last-will-related variables
struct mqtt_client::MqttClient::Mqtt2RosInterface::@7 ros
ROS-related variables.
std::filesystem::path directory
client buffer directory
std::string topic
ROS topic.
mqtt::connect_options connect_options_
MQTT client connection options.
bool primitive
whether to publish as primitive message
void setupSubscriptions()
Checks all active ROS topics in order to set up generic subscribers.
std::vector< std::string > alpn_protos
list of ALPN protocols
void message_arrived(mqtt::const_message_ptr mqtt_msg) override
Callback for when the client receives a MQTT message from the broker.
void connected(const std::string &cause) override
Callback for when the client has successfully connected to the broker.
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.
BrokerConfig broker_config_
Broker parameters.
static const std::string kLatencyRosTopicPrefix
ROS topic prefix under which ROS2MQTT2ROS latencies are published.
std::map< std::string, Mqtt2RosInterface > mqtt2ros_
MQTT2ROS connection variables sorted by MQTT topic.
std::filesystem::path certificate
client certificate
bool enabled
whether client buffer is enabled
MqttClient(const rclcpp::NodeOptions &options)
Initializes node.
bool stamped
whether timestamp is injected
std::map< std::string, Ros2MqttInterface > ros2mqtt_
ROS2MQTT connection variables sorted by ROS topic.
void setup()
Initializes broker connection and subscriptions.
void connection_lost(const std::string &cause) override
Callback for when the client has lost connection to the broker.
bool stamped
whether to inject timestamp in MQTT message
struct mqtt_client::MqttClient::Ros2MqttInterface::@5 mqtt
MQTT-related variables.
void deserializeRosMessage(const rclcpp::SerializedMessage &serialized_msg, T &msg)
std::filesystem::path ca_certificate
public CA certificate trusted by client
double keep_alive_interval
keep-alive interval
std::string topic
MQTT topic.
bool latched
whether to latch ROS message
int queue_size
ROS publisher queue size.
std::string host
broker host
void connect()
Connects to the broker using the member client and options.
void serializeRosMessage(const T &msg, std::vector< uint8_t > &buffer)
rclcpp::GenericPublisher::SharedPtr publisher
generic ROS publisher
std::string id
client unique ID
int queue_size
ROS subscriber queue size.
bool enabled
whether to connect via SSL/TLS
struct mqtt_client::MqttClient::BrokerConfig::@0 tls
SSL/TLS-related variables.
bool isConnected()
Returns whether the client is connected to the broker.
Namespace for the mqtt_client package.
Struct containing broker parameters.
bool retained
whether last-will is retained
void loadParameters()
Loads ROS parameters from parameter server.
bool retained
whether to retain MQTT message
mqtt_client
Author(s): Lennart Reiher
, Bastian Lampe , Christian Wende
autogenerated on Thu Oct 5 2023 02:09:10