Skip to content

Commit 786b4ed

Browse files
committed
Merge remote-tracking branch 'upstream/main' into ros2-add-multiple-topics
2 parents 817ff55 + 463e501 commit 786b4ed

File tree

10 files changed

+249
-15
lines changed

10 files changed

+249
-15
lines changed

.github/workflows/docker-ros.yml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ jobs:
1414
command: roslaunch mqtt_client standalone.launch
1515
platform: amd64,arm64
1616
target: run
17-
17+
1818
ros2:
1919
runs-on: ubuntu-latest
2020
steps:
@@ -26,4 +26,3 @@ jobs:
2626
platform: amd64,arm64
2727
target: run
2828
enable-push-as-latest: 'true'
29-

README.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -254,6 +254,9 @@ client:
254254
certificate: # client certificate file (only needed if broker requires client certificates; relative to ROS_HOME)
255255
key: # client private key file (relative to ROS_HOME)
256256
password: # client private key password
257+
version: # TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
258+
verify: # verify the client should conduct post-connect checks.
259+
alpn_protos: # list of ALPN protocols (https://www.openssl.org/docs/man1.1.1/man3/SSL_CTX_set_alpn_protos.html)
257260
```
258261
259262
#### Bridge Parameters

mqtt_client/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,7 @@ elseif(${ROS_VERSION} EQUAL 1)
8484
mqtt_client_interfaces
8585
nodelet
8686
roscpp
87+
rosfmt ## For fmt::format.
8788
std_msgs
8889
topic_tools
8990
)

mqtt_client/config/params.aws.yaml

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
# YAML alias for MQTT SSL version.
2+
# The supported values are defined at:
3+
# https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305
4+
tls_1_2: &tls_1_2 3
5+
6+
broker:
7+
# YOU MUST CHANGE THIS ENDPOINT
8+
# Can be found by executing: aws iot describe-endpoint
9+
host: not-a-real-endpoint-please-use-your-own.us-west-2.amazonaws.com
10+
port: 8883
11+
tls:
12+
enabled: true
13+
# Available at https://www.amazontrust.com/repository/AmazonRootCA1.pem
14+
ca_certificate: path/to/AmazonRootCA1.pem
15+
client:
16+
id: user
17+
# Whether or not to start a clean session with each reconnect.
18+
# If True, the server will forget all subscriptions with each reconnect.
19+
# Set False to request that the server resume an existing session or start
20+
# a new session that may be resumed after a connection loss.
21+
clean_session: false
22+
# The keep alive value, in seconds, to send in CONNECT packet.
23+
keep_alive_interval: 6.0
24+
tls:
25+
# The certificate generated by the AWS IoT Core service
26+
certificate: path/to/a-certificate.pem
27+
# The private key generated by the AWS IoT Core service
28+
key: path/to/a-private-key.pem
29+
# AWS uses TLS v1.2 to encrypt all communication.
30+
version: *tls_1_2
31+
verify: true
32+
# https://www.openssl.org/docs/man1.1.1/man3/SSL_CTX_set_alpn_protos.html
33+
alpn_protos:
34+
# MQTT over AWS IOT requires an ALPN protocol negotiation.
35+
# https://docs.aws.amazon.com/iot/latest/developerguide/protocols.html
36+
- x-amzn-mqtt-ca
37+
buffer:
38+
enabled: true
39+
bridge:
40+
# NOTE: It seems that AWS IOT only supports primitive topics. Using non-primitive
41+
# types results in the error message `Connection to broker lost, will try to reconnect...`
42+
ros2mqtt:
43+
- ros_topic: /ping/primitive
44+
mqtt_topic: pingpong/primitive
45+
primitive: true
46+
mqtt2ros:
47+
- mqtt_topic: pingpong/primitive
48+
ros_topic: /pong/primitive
49+
primitive: true
Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
mqtt_client:
2+
ros__parameters:
3+
broker:
4+
# YOU MUST CHANGE THIS ENDPOINT
5+
# Can be found by executing: aws iot describe-endpoint
6+
host: not-a-real-endpoint-please-use-your-own.us-west-2.amazonaws.com
7+
port: 8883
8+
tls:
9+
enabled: true
10+
# Available at https://www.amazontrust.com/repository/AmazonRootCA1.pem
11+
ca_certificate: path/to/AmazonRootCA1.pem
12+
client:
13+
id: user
14+
# Whether or not to start a clean session with each reconnect.
15+
# If True, the server will forget all subscriptions with each reconnect.
16+
# Set False to request that the server resume an existing session or start
17+
# a new session that may be resumed after a connection loss.
18+
clean_session: false
19+
# The keep alive value, in seconds, to send in CONNECT packet.
20+
keep_alive_interval: 6.0
21+
tls:
22+
# The certificate generated by the AWS IoT Core service
23+
certificate: path/to/a-certificate.pem
24+
# The private key generated by the AWS IoT Core service
25+
key: path/to/a-private-key.pem
26+
# AWS uses TLS v1.2 to encrypt all communication.
27+
# The supported values are defined at:
28+
# https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305
29+
version: 3 # TLS v1.2
30+
verify: true
31+
# https://www.openssl.org/docs/man1.1.1/man3/SSL_CTX_set_alpn_protos.html
32+
alpn_protos:
33+
# MQTT over AWS IOT requires an ALPN protocol negotiation.
34+
# https://docs.aws.amazon.com/iot/latest/developerguide/protocols.html
35+
- x-amzn-mqtt-ca
36+
buffer:
37+
enabled: true
38+
bridge:
39+
# NOTE: It seems that AWS IOT only supports primitive topics. Using non-primitive
40+
# types results in the error message `Connection to broker lost, will try to reconnect...`
41+
ros2mqtt:
42+
ros_topic: /ping/primitive
43+
mqtt_topic: pingpong/primitive
44+
primitive: true
45+
mqtt2ros:
46+
mqtt_topic: pingpong/primitive
47+
ros_topic: /pong/primitive
48+
primitive: true

mqtt_client/include/mqtt_client/MqttClient.h

Lines changed: 65 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,11 @@ SOFTWARE.
3232
#include <memory>
3333
#include <string>
3434

35-
#include <mqtt/async_client.h>
3635
#include <mqtt_client_interfaces/IsConnected.h>
36+
#include <mqtt/async_client.h>
3737
#include <nodelet/nodelet.h>
3838
#include <ros/ros.h>
39+
#include <rosfmt/full.h> // fmt::format, fmt::join
3940
#include <topic_tools/shape_shifter.h>
4041

4142

@@ -126,6 +127,36 @@ class MqttClient : public nodelet::Nodelet,
126127
template <typename T>
127128
bool loadParameter(const std::string& key, T& value, const T& default_value);
128129

130+
/**
131+
* @brief Loads requested ROS parameter from parameter server.
132+
*
133+
* @tparam T type (one of int, double, bool)
134+
*
135+
* @param[in] key parameter name
136+
* @param[out] value variable where to store the retrieved parameter
137+
*
138+
* @return true if parameter was successfully retrieved
139+
* @return false if parameter was not found
140+
*/
141+
template <typename T>
142+
bool loadParameter(const std::string& key, std::vector<T>& value);
143+
144+
/**
145+
* @brief Loads requested ROS parameter from parameter server, allows default
146+
* value.
147+
*
148+
* @tparam T type (one of int, double, bool)
149+
*
150+
* @param[in] key parameter name
151+
* @param[out] value variable where to store the retrieved parameter
152+
* @param[in] default_value default value
153+
*
154+
* @return true if parameter was successfully retrieved
155+
* @return false if parameter was not found or default was used
156+
*/
157+
template <typename T>
158+
bool loadParameter(const std::string& key, std::vector<T>& value, const std::vector<T>& default_value);
159+
129160
/**
130161
* @brief Converts a string to a path object resolving paths relative to
131162
* ROS_HOME.
@@ -330,9 +361,13 @@ class MqttClient : public nodelet::Nodelet,
330361
double keep_alive_interval; ///< keep-alive interval
331362
int max_inflight; ///< maximum number of inflight messages
332363
struct {
333-
std::filesystem::path certificate; ///< client certificate
334-
std::filesystem::path key; ///< client private keyfile
335-
std::string password; ///< decryption password for private key
364+
std::filesystem::path certificate; ///< client certificate
365+
std::filesystem::path key; ///< client private keyfile
366+
std::string password; ///< decryption password for private key
367+
int version; ///< TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
368+
bool verify; ///< Verify the client should conduct
369+
///< post-connect checks
370+
std::vector<std::string> alpn_protos; ///< list of ALPN protocols
336371
} tls; ///< SSL/TLS-related variables
337372
};
338373

@@ -468,6 +503,32 @@ bool MqttClient::loadParameter(const std::string& key, T& value,
468503
}
469504

470505

506+
template <typename T>
507+
bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value)
508+
{
509+
const bool found = private_node_handle_.getParam(key, value);
510+
if (found)
511+
NODELET_DEBUG("Retrieved parameter '%s' = '[%s]'", key.c_str(),
512+
fmt::format("{}", fmt::join(value, ", ")).c_str());
513+
return found;
514+
}
515+
516+
517+
template <typename T>
518+
bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
519+
const std::vector<T>& default_value)
520+
{
521+
const bool found = private_node_handle_.param<T>(key, value, default_value);
522+
if (!found)
523+
NODELET_WARN("Parameter '%s' not set, defaulting to '%s'", key.c_str(),
524+
fmt::format("{}", fmt::join(value, ", ")).c_str());
525+
if (found)
526+
NODELET_DEBUG("Retrieved parameter '%s' = '%s'", key.c_str(),
527+
fmt::format("{}", fmt::join(value, ", ")).c_str());
528+
return found;
529+
}
530+
531+
471532
/**
472533
* Serializes a ROS message to a buffer.
473534
*

mqtt_client/include/mqtt_client/MqttClient.ros2.hpp

Lines changed: 63 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -127,6 +127,36 @@ class MqttClient : public rclcpp::Node,
127127
template <typename T>
128128
bool loadParameter(const std::string& key, T& value, const T& default_value);
129129

130+
/**
131+
* @brief Loads requested ROS parameter from parameter server.
132+
*
133+
* @tparam T type (one of int, double, bool)
134+
*
135+
* @param[in] key parameter name
136+
* @param[out] value variable where to store the retrieved parameter
137+
*
138+
* @return true if parameter was successfully retrieved
139+
* @return false if parameter was not found
140+
*/
141+
template <typename T>
142+
bool loadParameter(const std::string& key, std::vector<T>& value);
143+
144+
/**
145+
* @brief Loads requested ROS parameter from parameter server, allows default
146+
* value.
147+
*
148+
* @tparam T type (one of int, double, bool)
149+
*
150+
* @param[in] key parameter name
151+
* @param[out] value variable where to store the retrieved parameter
152+
* @param[in] default_value default value
153+
*
154+
* @return true if parameter was successfully retrieved
155+
* @return false if parameter was not found or default was used
156+
*/
157+
template <typename T>
158+
bool loadParameter(const std::string& key, std::vector<T>& value, const std::vector<T>& default_value);
159+
130160
/**
131161
* @brief Converts a string to a path object resolving paths relative to
132162
* ROS_HOME.
@@ -323,9 +353,13 @@ class MqttClient : public rclcpp::Node,
323353
double keep_alive_interval; ///< keep-alive interval
324354
int max_inflight; ///< maximum number of inflight messages
325355
struct {
326-
std::filesystem::path certificate; ///< client certificate
327-
std::filesystem::path key; ///< client private keyfile
328-
std::string password; ///< decryption password for private key
356+
std::filesystem::path certificate; ///< client certificate
357+
std::filesystem::path key; ///< client private keyfile
358+
std::string password; ///< decryption password for private key
359+
int version; ///< TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
360+
bool verify; ///< Verify the client should conduct
361+
///< post-connect checks
362+
std::vector<std::string> alpn_protos; ///< list of ALPN protocols
329363
} tls; ///< SSL/TLS-related variables
330364
};
331365

@@ -462,6 +496,32 @@ bool MqttClient::loadParameter(const std::string& key, T& value,
462496
}
463497

464498

499+
template <typename T>
500+
bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value)
501+
{
502+
const bool found = get_parameter(key, value);
503+
if (found)
504+
RCLCPP_WARN(get_logger(), "Retrieved parameter '%s' = '[%s]'", key.c_str(),
505+
fmt::format("{}", fmt::join(value, ", ")).c_str());
506+
return found;
507+
}
508+
509+
510+
template <typename T>
511+
bool MqttClient::loadParameter(const std::string& key, std::vector<T>& value,
512+
const std::vector<T>& default_value)
513+
{
514+
const bool found = get_parameter_or(key, value, default_value);
515+
if (!found)
516+
RCLCPP_WARN(get_logger(), "Parameter '%s' not set, defaulting to '%s'",
517+
key.c_str(), fmt::format("{}", fmt::join(value, ", ")).c_str());
518+
if (found)
519+
RCLCPP_DEBUG(get_logger(), "Retrieved parameter '%s' = '%s'", key.c_str(),
520+
fmt::format("{}", fmt::join(value, ", ")).c_str());
521+
return found;
522+
}
523+
524+
465525
/**
466526
* Serializes a ROS message.
467527
*

mqtt_client/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
<depend condition="$ROS_VERSION == 1">nodelet</depend>
3535
<depend condition="$ROS_VERSION == 1">paho-mqtt-cpp</depend>
3636
<depend condition="$ROS_VERSION == 1">roscpp</depend>
37+
<depend condition="$ROS_VERSION == 1">rosfmt</depend> <!-- Needed for fmt library. -->
3738
<depend condition="$ROS_VERSION == 1">topic_tools</depend>
3839

3940
<export>

mqtt_client/src/MqttClient.cpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -194,6 +194,9 @@ void MqttClient::loadParameters() {
194194
if (loadParameter("client/tls/certificate", client_tls_certificate)) {
195195
loadParameter("client/tls/key", client_tls_key);
196196
loadParameter("client/tls/password", client_config_.tls.password);
197+
loadParameter("client/tls/version", client_config_.tls.version);
198+
loadParameter("client/tls/verify", client_config_.tls.verify);
199+
loadParameter("client/tls/alpn_protos", client_config_.tls.alpn_protos);
197200
}
198201
}
199202

@@ -437,13 +440,16 @@ void MqttClient::setupClient() {
437440
if (!client_config_.tls.password.empty())
438441
ssl.set_private_key_password(client_config_.tls.password);
439442
}
443+
ssl.set_ssl_version(client_config_.tls.version);
444+
ssl.set_verify(client_config_.tls.verify);
445+
ssl.set_alpn_protos(client_config_.tls.alpn_protos);
440446
connect_options_.set_ssl(ssl);
441447
}
442448

443449
// create MQTT client
444-
std::string protocol = broker_config_.tls.enabled ? "ssl" : "tcp";
445-
std::string uri = protocol + std::string("://") + broker_config_.host +
446-
std::string(":") + std::to_string(broker_config_.port);
450+
const std::string protocol = broker_config_.tls.enabled ? "ssl" : "tcp";
451+
const std::string uri = fmt::format("{}://{}:{}", protocol, broker_config_.host,
452+
broker_config_.port);
447453
try {
448454
if (client_config_.buffer.enabled) {
449455
client_ = std::shared_ptr<mqtt::async_client>(new mqtt::async_client(

mqtt_client/src/MqttClient.ros2.cpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -261,6 +261,9 @@ void MqttClient::loadParameters() {
261261
if (loadParameter("client.tls.certificate", client_tls_certificate)) {
262262
loadParameter("client.tls.key", client_tls_key);
263263
loadParameter("client.tls.password", client_config_.tls.password);
264+
loadParameter("client.tls.version", client_config_.tls.version);
265+
loadParameter("client.tls.verify", client_config_.tls.verify);
266+
loadParameter("client.tls.alpn_protos", client_config_.tls.alpn_protos);
264267
}
265268
}
266269

@@ -517,13 +520,16 @@ void MqttClient::setupClient() {
517520
if (!client_config_.tls.password.empty())
518521
ssl.set_private_key_password(client_config_.tls.password);
519522
}
523+
ssl.set_ssl_version(client_config_.tls.version);
524+
ssl.set_verify(client_config_.tls.verify);
525+
ssl.set_alpn_protos(client_config_.tls.alpn_protos);
520526
connect_options_.set_ssl(ssl);
521527
}
522528

523529
// create MQTT client
524-
std::string protocol = broker_config_.tls.enabled ? "ssl" : "tcp";
525-
std::string uri = protocol + std::string("://") + broker_config_.host +
526-
std::string(":") + std::to_string(broker_config_.port);
530+
const std::string protocol = broker_config_.tls.enabled ? "ssl" : "tcp";
531+
const std::string uri = fmt::format("{}://{}:{}", protocol, broker_config_.host,
532+
broker_config_.port);
527533
try {
528534
if (client_config_.buffer.enabled) {
529535
client_ = std::shared_ptr<mqtt::async_client>(new mqtt::async_client(

0 commit comments

Comments
 (0)