diff --git a/README.md b/README.md index 7693dce..4627672 100644 --- a/README.md +++ b/README.md @@ -339,7 +339,7 @@ bridge: As seen in the [Quick Start](#quick-start), the *mqtt_client* can not only exchange arbitrary ROS messages with other *mqtt_clients*, but it can also exchange primitive message data with other non-*mqtt_client* MQTT clients. This allows ROS-based devices to exchange primitive messages with devices not based on ROS. The `primitive` parameter can be set for both ROS-to-MQTT (`bridge/ros2mqtt`) and for MQTT-to-ROS (`bridge/mqtt2ros`) transmissions. -If a ROS-to-MQTT transmission is configured as `primitive` and the ROS message type is one of the supported primitive ROS message types, the raw data is published as a string. The supported primitive ROS message types are [`std_msgs/String`](http://docs.ros.org/en/api/std_msgs/html/msg/String.html), [`std_msgs/Bool`](http://docs.ros.org/en/api/std_msgs/html/msg/Bool.html), [`std_msgs/Char`](http://docs.ros.org/en/api/std_msgs/html/msg/Char.html), [`std_msgs/UInt8`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt8.html), [`std_msgs/UInt16`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt16.html), [`std_msgs/UInt32`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt32.html), [`std_msgs/UInt64`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt16.html), [`std_msgs/Int8`](http://docs.ros.org/en/api/std_msgs/html/msg/Int8.html), [`std_msgs/Int16`](http://docs.ros.org/en/api/std_msgs/html/msg/Int16.html), [`std_msgs/Int32`](http://docs.ros.org/en/api/std_msgs/html/msg/Int32.html), [`std_msgs/Int64`](http://docs.ros.org/en/api/std_msgs/html/msg/Int64.html), [`std_msgs/Float32`](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html), [`std_msgs/Float32`](http://docs.ros.org/en/api/std_msgs/html/msg/Float64.html). +If a ROS-to-MQTT transmission is configured as `primitive` and the ROS message type is one of the supported primitive ROS message types, the raw data is published as a string. The supported primitive ROS message types are [`std_msgs/String`](http://docs.ros.org/en/api/std_msgs/html/msg/String.html), [`std_msgs/Bool`](http://docs.ros.org/en/api/std_msgs/html/msg/Bool.html), [`std_msgs/Char`](http://docs.ros.org/en/api/std_msgs/html/msg/Char.html), [`std_msgs/UInt8`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt8.html), [`std_msgs/UInt16`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt16.html), [`std_msgs/UInt32`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt32.html), [`std_msgs/UInt64`](http://docs.ros.org/en/api/std_msgs/html/msg/UInt64.html), [`std_msgs/Int8`](http://docs.ros.org/en/api/std_msgs/html/msg/Int8.html), [`std_msgs/Int16`](http://docs.ros.org/en/api/std_msgs/html/msg/Int16.html), [`std_msgs/Int32`](http://docs.ros.org/en/api/std_msgs/html/msg/Int32.html), [`std_msgs/Int64`](http://docs.ros.org/en/api/std_msgs/html/msg/Int64.html), [`std_msgs/Float32`](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html), [`std_msgs/Float64`](http://docs.ros.org/en/api/std_msgs/html/msg/Float64.html). If an MQTT-to-ROS transmission is configured as `primitive`, the MQTT message is interpreted and published as a primitive data type, if possible. The message is probed in the following order: `bool` ([`std_msgs/Bool`](http://docs.ros.org/en/api/std_msgs/html/msg/Bool.html)), `int` ([`std_msgs/Int32`](http://docs.ros.org/en/api/std_msgs/html/msg/Int32.html)), `float` ([`std_msgs/Float32`](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)), `string` ([`std_msgs/String`](http://docs.ros.org/en/api/std_msgs/html/msg/String.html)). diff --git a/mqtt_client/include/mqtt_client/MqttClient.ros2.hpp b/mqtt_client/include/mqtt_client/MqttClient.ros2.hpp index 0d5c6b8..6677ff6 100644 --- a/mqtt_client/include/mqtt_client/MqttClient.ros2.hpp +++ b/mqtt_client/include/mqtt_client/MqttClient.ros2.hpp @@ -199,7 +199,7 @@ class MqttClient : public rclcpp::Node, const Ros2MqttInterface& ros2mqtt) const; /** - * @brief Get the candiate topic endpoints for subscription matching + * @brief Get the candidate topic endpoints for subscription matching * * @param ros2mqtt the ROS to MQTT interface spec * diff --git a/mqtt_client/src/MqttClient.ros2.cpp b/mqtt_client/src/MqttClient.ros2.cpp index c45be95..bf7f62c 100644 --- a/mqtt_client/src/MqttClient.ros2.cpp +++ b/mqtt_client/src/MqttClient.ros2.cpp @@ -67,8 +67,8 @@ T mqtt2float(mqtt::const_message_ptr mqtt_msg) { std::size_t pos; const T v = std::stold(str_msg, &pos); - if (pos != str_msg.size()) - throw std::invalid_argument ("not all charaters processed"); + if (pos != str_msg.size()) + throw std::invalid_argument ("not all characters processed"); return v; } @@ -79,8 +79,8 @@ T mqtt2int(mqtt::const_message_ptr mqtt_msg) { std::size_t pos; const T v = std::stoll(str_msg, &pos); - if (pos != str_msg.size()) - throw std::invalid_argument ("not all charaters processed"); + if (pos != str_msg.size()) + throw std::invalid_argument ("not all characters processed"); return v; } @@ -150,9 +150,9 @@ bool fixedMqtt2PrimitiveRos(mqtt::const_message_ptr mqtt_msg, msg.data = mqtt2int(mqtt_msg); serializeRosMessage(msg, serialized_msg); - } else if (msg_type == "std_msgs/msg/Int64") { - std_msgs::msg::Int32 msg; - msg.data = mqtt2int(mqtt_msg); + } else if (msg_type == "std_msgs/msg/Int64") { + std_msgs::msg::Int64 msg; + msg.data = mqtt2int(mqtt_msg); serializeRosMessage(msg, serialized_msg); } else if (msg_type == "std_msgs/msg/Float32") {