Skip to content

Commit 463e501

Browse files
authored
Merge pull request #28 from oxin-ros/add-ALPN-protocol-support-for-aws
Add ALPN protocol support for AWS
2 parents 08748b9 + e393c0a commit 463e501

File tree

11 files changed

+256
-17
lines changed

11 files changed

+256
-17
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-

.github/workflows/industrial_ci.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
name: industrial_ci
22

3-
on: push
3+
on: [push, pull_request]
44

55
jobs:
66
industrial_ci:

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: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ if(${ROS_VERSION} EQUAL 2)
1515

1616
find_package(ament_cmake REQUIRED)
1717

18+
find_package(fmt REQUIRED)
1819
find_package(mqtt_client_interfaces REQUIRED)
1920
find_package(rclcpp REQUIRED)
2021
find_package(std_msgs REQUIRED)
@@ -36,6 +37,7 @@ if(${ROS_VERSION} EQUAL 2)
3637
)
3738

3839
ament_target_dependencies(${PROJECT_NAME}
40+
fmt
3941
mqtt_client_interfaces
4042
rclcpp
4143
std_msgs
@@ -82,6 +84,7 @@ elseif(${ROS_VERSION} EQUAL 1)
8284
mqtt_client_interfaces
8385
nodelet
8486
roscpp
87+
rosfmt ## For fmt::format.
8588
std_msgs
8689
topic_tools
8790
)

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: 66 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,10 @@ SOFTWARE.
3232
#include <memory>
3333
#include <string>
3434

35-
#include <mqtt/async_client.h>
35+
#define FMT_HEADER_ONLY
36+
#include <fmt/format.h>
3637
#include <mqtt_client_interfaces/srv/is_connected.hpp>
38+
#include <mqtt/async_client.h>
3739
#include <rclcpp/rclcpp.hpp>
3840
#include <rclcpp/serialization.hpp>
3941
#include <std_msgs/msg/float64.hpp>
@@ -125,6 +127,36 @@ class MqttClient : public rclcpp::Node,
125127
template <typename T>
126128
bool loadParameter(const std::string& key, T& value, const T& default_value);
127129

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+
128160
/**
129161
* @brief Converts a string to a path object resolving paths relative to
130162
* ROS_HOME.
@@ -321,9 +353,13 @@ class MqttClient : public rclcpp::Node,
321353
double keep_alive_interval; ///< keep-alive interval
322354
int max_inflight; ///< maximum number of inflight messages
323355
struct {
324-
std::filesystem::path certificate; ///< client certificate
325-
std::filesystem::path key; ///< client private keyfile
326-
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
327363
} tls; ///< SSL/TLS-related variables
328364
};
329365

@@ -460,6 +496,32 @@ bool MqttClient::loadParameter(const std::string& key, T& value,
460496
}
461497

462498

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+
463525
/**
464526
* Serializes a ROS message.
465527
*

mqtt_client/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323

2424
<!-- ROS2 -->
2525
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>
26+
<depend condition="$ROS_VERSION == 2">fmt</depend>
2627
<depend condition="$ROS_VERSION == 2">libpaho-mqtt-dev</depend>
2728
<depend condition="$ROS_VERSION == 2">libpaho-mqttpp-dev</depend>
2829
<depend condition="$ROS_VERSION == 2">rclcpp</depend>
@@ -33,6 +34,7 @@
3334
<depend condition="$ROS_VERSION == 1">nodelet</depend>
3435
<depend condition="$ROS_VERSION == 1">paho-mqtt-cpp</depend>
3536
<depend condition="$ROS_VERSION == 1">roscpp</depend>
37+
<depend condition="$ROS_VERSION == 1">rosfmt</depend> <!-- Needed for fmt library. -->
3638
<depend condition="$ROS_VERSION == 1">topic_tools</depend>
3739

3840
<export>

0 commit comments

Comments
 (0)