Skip to content

Commit fb0fa19

Browse files
committed
[POC] add message property as rviz property
1 parent 5d419bd commit fb0fa19

File tree

1 file changed

+30
-13
lines changed

1 file changed

+30
-13
lines changed

visualization/motion_planning_tasks/properties/property_factory.cpp

Lines changed: 30 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -43,40 +43,57 @@
4343
#include <rviz/properties/property_tree_model.h>
4444
#include <rviz/properties/string_property.h>
4545
#include <rviz/properties/float_property.h>
46+
#include <rviz/properties/vector_property.h>
47+
48+
#include <geometry_msgs/Vector3Stamped.h>
4649

4750
namespace mtc = ::moveit::task_constructor;
4851

4952
namespace moveit_rviz_plugin {
5053

51-
static rviz::StringProperty* stringFactory(const QString& name, mtc::Property& mtc_prop,
52-
const planning_scene::PlanningScene* /*unused*/,
53-
rviz::DisplayContext* /*unused*/) {
54-
std::string value;
55-
if (!mtc_prop.value().empty())
56-
value = boost::any_cast<std::string>(mtc_prop.value());
57-
rviz::StringProperty* rviz_prop =
54+
namespace {
55+
56+
rviz::Property* stringFactory(const QString& name, mtc::Property& mtc_prop,
57+
const planning_scene::PlanningScene* /*scene*/, rviz::DisplayContext* /*context*/) {
58+
std::string value{ mtc_prop.defined() ? mtc_prop.value<std::string>() : "" };
59+
auto* rviz_prop =
5860
new rviz::StringProperty(name, QString::fromStdString(value), QString::fromStdString(mtc_prop.description()));
5961
QObject::connect(rviz_prop, &rviz::StringProperty::changed,
6062
[rviz_prop, &mtc_prop]() { mtc_prop.setValue(rviz_prop->getStdString()); });
6163
return rviz_prop;
6264
}
65+
6366
template <typename T>
64-
static rviz::FloatProperty* floatFactory(const QString& name, mtc::Property& mtc_prop,
65-
const planning_scene::PlanningScene* /*unused*/,
66-
rviz::DisplayContext* /*unused*/) {
67-
T value = !mtc_prop.value().empty() ? boost::any_cast<T>(mtc_prop.value()) : T();
67+
static rviz::Property* floatFactory(const QString& name, mtc::Property& mtc_prop,
68+
const planning_scene::PlanningScene* /*unused*/, rviz::DisplayContext* /*unused*/) {
69+
T value{ mtc_prop.defined() ? mtc_prop.value<T>() : static_cast<T>(0.0) };
6870
rviz::FloatProperty* rviz_prop =
6971
new rviz::FloatProperty(name, value, QString::fromStdString(mtc_prop.description()));
7072
QObject::connect(rviz_prop, &rviz::FloatProperty::changed,
7173
[rviz_prop, &mtc_prop]() { mtc_prop.setValue(T(rviz_prop->getFloat())); });
7274
return rviz_prop;
7375
}
7476

77+
rviz::Property* vector3Factory(const QString& name, mtc::Property& mtc_prop,
78+
const planning_scene::PlanningScene* /*scene*/, rviz::DisplayContext* /*context*/) {
79+
auto value{ mtc_prop.defined() ? mtc_prop.value<geometry_msgs::Vector3Stamped>() : geometry_msgs::Vector3Stamped{} };
80+
81+
auto* rviz_prop =
82+
new rviz::VectorProperty(name, Ogre::Vector3::ZERO, QString::fromStdString(mtc_prop.description()));
83+
rviz_prop->setVector(Ogre::Vector3{ static_cast<Ogre::Real>(value.vector.x), static_cast<Ogre::Real>(value.vector.y),
84+
static_cast<Ogre::Real>(value.vector.z) });
85+
86+
return rviz_prop;
87+
}
88+
89+
} // namespace
90+
7591
PropertyFactory::PropertyFactory() {
76-
// register some standard types
92+
// register standard types
93+
registerType<std::string>(&stringFactory);
7794
registerType<float>(&floatFactory<float>);
7895
registerType<double>(&floatFactory<double>);
79-
registerType<std::string>(&stringFactory);
96+
registerType<geometry_msgs::Vector3Stamped>(&vector3Factory);
8097
}
8198

8299
PropertyFactory& PropertyFactory::instance() {

0 commit comments

Comments
 (0)