Skip to content

Commit 8fc18e3

Browse files
committed
add descriptions to all parameters
1 parent abe0392 commit 8fc18e3

File tree

1 file changed

+69
-32
lines changed

1 file changed

+69
-32
lines changed

mqtt_client/src/MqttClient.ros2.cpp

Lines changed: 69 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -147,38 +147,75 @@ MqttClient::MqttClient() : Node("mqtt_client") {
147147

148148
void MqttClient::loadParameters() {
149149

150-
declare_parameter("broker.host");
151-
declare_parameter("broker.port");
152-
declare_parameter("broker.user");
153-
declare_parameter("broker.pass");
154-
declare_parameter("broker.tls.enabled");
155-
declare_parameter("broker.tls.ca_certificate");
156-
declare_parameter("client.id");
157-
declare_parameter("client.buffer.size");
158-
declare_parameter("client.buffer.directory");
159-
declare_parameter("client.last_will.topic");
160-
declare_parameter("client.last_will.message");
161-
declare_parameter("client.last_will.qos");
162-
declare_parameter("client.last_will.retained");
163-
declare_parameter("client.clean_session");
164-
declare_parameter("client.keep_alive_interval");
165-
declare_parameter("client.max_inflight");
166-
declare_parameter("client.tls.certificate");
167-
declare_parameter("client.tls.key");
168-
declare_parameter("client.tls.password");
169-
declare_parameter("bridge.ros2mqtt.ros_topic");
170-
declare_parameter("bridge.ros2mqtt.mqtt_topic");
171-
declare_parameter("bridge.ros2mqtt.primitive");
172-
declare_parameter("bridge.ros2mqtt.inject_timestamp");
173-
declare_parameter("bridge.ros2mqtt.advanced.ros.queue_size");
174-
declare_parameter("bridge.ros2mqtt.advanced.mqtt.qos");
175-
declare_parameter("bridge.ros2mqtt.advanced.mqtt.retained");
176-
declare_parameter("bridge.mqtt2ros.mqtt_topic");
177-
declare_parameter("bridge.mqtt2ros.ros_topic");
178-
declare_parameter("bridge.mqtt2ros.primitive");
179-
declare_parameter("bridge.mqtt2ros.advanced.mqtt.qos");
180-
declare_parameter("bridge.mqtt2ros.advanced.ros.queue_size");
181-
declare_parameter("bridge.mqtt2ros.advanced.ros.latched");
150+
rcl_interfaces::msg::ParameterDescriptor param_desc;
151+
152+
param_desc.description = "IP address or hostname of the machine running the MQTT broker";
153+
declare_parameter("broker.host", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
154+
param_desc.description = "port the MQTT broker is listening on";
155+
declare_parameter("broker.port", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
156+
param_desc.description = "username used for authenticating to the broker (if empty, will try to connect anonymously)";
157+
declare_parameter("broker.user", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
158+
param_desc.description = "password used for authenticating to the broker";
159+
declare_parameter("broker.pass", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
160+
param_desc.description = "whether to connect via SSL/TLS";
161+
declare_parameter("broker.tls.enabled", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
162+
param_desc.description = "CA certificate file trusted by client (relative to ROS_HOME)";
163+
declare_parameter("broker.tls.ca_certificate", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
164+
165+
param_desc.description = "unique ID used to identify the client (broker may allow empty ID and automatically generate one)";
166+
declare_parameter("client.id", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
167+
param_desc.description = "maximum number of messages buffered by the bridge when not connected to broker (only available if client ID is not empty)";
168+
declare_parameter("client.buffer.size", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
169+
param_desc.description = "directory used to buffer messages when not connected to broker (relative to ROS_HOME)";
170+
declare_parameter("client.buffer.directory", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
171+
param_desc.description = "topic used for this client's last-will message (no last will, if not specified)";
172+
declare_parameter("client.last_will.topic", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
173+
param_desc.description = "last-will message";
174+
declare_parameter("client.last_will.message", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
175+
param_desc.description = "QoS value for last-will message";
176+
declare_parameter("client.last_will.qos", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
177+
param_desc.description = "whether to retain last-will message";
178+
declare_parameter("client.last_will.retained", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
179+
param_desc.description = "whether to use a clean session for this client";
180+
declare_parameter("client.clean_session", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
181+
param_desc.description = "keep-alive interval in seconds";
182+
declare_parameter("client.keep_alive_interval", rclcpp::ParameterType::PARAMETER_DOUBLE, param_desc);
183+
param_desc.description = "maximum number of inflight messages";
184+
declare_parameter("client.max_inflight", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
185+
param_desc.description = "client certificate file (only needed if broker requires client certificates; relative to ROS_HOME)";
186+
declare_parameter("client.tls.certificate", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
187+
param_desc.description = "client private key file (relative to ROS_HOME)";
188+
declare_parameter("client.tls.key", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
189+
param_desc.description = "client private key password";
190+
declare_parameter("client.tls.password", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
191+
192+
param_desc.description = "ROS topic whose messages are transformed to MQTT messages";
193+
declare_parameter("bridge.ros2mqtt.ros_topic", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
194+
param_desc.description = "MQTT topic on which the corresponding ROS messages are sent to the broker";
195+
declare_parameter("bridge.ros2mqtt.mqtt_topic", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
196+
param_desc.description = "whether to publish as primitive message";
197+
declare_parameter("bridge.ros2mqtt.primitive", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
198+
param_desc.description = "whether to attach a timestamp to a ROS2MQTT payload (for latency computation on receiver side)";
199+
declare_parameter("bridge.ros2mqtt.inject_timestamp", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
200+
param_desc.description = "ROS subscriber queue size";
201+
declare_parameter("bridge.ros2mqtt.advanced.ros.queue_size", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
202+
param_desc.description = "MQTT QoS value";
203+
declare_parameter("bridge.ros2mqtt.advanced.mqtt.qos", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
204+
param_desc.description = "whether to retain MQTT message";
205+
declare_parameter("bridge.ros2mqtt.advanced.mqtt.retained", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
206+
207+
param_desc.description = "MQTT topic on which messages are received from the broker";
208+
declare_parameter("bridge.mqtt2ros.mqtt_topic", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
209+
param_desc.description = "ROS topic on which corresponding MQTT messages are published";
210+
declare_parameter("bridge.mqtt2ros.ros_topic", rclcpp::ParameterType::PARAMETER_STRING, param_desc);
211+
param_desc.description = "whether to publish as primitive message (if coming from non-ROS MQTT client)";
212+
declare_parameter("bridge.mqtt2ros.primitive", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
213+
param_desc.description = "MQTT QoS value";
214+
declare_parameter("bridge.mqtt2ros.advanced.mqtt.qos", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
215+
param_desc.description = "ROS publisher queue size";
216+
declare_parameter("bridge.mqtt2ros.advanced.ros.queue_size", rclcpp::ParameterType::PARAMETER_INTEGER, param_desc);
217+
param_desc.description = "whether to latch ROS message";
218+
declare_parameter("bridge.mqtt2ros.advanced.ros.latched", rclcpp::ParameterType::PARAMETER_BOOL, param_desc);
182219

183220
// load broker parameters from parameter server
184221
std::string broker_tls_ca_certificate;

0 commit comments

Comments
 (0)