Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feat/ubuntu 18.04 support #11

Open
wants to merge 9 commits into
base: main
Choose a base branch
from
Open
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
45 changes: 37 additions & 8 deletions mqtt_client/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
cmake_minimum_required(VERSION 3.12.0 FATAL_ERROR)
# While FetchContent only requires CMake 3.11, the convenience function
# `FetchContent_MakeAvailable` was introduced in CMake 3.14
cmake_minimum_required(VERSION 3.14 FATAL_ERROR)
project(mqtt_client)

find_package(ros_environment REQUIRED QUIET)
Expand Down Expand Up @@ -96,13 +98,39 @@ elseif(${ROS_VERSION} EQUAL 1)
topic_tools
)

## System dependencies are found with CMake's conventions
find_package(PahoMqttCpp REQUIRED)
set(PahoMqttCpp_LIBRARIES PahoMqttCpp::paho-mqttpp3)

find_package(fmt REQUIRED)
set(fmt_LIBRARIES fmt::fmt)

# System dependencies.
include(FetchContent)

find_package(PahoMqttCpp QUIET)
if(PahoMqttCpp_FOUND)
set(PahoMqttCpp_LIBRARIES PahoMqttCpp::paho-mqttpp3)
else()
FetchContent_Declare(PahoMqttCpp
GIT_REPOSITORY https://github.com/eclipse/paho.mqtt.cpp
GIT_TAG v1.4.1
)
FetchContent_MakeAvailable(PahoMqttCpp)
set(PahoMqttCpp_LIBRARIES PahoMqttCpp::paho-mqttpp3)
endif()

find_package(fmt QUIET)
if(fmt_FOUND)
set(fmt_LIBRARIES fmt::fmt)
else()
FetchContent_Declare(fmt
GIT_REPOSITORY https://github.com/fmtlib/fmt.git
GIT_TAG 10.2.1
)
FetchContent_MakeAvailable(fmt)
set(fmt_LIBRARIES fmt::fmt)
endif()

FetchContent_Declare(
utf8cpp
GIT_REPOSITORY https://github.com/nemtrif/utfcpp.git
GIT_TAG v3.2.4)
FetchContent_MakeAvailable(utf8cpp)
set(utf8cpp_LIBRARIES utf8::cpp)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
Expand Down Expand Up @@ -242,6 +270,7 @@ elseif(${ROS_VERSION} EQUAL 1)
${catkin_LIBRARIES}
${fmt_LIBRARIES}
${PahoMqttCpp_LIBRARIES}
${utf8cpp_LIBRARIES}
)

#############
Expand Down
14 changes: 7 additions & 7 deletions mqtt_client/include/mqtt_client/MqttClient.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ SOFTWARE.

#pragma once

#include <filesystem>
#include "boost/filesystem.hpp"
#include <map>
#include <memory>
#include <string>
Expand Down Expand Up @@ -166,9 +166,9 @@ class MqttClient : public nodelet::Nodelet,
*
* @param path_string (relative) path as string
*
* @return std::filesystem::path path variable
* @return boost::filesystem::path path variable
*/
std::filesystem::path resolvePath(const std::string& path_string);
boost::filesystem::path resolvePath(const std::string& path_string);

/**
* @brief Initializes broker connection and subscriptions.
Expand Down Expand Up @@ -336,7 +336,7 @@ class MqttClient : public nodelet::Nodelet,
std::string pass; ///< password
struct {
bool enabled; ///< whether to connect via SSL/TLS
std::filesystem::path
boost::filesystem::path
ca_certificate; ///< public CA certificate trusted by client
} tls; ///< SSL/TLS-related variables
};
Expand All @@ -349,7 +349,7 @@ class MqttClient : public nodelet::Nodelet,
struct {
bool enabled; ///< whether client buffer is enabled
int size; ///< client buffer size
std::filesystem::path directory; ///< client buffer directory
boost::filesystem::path directory; ///< client buffer directory
} buffer; ///< client buffer-related variables
struct {
std::string topic; ///< last-will topic
Expand All @@ -361,8 +361,8 @@ class MqttClient : public nodelet::Nodelet,
double keep_alive_interval; ///< keep-alive interval
int max_inflight; ///< maximum number of inflight messages
struct {
std::filesystem::path certificate; ///< client certificate
std::filesystem::path key; ///< client private keyfile
boost::filesystem::path certificate; ///< client certificate
boost::filesystem::path key; ///< client private keyfile
std::string password; ///< decryption password for private key
int version; ///< TLS version (https://github.com/eclipse/paho.mqtt.cpp/blob/master/src/mqtt/ssl_options.h#L305)
bool verify; ///< Verify the client should conduct
Expand Down
11 changes: 6 additions & 5 deletions mqtt_client/package.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<?xml version='1.0' encoding='utf8'?>
<package format="3">

<name>mqtt_client</name>
<version>2.3.0</version>
<version>3.0.0</version>
<description>Node that enables connected ROS-based devices or robots to exchange ROS messages via an MQTT broker using the MQTT protocol.</description>

<maintainer email="[email protected]">Lennart Reiher</maintainer>
Expand All @@ -22,18 +22,19 @@
<depend>ros_environment</depend>
<depend>std_msgs</depend>

<!-- ROS2 -->

<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>
<depend condition="$ROS_VERSION == 2">libpaho-mqtt-dev</depend>
<depend condition="$ROS_VERSION == 2">libpaho-mqttpp-dev</depend>
<depend condition="$ROS_VERSION == 2">rclcpp</depend>
<depend condition="$ROS_VERSION == 2">rclcpp_components</depend>
<depend condition="$ROS_VERSION == 2">rcpputils</depend>

<!-- ROS1 -->

<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<depend condition="$ROS_VERSION == 1">nodelet</depend>
<depend condition="$ROS_VERSION == 1">paho-mqtt-cpp</depend>


<depend condition="$ROS_VERSION == 1">roscpp</depend>
<depend condition="$ROS_VERSION == 1">topic_tools</depend>

Expand Down
51 changes: 39 additions & 12 deletions mqtt_client/src/MqttClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ SOFTWARE.
#include <cstring>
#include <vector>

#include "utf8.h"

#include <mqtt_client/MqttClient.h>
#include <mqtt_client_interfaces/RosMsgType.h>
#include <pluginlib/class_list_macros.h>
Expand All @@ -47,10 +49,10 @@ SOFTWARE.
#include <std_msgs/UInt32.h>
#include <std_msgs/UInt64.h>
#include <std_msgs/UInt8.h>
#include <std_msgs/UInt8MultiArray.h>
#include <xmlrpcpp/XmlRpcException.h>
#include <xmlrpcpp/XmlRpcValue.h>


PLUGINLIB_EXPORT_CLASS(mqtt_client::MqttClient, nodelet::Nodelet)


Expand Down Expand Up @@ -85,6 +87,7 @@ const std::string MqttClient::kLatencyRosTopicPrefix = "latencies/";
* std_msgs/Int64
* std_msgs/Float32
* std_msgs/Float64
* std_msgs/UInt8MultiArray
*
* @param [in] msg generic ShapeShifter ROS message
* @param [out] primitive string representation of primitive message data
Expand Down Expand Up @@ -136,6 +139,11 @@ bool primitiveRosMessageToString(const topic_tools::ShapeShifter::ConstPtr& msg,
} else if (msg_type_md5 ==
ros::message_traits::MD5Sum<std_msgs::Float64>::value()) {
primitive = std::to_string(msg->instantiate<std_msgs::Float64>()->data);
} else if (msg_type_md5 ==
ros::message_traits::MD5Sum<std_msgs::UInt8MultiArray>::value()) {
primitive = std::string(
msg->instantiate<std_msgs::UInt8MultiArray>()->data.begin(),
msg->instantiate<std_msgs::UInt8MultiArray>()->data.end());
} else {
found_primitive = false;
}
Expand Down Expand Up @@ -362,21 +370,21 @@ bool MqttClient::loadParameter(const std::string& key, std::string& value,
}


std::filesystem::path MqttClient::resolvePath(const std::string& path_string) {
boost::filesystem::path MqttClient::resolvePath(const std::string& path_string) {

std::filesystem::path path(path_string);
boost::filesystem::path path(path_string);
if (path_string.empty()) return path;
if (!path.has_root_path()) {
std::string ros_home;
ros::get_environment_variable(ros_home, "ROS_HOME");
if (ros_home.empty())
ros_home = std::string(std::filesystem::current_path());
path = std::filesystem::path(ros_home);
ros_home = boost::filesystem::current_path().string();
path = boost::filesystem::path(ros_home);
path.append(path_string);
}
if (!std::filesystem::exists(path))
if (!boost::filesystem::exists(path))
NODELET_WARN("Requested path '%s' does not exist",
std::string(path).c_str());
path.string().c_str());
return path;
}

Expand Down Expand Up @@ -432,11 +440,11 @@ void MqttClient::setupClient() {
// SSL/TLS
if (broker_config_.tls.enabled) {
mqtt::ssl_options ssl;
ssl.set_trust_store(broker_config_.tls.ca_certificate);
ssl.set_trust_store(broker_config_.tls.ca_certificate.string());
if (!client_config_.tls.certificate.empty() &&
!client_config_.tls.key.empty()) {
ssl.set_key_store(client_config_.tls.certificate);
ssl.set_private_key(client_config_.tls.key);
ssl.set_key_store(client_config_.tls.certificate.string());
ssl.set_private_key(client_config_.tls.key.string());
if (!client_config_.tls.password.empty())
ssl.set_private_key_password(client_config_.tls.password);
}
Expand All @@ -454,7 +462,7 @@ void MqttClient::setupClient() {
if (client_config_.buffer.enabled) {
client_ = std::shared_ptr<mqtt::async_client>(new mqtt::async_client(
uri, client_config_.id, client_config_.buffer.size,
client_config_.buffer.directory));
client_config_.buffer.directory.string()));
} else {
client_ = std::shared_ptr<mqtt::async_client>(
new mqtt::async_client(uri, client_config_.id));
Expand Down Expand Up @@ -508,7 +516,7 @@ void MqttClient::ros2mqtt(const topic_tools::ShapeShifter::ConstPtr& ros_msg,

// resolve ROS messages to primitive strings if possible
std::string payload;
bool found_primitive = primitiveRosMessageToString(ros_msg, payload);
const bool found_primitive = primitiveRosMessageToString(ros_msg, payload);
if (found_primitive) {
payload_buffer = std::vector<uint8_t>(payload.begin(), payload.end());
} else {
Expand Down Expand Up @@ -755,6 +763,25 @@ void MqttClient::mqtt2primitive(mqtt::const_message_ptr mqtt_msg) {
}
}

// check for non-UTF8 string.
if (!found_primitive) {
const bool is_valid_utf8 = utf8::is_valid(str_msg);
if (!is_valid_utf8) {
std_msgs::UInt8MultiArray msg;
msg.data = std::vector<uint8_t>(str_msg.begin(), str_msg.end());
serializeRosMessage(msg, msg_buffer);

// collect ROS message type information
msg_type_md5 = ros::message_traits::MD5Sum<std_msgs::UInt8MultiArray>::value();
msg_type_name =
ros::message_traits::DataType<std_msgs::UInt8MultiArray>::value();
msg_type_definition =
ros::message_traits::Definition<std_msgs::UInt8MultiArray>::value();

found_primitive = true;
}
}

// fall back to string
if (!found_primitive) {

Expand Down
19 changes: 18 additions & 1 deletion mqtt_client/src/MqttClient.ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,6 +251,10 @@ bool primitiveRosMessageToString(
std_msgs::msg::Float64 msg;
deserializeRosMessage(*serialized_msg, msg);
primitive = std::to_string(msg.data);
} else if (msg_type == "std_msgs/msg/UInt8MultiArray") {
std_msgs::msg::UInt8MultiArray msg;
deserializeRosMessage(*serialized_msg, msg);
primitive = std::string(msg.data.begin(), msg.data.end());
} else {
found_primitive = false;
}
Expand Down Expand Up @@ -953,7 +957,7 @@ void MqttClient::ros2mqtt(

// resolve ROS messages to primitive strings if possible
std::string payload;
bool found_primitive =
const bool found_primitive =
primitiveRosMessageToString(serialized_msg, ros_msg_type.name, payload);
if (found_primitive) {
payload_buffer = std::vector<uint8_t>(payload.begin(), payload.end());
Expand Down Expand Up @@ -1179,6 +1183,19 @@ void MqttClient::mqtt2primitive(mqtt::const_message_ptr mqtt_msg) {
}
}

// check for non-UTF8 string.
if (!found_primitive) {
const bool is_valid_utf8 = utf8::is_valid(str_msg);
if (!is_valid_utf8) {
std_msgs::msg::UInt8MultiArray msg;
msg.data = std::vector<uint8_t>(str_msg.begin(), str_msg.end());
serializeRosMessage(msg, serialized_msg);

ros_msg_type = "std_msgs/msg/UInt8MultiArray";
found_primitive = true;
}
}

// fall back to string
if (!found_primitive) {

Expand Down
10 changes: 5 additions & 5 deletions mqtt_client_interfaces/package.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<?xml version='1.0' encoding='utf8'?>
<package format="3">

<name>mqtt_client_interfaces</name>
<version>2.3.0</version>
<version>3.0.0</version>
<description>Message and service definitions for mqtt_client</description>

<maintainer email="[email protected]">Lennart Reiher</maintainer>
Expand All @@ -16,13 +16,13 @@

<depend>ros_environment</depend>

<!-- ROS2 -->

<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>
<build_depend condition="$ROS_VERSION == 2">rosidl_default_generators</build_depend>
<depend condition="$ROS_VERSION == 2">std_msgs</depend>
<exec_depend condition="$ROS_VERSION == 2">rosidl_default_runtime</exec_depend>

<!-- ROS1 -->

<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<depend condition="$ROS_VERSION == 1">message_generation</depend>
<depend condition="$ROS_VERSION == 1">std_msgs</depend>
Expand All @@ -35,4 +35,4 @@

<member_of_group condition="$ROS_VERSION == 2">rosidl_interface_packages</member_of_group>

</package>
</package>