Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)).

Expand Down
2 changes: 1 addition & 1 deletion mqtt_client/include/mqtt_client/MqttClient.ros2.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
*
Expand Down
14 changes: 7 additions & 7 deletions mqtt_client/src/MqttClient.ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand Down Expand Up @@ -150,9 +150,9 @@ bool fixedMqtt2PrimitiveRos(mqtt::const_message_ptr mqtt_msg,
msg.data = mqtt2int<int32_t>(mqtt_msg);

serializeRosMessage(msg, serialized_msg);
} else if (msg_type == "std_msgs/msg/Int64") {
std_msgs::msg::Int32 msg;
msg.data = mqtt2int<int32_t>(mqtt_msg);
} else if (msg_type == "std_msgs/msg/Int64") {
std_msgs::msg::Int64 msg;
msg.data = mqtt2int<int64_t>(mqtt_msg);

serializeRosMessage(msg, serialized_msg);
} else if (msg_type == "std_msgs/msg/Float32") {
Expand Down
Loading