mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
PropertyFactory::createDefault()
... creating a read-only rviz::Property from serialized mtc::Property value
This commit is contained in:
parent
a1c81f1236
commit
20e951bf63
@ -102,7 +102,8 @@ rviz::Property* PropertyFactory::create(const std::string& prop_name, mtc::Prope
|
|||||||
rviz::DisplayContext* display_context) const
|
rviz::DisplayContext* display_context) const
|
||||||
{
|
{
|
||||||
auto it = property_registry_.find(prop.typeName());
|
auto it = property_registry_.find(prop.typeName());
|
||||||
if (it == property_registry_.end()) return nullptr;
|
if (it == property_registry_.end())
|
||||||
|
return createDefault(prop_name, prop.typeName(), prop.description(), prop.serialize());
|
||||||
return it->second(QString::fromStdString(prop_name), prop, scene, display_context);
|
return it->second(QString::fromStdString(prop_name), prop, scene, display_context);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -150,4 +151,22 @@ void PropertyFactory::addRemainingProperties(rviz::Property* root, mtc::Property
|
|||||||
new rviz::Property("no properties", QVariant(), QString(), root);
|
new rviz::Property("no properties", QVariant(), QString(), root);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rviz::Property* PropertyFactory::createDefault(const std::string& name, const std::string& type,
|
||||||
|
const std::string& description, const std::string& value,
|
||||||
|
rviz::Property* old)
|
||||||
|
{
|
||||||
|
if (old) { // reuse existing Property?
|
||||||
|
assert(old->getNameStd() == name);
|
||||||
|
old->setDescription(QString::fromStdString(description));
|
||||||
|
old->setValue(QString::fromStdString(value));
|
||||||
|
return old;
|
||||||
|
} else { // create new Property?
|
||||||
|
rviz::Property *result = new rviz::StringProperty(QString::fromStdString(name),
|
||||||
|
QString::fromStdString(value),
|
||||||
|
QString::fromStdString(description));
|
||||||
|
result->setReadOnly(true);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@ -94,6 +94,10 @@ public:
|
|||||||
/// create rviz::Property for given MTC Property
|
/// create rviz::Property for given MTC Property
|
||||||
rviz::Property* create(const std::string &prop_name, moveit::task_constructor::Property &prop,
|
rviz::Property* create(const std::string &prop_name, moveit::task_constructor::Property &prop,
|
||||||
const planning_scene::PlanningScene *scene, rviz::DisplayContext *display_context) const;
|
const planning_scene::PlanningScene *scene, rviz::DisplayContext *display_context) const;
|
||||||
|
/// create rviz::Property for property of given name, type, description, and value
|
||||||
|
static rviz::Property* createDefault(const std::string& name, const std::string& type,
|
||||||
|
const std::string& description, const std::string& value,
|
||||||
|
rviz::Property* old=nullptr);
|
||||||
|
|
||||||
/// create PropertyTreeModel for given Stage
|
/// create PropertyTreeModel for given Stage
|
||||||
rviz::PropertyTreeModel* createPropertyTreeModel(moveit::task_constructor::Stage &stage,
|
rviz::PropertyTreeModel* createPropertyTreeModel(moveit::task_constructor::Stage &stage,
|
||||||
|
|||||||
@ -129,7 +129,7 @@ RemoteTaskModel::Node::createProperty(const moveit_task_constructor_msgs::Proper
|
|||||||
auto& factory = PropertyFactory::instance();
|
auto& factory = PropertyFactory::instance();
|
||||||
// try to deserialize from msg (using registered functions)
|
// try to deserialize from msg (using registered functions)
|
||||||
boost::any value = Property::deserialize(prop.type, prop.value);
|
boost::any value = Property::deserialize(prop.type, prop.value);
|
||||||
if (!value.empty()) {
|
if (!value.empty()) { // if successful, create rviz::Property from mtc::Property using factory methods
|
||||||
auto it = properties_.insert(std::make_pair(prop.name, Property())).first;
|
auto it = properties_.insert(std::make_pair(prop.name, Property())).first;
|
||||||
it->second.setDescription(prop.description);
|
it->second.setDescription(prop.description);
|
||||||
it->second.setValue(value);
|
it->second.setValue(value);
|
||||||
@ -140,17 +140,8 @@ RemoteTaskModel::Node::createProperty(const moveit_task_constructor_msgs::Proper
|
|||||||
properties_.erase(it);
|
properties_.erase(it);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (old) { // reuse existing Property?
|
// otherwise create default, read-only rviz::Property by parsing serialized YAML
|
||||||
old->setDescription(QString::fromStdString(prop.description));
|
return factory.createDefault(prop.name, prop.type, prop.description, prop.value, old);
|
||||||
old->setValue(QString::fromStdString(prop.value));
|
|
||||||
return old;
|
|
||||||
} else { // create new Property?
|
|
||||||
rviz::Property *result = new rviz::StringProperty(QString::fromStdString(prop.name),
|
|
||||||
QString::fromStdString(prop.value),
|
|
||||||
QString::fromStdString(prop.description));
|
|
||||||
result->setReadOnly(true);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// return Node* corresponding to index
|
// return Node* corresponding to index
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user