Skip to content

Commit 8ed75d1

Browse files
committed
Added the ability to explicitly set type names and some QoS settings for Mqtt -> ROS
1 parent 8ac97d0 commit 8ed75d1

File tree

3 files changed

+303
-33
lines changed

3 files changed

+303
-33
lines changed
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
/**/*:
2+
ros__parameters:
3+
broker:
4+
host: localhost
5+
port: 1883
6+
bridge:
7+
ros2mqtt:
8+
ros_topics:
9+
- /ping/primitive
10+
/ping/primitive:
11+
mqtt_topic: pingpong/primitive
12+
primitive: true
13+
ros_type: std_msgs/msg/Bool
14+
mqtt2ros:
15+
mqtt_topics:
16+
- pingpong/primitive
17+
pingpong/primitive:
18+
ros_topic: /pong/primitive
19+
primitive: true
20+
ros_type: std_msgs/msg/Bool

mqtt_client/include/mqtt_client/MqttClient.ros2.hpp

Lines changed: 42 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -34,12 +34,13 @@ SOFTWARE.
3434

3535
#define FMT_HEADER_ONLY
3636
#include <fmt/format.h>
37+
#include <mqtt/async_client.h>
3738
#include <mqtt_client_interfaces/srv/is_connected.hpp>
3839
#include <mqtt_client_interfaces/srv/new_mqtt2_ros_bridge.hpp>
3940
#include <mqtt_client_interfaces/srv/new_ros2_mqtt_bridge.hpp>
40-
#include <mqtt/async_client.h>
4141
#include <rclcpp/rclcpp.hpp>
4242
#include <rclcpp/serialization.hpp>
43+
#include <rclcpp/qos.hpp>
4344
#include <std_msgs/msg/float64.hpp>
4445

4546

@@ -98,8 +99,7 @@ class MqttClient : public rclcpp::Node,
9899
* @return true if parameter was successfully retrieved
99100
* @return false if parameter was not found or default was used
100101
*/
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);
103103

104104
/**
105105
* @brief Loads requested ROS parameter from parameter server.
@@ -242,6 +242,15 @@ class MqttClient : public rclcpp::Node,
242242
*/
243243
void mqtt2primitive(mqtt::const_message_ptr mqtt_msg);
244244

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+
245254
/**
246255
* @brief Callback for when the client has successfully connected to the
247256
* broker.
@@ -351,10 +360,9 @@ class MqttClient : public rclcpp::Node,
351360
std::string user; ///< username
352361
std::string pass; ///< password
353362
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
358366
};
359367

360368
/**
@@ -377,14 +385,14 @@ class MqttClient : public rclcpp::Node,
377385
double keep_alive_interval; ///< keep-alive interval
378386
int max_inflight; ///< maximum number of inflight messages
379387
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
388396
};
389397

390398
/**
@@ -403,6 +411,7 @@ class MqttClient : public rclcpp::Node,
403411
int qos = 0; ///< MQTT QoS value
404412
bool retained = false; ///< whether to retain MQTT message
405413
} mqtt; ///< MQTT-related variables
414+
bool fixed_type = false; ///< whether the published message type is specified explicitly
406415
bool primitive = false; ///< whether to publish as primitive message
407416
bool stamped = false; ///< whether to inject timestamp in MQTT message
408417
};
@@ -412,18 +421,23 @@ class MqttClient : public rclcpp::Node,
412421
*/
413422
struct Mqtt2RosInterface {
414423
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
417426
struct {
418427
std::string topic; ///< ROS topic
419428
std::string msg_type; ///< message type of publisher
420429
rclcpp::GenericPublisher::SharedPtr publisher; ///< generic ROS publisher
421430
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr
422431
latency_publisher; ///< ROS publisher for latency
423432
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;
424437
bool latched = false; ///< whether to latch ROS message
425438
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
427441
bool primitive = false; ///< whether to publish as primitive message (if
428442
///< coming from non-ROS MQTT client)
429443
bool stamped = false; ///< whether timestamp is injected
@@ -511,7 +525,8 @@ class MqttClient : public rclcpp::Node,
511525

512526

513527
template <typename T>
514-
bool MqttClient::loadParameter(const std::string& key, T& value) {
528+
bool MqttClient::loadParameter(const std::string& key, T& value)
529+
{
515530
bool found = get_parameter(key, value);
516531
if (found)
517532
RCLCPP_DEBUG(get_logger(), "Retrieved parameter '%s' = '%s'", key.c_str(),
@@ -522,7 +537,8 @@ bool MqttClient::loadParameter(const std::string& key, T& value) {
522537

523538
template <typename T>
524539
bool MqttClient::loadParameter(const std::string& key, T& value,
525-
const T& default_value) {
540+
const T& default_value)
541+
{
526542
bool found = get_parameter_or(key, value, default_value);
527543
if (!found)
528544
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)
540556
const bool found = get_parameter(key, value);
541557
if (found)
542558
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());
544560
return found;
545561
}
546562

@@ -555,7 +571,7 @@ bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
555571
key.c_str(), fmt::format("{}", fmt::join(value, ", ")).c_str());
556572
if (found)
557573
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());
559575
return found;
560576
}
561577

@@ -570,7 +586,8 @@ bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
570586
*/
571587
template <typename T>
572588
void serializeRosMessage(const T& msg,
573-
rclcpp::SerializedMessage& serialized_msg) {
589+
rclcpp::SerializedMessage& serialized_msg)
590+
{
574591

575592
rclcpp::Serialization<T> serializer;
576593
serializer.serialize_message(&msg, &serialized_msg);
@@ -587,7 +604,8 @@ void serializeRosMessage(const T& msg,
587604
*/
588605
template <typename T>
589606
void deserializeRosMessage(const rclcpp::SerializedMessage& serialized_msg,
590-
T& msg) {
607+
T& msg)
608+
{
591609

592610
rclcpp::Serialization<T> serializer;
593611
serializer.deserialize_message(&serialized_msg, &msg);

0 commit comments

Comments
 (0)