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
Prev Previous commit
Next Next commit
Correctly define serialization for std::map<std::string, double>
  • Loading branch information
rhaschke committed Sep 10, 2021

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature.
commit 0d3ce1d4623015ce5918983f432a91ed1b80fa26
35 changes: 34 additions & 1 deletion core/include/moveit/task_constructor/properties/serialize.hpp
Original file line number Diff line number Diff line change
@@ -48,7 +48,7 @@
#include <functional>
#include <sstream>
#include <ros/serialization.h>

#include <sensor_msgs/JointState.h>
#include <moveit_task_constructor_msgs/Property.h>

namespace moveit {
@@ -167,5 +167,38 @@ class PropertySerializer
}
};

template <>
class PropertySerializer<std::map<std::string, double>> : public PropertySerializerROS<sensor_msgs::JointState>
{
using T = std::map<std::string, double>;
using BaseT = PropertySerializerROS<sensor_msgs::JointState>;

public:
PropertySerializer() { insert(typeid(T), this->typeName(), &serialize, &deserialize); }

static const char* typeName() { return typeid(T).name(); }

static std::string serialize(const boost::any& value) {
T values = boost::any_cast<T>(value);
sensor_msgs::JointState state;
state.name.reserve(values.size());
state.position.reserve(values.size());
for (const auto& p : values) {
state.name.push_back(p.first);
state.position.push_back(p.second);
}
return BaseT::serialize(state);
}

static boost::any deserialize(const std::string& wired) {
auto state = boost::any_cast<sensor_msgs::JointState>(BaseT::deserialize(wired));
assert(state.position.size() == state.name.size());
T values;
for (size_t i = 0; i < state.name.size(); ++i)
values.insert(std::make_pair(state.name[i], state.position[i]));
return values;
}
};

} // namespace task_constructor
} // namespace moveit
40 changes: 0 additions & 40 deletions core/src/properties.cpp
Original file line number Diff line number Diff line change
@@ -38,8 +38,6 @@

#include <moveit/task_constructor/properties.h>

#include <sensor_msgs/JointState.h>

#include <boost/format.hpp>
#include <functional>
#include <ros/console.h>
@@ -91,44 +89,6 @@ class PropertyTypeRegistry

static PropertyTypeRegistry REGISTRY_SINGLETON;

class JointMapSerializer : public PropertySerializerBase
{
using T = std::map<std::string, double>;

public:
JointMapSerializer() {
PropertySerializer<sensor_msgs::JointState>();
insert(typeid(T), typeid(T).name(), &serialize, &deserialize);
}

protected:
static std::string serialize(const boost::any& value) {
sensor_msgs::JointState state;
for (const auto& p : boost::any_cast<T>(value)) {
state.name.push_back(p.first);
state.position.push_back(p.second);
}
return REGISTRY_SINGLETON.entry(typeid(sensor_msgs::JointState)).serialize_(state);
}

static boost::any deserialize(const std::string& wired) {
auto state{ boost::any_cast<sensor_msgs::JointState>(
REGISTRY_SINGLETON.entry(typeid(sensor_msgs::JointState)).deserialize_(wired)) };
assert(state.position.size() >= state.name.size());
T joint_map;
for (size_t i = 0; i < state.name.size(); ++i)
joint_map.insert(std::make_pair(state.name[i], state.position[i]));
return joint_map;
}
};

static bool _REGISTRY_INITIALIZER{ []() {
PropertySerializer<std::string>();
PropertySerializer<int>();
JointMapSerializer();
return true;
}() };

bool PropertyTypeRegistry::insert(const std::type_index& type_index, const std::string& type_name,
PropertySerializerBase::SerializeFunction serialize,
PropertySerializerBase::DeserializeFunction deserialize) {