@@ -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 *
0 commit comments