@@ -34,12 +34,13 @@ SOFTWARE.
34
34
35
35
#define FMT_HEADER_ONLY
36
36
#include < fmt/format.h>
37
+ #include < mqtt/async_client.h>
37
38
#include < mqtt_client_interfaces/srv/is_connected.hpp>
38
39
#include < mqtt_client_interfaces/srv/new_mqtt2_ros_bridge.hpp>
39
40
#include < mqtt_client_interfaces/srv/new_ros2_mqtt_bridge.hpp>
40
- #include < mqtt/async_client.h>
41
41
#include < rclcpp/rclcpp.hpp>
42
42
#include < rclcpp/serialization.hpp>
43
+ #include < rclcpp/qos.hpp>
43
44
#include < std_msgs/msg/float64.hpp>
44
45
45
46
@@ -98,8 +99,7 @@ class MqttClient : public rclcpp::Node,
98
99
* @return true if parameter was successfully retrieved
99
100
* @return false if parameter was not found or default was used
100
101
*/
101
- bool loadParameter (const std::string& key, std::string& value,
102
- const std::string& default_value);
102
+ bool loadParameter (const std::string& key, std::string& value, const std::string& default_value);
103
103
104
104
/* *
105
105
* @brief Loads requested ROS parameter from parameter server.
@@ -242,6 +242,15 @@ class MqttClient : public rclcpp::Node,
242
242
*/
243
243
void mqtt2primitive (mqtt::const_message_ptr mqtt_msg);
244
244
245
+ /* *
246
+ * @brief Publishes a primitive message received via MQTT to ROS.
247
+ *
248
+ * Currently not implemented.
249
+ *
250
+ * @param mqtt_msg MQTT message
251
+ */
252
+ void mqtt2fixed (mqtt::const_message_ptr mqtt_msg);
253
+
245
254
/* *
246
255
* @brief Callback for when the client has successfully connected to the
247
256
* broker.
@@ -351,10 +360,9 @@ class MqttClient : public rclcpp::Node,
351
360
std::string user; // /< username
352
361
std::string pass; // /< password
353
362
struct {
354
- bool enabled; // /< whether to connect via SSL/TLS
355
- std::filesystem::path
356
- ca_certificate; // /< public CA certificate trusted by client
357
- } tls; // /< SSL/TLS-related variables
363
+ bool enabled; // /< whether to connect via SSL/TLS
364
+ std::filesystem::path ca_certificate; // /< public CA certificate trusted by client
365
+ } tls; // /< SSL/TLS-related variables
358
366
};
359
367
360
368
/* *
@@ -377,14 +385,14 @@ class MqttClient : public rclcpp::Node,
377
385
double keep_alive_interval; // /< keep-alive interval
378
386
int max_inflight; // /< maximum number of inflight messages
379
387
struct {
380
- std::filesystem::path certificate; // /< client certificate
381
- std::filesystem::path key; // /< client private keyfile
382
- std::string password; // /< decryption password for private key
383
- int version; // /< TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
384
- bool verify; // /< Verify the client should conduct
385
- // /< post-connect checks
386
- std::vector<std::string> alpn_protos; // /< list of ALPN protocols
387
- } tls; // /< SSL/TLS-related variables
388
+ std::filesystem::path certificate; // /< client certificate
389
+ std::filesystem::path key; // /< client private keyfile
390
+ std::string password; // /< decryption password for private key
391
+ int version; // /< TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
392
+ bool verify; // /< Verify the client should conduct
393
+ // /< post-connect checks
394
+ std::vector<std::string> alpn_protos; // /< list of ALPN protocols
395
+ } tls; // /< SSL/TLS-related variables
388
396
};
389
397
390
398
/* *
@@ -403,6 +411,7 @@ class MqttClient : public rclcpp::Node,
403
411
int qos = 0 ; // /< MQTT QoS value
404
412
bool retained = false ; // /< whether to retain MQTT message
405
413
} mqtt; // /< MQTT-related variables
414
+ bool fixed_type = false ; // /< whether the published message type is specified explicitly
406
415
bool primitive = false ; // /< whether to publish as primitive message
407
416
bool stamped = false ; // /< whether to inject timestamp in MQTT message
408
417
};
@@ -412,18 +421,23 @@ class MqttClient : public rclcpp::Node,
412
421
*/
413
422
struct Mqtt2RosInterface {
414
423
struct {
415
- int qos = 0 ; // /< MQTT QoS value
416
- } mqtt; // /< MQTT-related variables
424
+ int qos = 0 ; // /< MQTT QoS value
425
+ } mqtt; // /< MQTT-related variables
417
426
struct {
418
427
std::string topic; // /< ROS topic
419
428
std::string msg_type; // /< message type of publisher
420
429
rclcpp::GenericPublisher::SharedPtr publisher; // /< generic ROS publisher
421
430
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr
422
431
latency_publisher; // /< ROS publisher for latency
423
432
int queue_size = 1 ; // /< ROS publisher queue size
433
+ struct {
434
+ rclcpp::ReliabilityPolicy reliability = rclcpp::ReliabilityPolicy::SystemDefault;
435
+ rclcpp::DurabilityPolicy durability = rclcpp::DurabilityPolicy::SystemDefault;
436
+ } qos;
424
437
bool latched = false ; // /< whether to latch ROS message
425
438
bool is_stale = false ; // /< whether a new generic publisher/subscriber is required
426
- } ros; // /< ROS-related variables
439
+ } ros; // /< ROS-related variables
440
+ bool fixed_type = false ; // /< whether the published ros message type is specified explicitly
427
441
bool primitive = false ; // /< whether to publish as primitive message (if
428
442
// /< coming from non-ROS MQTT client)
429
443
bool stamped = false ; // /< whether timestamp is injected
@@ -511,7 +525,8 @@ class MqttClient : public rclcpp::Node,
511
525
512
526
513
527
template <typename T>
514
- bool MqttClient::loadParameter (const std::string& key, T& value) {
528
+ bool MqttClient::loadParameter (const std::string& key, T& value)
529
+ {
515
530
bool found = get_parameter (key, value);
516
531
if (found)
517
532
RCLCPP_DEBUG (get_logger (), " Retrieved parameter '%s' = '%s'" , key.c_str (),
@@ -522,7 +537,8 @@ bool MqttClient::loadParameter(const std::string& key, T& value) {
522
537
523
538
template <typename T>
524
539
bool MqttClient::loadParameter (const std::string& key, T& value,
525
- const T& default_value) {
540
+ const T& default_value)
541
+ {
526
542
bool found = get_parameter_or (key, value, default_value);
527
543
if (!found)
528
544
RCLCPP_WARN (get_logger (), " Parameter '%s' not set, defaulting to '%s'" ,
@@ -540,7 +556,7 @@ bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value)
540
556
const bool found = get_parameter (key, value);
541
557
if (found)
542
558
RCLCPP_WARN (get_logger (), " Retrieved parameter '%s' = '[%s]'" , key.c_str (),
543
- fmt::format (" {}" , fmt::join (value, " , " )).c_str ());
559
+ fmt::format (" {}" , fmt::join (value, " , " )).c_str ());
544
560
return found;
545
561
}
546
562
@@ -555,7 +571,7 @@ bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
555
571
key.c_str (), fmt::format (" {}" , fmt::join (value, " , " )).c_str ());
556
572
if (found)
557
573
RCLCPP_DEBUG (get_logger (), " Retrieved parameter '%s' = '%s'" , key.c_str (),
558
- fmt::format (" {}" , fmt::join (value, " , " )).c_str ());
574
+ fmt::format (" {}" , fmt::join (value, " , " )).c_str ());
559
575
return found;
560
576
}
561
577
@@ -570,7 +586,8 @@ bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
570
586
*/
571
587
template <typename T>
572
588
void serializeRosMessage (const T& msg,
573
- rclcpp::SerializedMessage& serialized_msg) {
589
+ rclcpp::SerializedMessage& serialized_msg)
590
+ {
574
591
575
592
rclcpp::Serialization<T> serializer;
576
593
serializer.serialize_message (&msg, &serialized_msg);
@@ -587,7 +604,8 @@ void serializeRosMessage(const T& msg,
587
604
*/
588
605
template <typename T>
589
606
void deserializeRosMessage (const rclcpp::SerializedMessage& serialized_msg,
590
- T& msg) {
607
+ T& msg)
608
+ {
591
609
592
610
rclcpp::Serialization<T> serializer;
593
611
serializer.deserialize_message (&serialized_msg, &msg);
0 commit comments