32 #ifndef EULER_PROPERTY_H 33 #define EULER_PROPERTY_H 35 #include <Eigen/Geometry> 55 const QString& name = QString(),
56 const Eigen::Quaterniond& value = Eigen::Quaterniond::Identity(),
57 const char *changed_slot = 0,
58 QObject* receiver = 0);
61 virtual bool setValue(
const QVariant& value);
75 void setEulerAngles(
double e1,
double e2,
double e3,
bool normalize);
108 #endif // EULER_PROPERTY_H virtual bool setValue(const QVariant &value)
Eigen::Quaterniond getQuaternion() const
virtual void setReadOnly(bool read_only)
Overridden from Property to propagate read-only-ness to children.
void quaternionChanged(Eigen::Quaterniond q)
Eigen::Quaterniond quaternion_
void setEulerAngles(double euler[3], bool normalize)
invalid_axes(const std::string &msg)
void updateAngles(const Eigen::Quaterniond &q)
void setQuaternion(const Eigen::Quaterniond &q)
void setEulerAxes(const QString &axes_spec)
FloatProperty * euler_[3]
TFSIMD_FORCE_INLINE Vector3 & normalize()
bool ignore_child_updates_
void updateFromChildren()
virtual void save(Config config) const
virtual void load(const Config &config)
Load the value of this property and/or its children from the given Config node.
EulerProperty(Property *parent=0, const QString &name=QString(), const Eigen::Quaterniond &value=Eigen::Quaterniond::Identity(), const char *changed_slot=0, QObject *receiver=0)
void statusUpdate(int, const QString &, const QString &)