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

add external properties to SolutionInfo #194

Open
wants to merge 12 commits into
base: master
Choose a base branch
from
4 changes: 2 additions & 2 deletions core/include/moveit/task_constructor/properties/base64.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ std::basic_string<T> encode(const T* bytes_to_encode, uint32_t in_len) {
ret += '=';
}

return std::move(ret);
return ret;
}

template <typename T = char>
Expand Down Expand Up @@ -126,7 +126,7 @@ std::basic_string<T> decode(const T* encoded_string, int64_t in_len) {
ret += char_array_3[j];
}

return std::move(ret);
return ret;
}

}; // namespace base64
Expand Down
108 changes: 49 additions & 59 deletions core/include/moveit/task_constructor/properties/serialize.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <boost/any.hpp>
#include <typeindex>
#include <type_traits>
#include <map>
#include <set>
#include <vector>
Expand All @@ -57,30 +58,24 @@ namespace task_constructor {

class Property;

// hasSerialize<T>::value provides a true/false constexpr depending on whether operator<< is supported.
// has*Operator<T>::value is true iff operator<< resp. operator>> is available for T.
// This uses SFINAE, extracted from https://jguegant.github.io/blogs/tech/sfinae-introduction.html
template <typename T, typename = std::ostream&>
struct hasInsertionOperator : std::false_type
struct IsStreamSerializable : std::false_type
{};

template <typename T>
struct hasInsertionOperator<T, decltype(std::declval<std::ostream&>() << std::declval<T>())> : std::true_type
struct IsStreamSerializable<T, decltype(std::declval<std::ostream&>() << std::declval<T>())> : std::true_type
{};

template <typename T>
constexpr bool hasInsertionOperator_v = hasInsertionOperator<T>::value;

template <typename T, typename = std::istream&>
struct hasExtractionOperator : std::false_type
struct IsStreamDeserializable : std::false_type
rhaschke marked this conversation as resolved.
Show resolved Hide resolved
{};

template <typename T>
struct hasExtractionOperator<T, decltype(std::declval<std::istream&>() >> std::declval<T&>())> : std::true_type
struct IsStreamDeserializable<T, decltype(std::declval<std::istream&>() >> std::declval<T&>())> : std::true_type
{};

template <typename T>
constexpr bool hasExtractionOperator_v = hasExtractionOperator<T>::value;
v4hn marked this conversation as resolved.
Show resolved Hide resolved

class PropertySerializerBase
{
public:
Expand All @@ -95,90 +90,85 @@ class PropertySerializerBase
DeserializeFunction deserialize);
};

template <typename T>
class PropertySerializer : public PropertySerializerBase
/** Serialization for std::string **/
class PropertySerializerString : public PropertySerializerBase
{
protected:
/// a set of mutually exclusive conditions
template <typename U>
static constexpr bool IsROSMessage{ ros::message_traits::IsMessage<U>::value };

template <typename U>
static constexpr bool IsStreamSerializable{ !IsROSMessage<U> && hasInsertionOperator_v<U> };

template <typename U>
static constexpr bool IsStreamDeserializable{ !IsROSMessage<U> && hasExtractionOperator_v<U> };

template <typename U>
static constexpr bool IsString{ std::is_same<U, std::string>::value };

template <typename U>
static constexpr bool IsNotDeserializable{ !IsROSMessage<U> && !IsStreamSerializable<U> };

public:
PropertySerializer() { this->insert(typeid(T), this->typeName<T>(), &serialize, &deserialize); }
static const char* typeName() { return typeid(std::string).name(); }

template <typename Q = T>
static std::enable_if_t<!IsROSMessage<Q>, std::string> typeName() {
return typeid(T).name();
}
static std::string serialize(const boost::any& value) { return boost::any_cast<std::string>(value); }
static boost::any deserialize(const std::string& wired) { return wired; }
};

template <typename Q = T>
static std::enable_if_t<IsROSMessage<Q>, std::string> typeName() {
return ros::message_traits::DataType<T>::value();
}
/** Serialization for ROS messages **/
template <typename T>
class PropertySerializerROS : public PropertySerializerBase
{
public:
static const char* typeName() { return ros::message_traits::DataType<T>::value(); }

/** ROS messages are serialized using the provided binary encoding */
template <typename Q = T>
static std::enable_if_t<IsROSMessage<Q>, std::string> serialize(const boost::any& value) {
Q message{ boost::any_cast<Q>(value) };
static std::string serialize(const boost::any& value) {
T message{ boost::any_cast<T>(value) };
uint32_t serial_size = ros::serialization::serializationLength(message);
std::unique_ptr<uint8_t[]> buffer(new uint8_t[serial_size]);
ros::serialization::OStream stream(buffer.get(), serial_size);
ros::serialization::serialize(stream, message);
return reinterpret_cast<const char*>(base64::encode(buffer.get(), serial_size).c_str());
rhaschke marked this conversation as resolved.
Show resolved Hide resolved
}
template <typename Q = T>
static std::enable_if_t<IsROSMessage<Q>, boost::any> deserialize(const std::string& wired) {

static boost::any deserialize(const std::string& wired) {
auto decoded{ base64::decode(wired.data(), wired.size()) };
ros::serialization::IStream stream(const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(decoded.data())),
wired.size());
Q message;
T message;
ros::serialization::deserialize(stream, message);
return message;
}
};

/** Serialization based on std::[io]stringstream */
template <typename T>
class PropertySerializerStream : public PropertySerializerBase
{
public:
static const char* typeName() { return typeid(T).name(); }

/** Serialization based on std::[io]stringstream */
template <typename Q = T>
static std::enable_if_t<IsStreamSerializable<Q>, std::string> serialize(const boost::any& value) {
static std::enable_if_t<IsStreamSerializable<Q>::value, std::string> serialize(const boost::any& value) {
std::ostringstream oss;
oss << boost::any_cast<T>(value);
return oss.str();
}
template <typename Q = T>
static std::enable_if_t<IsStreamDeserializable<Q> && !IsString<Q>, boost::any>
deserialize(const std::string& wired) {
static std::enable_if_t<IsStreamDeserializable<Q>::value, boost::any> deserialize(const std::string& wired) {
std::istringstream iss(wired);
T value;
iss >> value;
return value;
}
// (istream >> string) only extracts until first whitespace, so we specialize
template <typename Q = T>
static std::enable_if_t<IsString<Q>, boost::any> deserialize(const std::string& wired) {
return wired;
}

/** No serialization available */
/** fallback, if no serialization/deserialization is available **/
template <typename Q = T>
static std::enable_if_t<IsNotDeserializable<Q>, std::string> serialize(const boost::any& value) {
static std::enable_if_t<!IsStreamSerializable<Q>::value, std::string> serialize(const boost::any& value) {
return dummySerialize(value);
}

template <typename Q = T>
static std::enable_if_t<IsNotDeserializable<Q>, boost::any> deserialize(const std::string& wire) {
static std::enable_if_t<!IsStreamDeserializable<Q>::value, boost::any> deserialize(const std::string& wire) {
return dummyDeserialize(wire);
}
};

template <typename T>
class PropertySerializer
: public std::conditional_t<std::is_same<T, std::string>::value, PropertySerializerString,
std::conditional_t<ros::message_traits::IsMessage<T>::value, PropertySerializerROS<T>,
PropertySerializerStream<T>>>
rhaschke marked this conversation as resolved.
Show resolved Hide resolved
{
public:
PropertySerializer() {
this->insert(typeid(T), this->typeName(), &PropertySerializer::serialize, &PropertySerializer::deserialize);
}
};

} // namespace task_constructor
} // namespace moveit
13 changes: 7 additions & 6 deletions core/test/test_properties.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,12 +89,13 @@ TEST(Property, anytype) {
}

TEST(Property, serialize_basic) {
EXPECT_TRUE(hasInsertionOperator<int>::value);
EXPECT_TRUE(hasExtractionOperator<int>::value);
EXPECT_TRUE(hasInsertionOperator<double>::value);
EXPECT_TRUE(hasExtractionOperator<double>::value);
EXPECT_TRUE(hasInsertionOperator<std::string>::value);
EXPECT_TRUE(hasExtractionOperator<std::string>::value);
EXPECT_TRUE(IsStreamSerializable<int>::value);
EXPECT_TRUE(IsStreamSerializable<double>::value);
EXPECT_TRUE(IsStreamSerializable<std::string>::value);

EXPECT_TRUE(IsStreamDeserializable<int>::value);
EXPECT_TRUE(IsStreamDeserializable<double>::value);
EXPECT_TRUE(IsStreamDeserializable<std::string>::value);
}

TEST(Property, serialize) {
Expand Down