Go to the documentation of this file.
32 #ifndef EULER_PROPERTY_H
33 #define EULER_PROPERTY_H
35 #include <Eigen/Geometry>
43 class SpinBoxFloatProperty;
56 const QString& name = QString(),
57 const Eigen::Quaterniond& value = Eigen::Quaterniond::Identity(),
58 const char* changed_slot =
nullptr,
59 QObject* receiver =
nullptr);
64 bool setValue(
const QVariant& value)
override;
80 void setEulerAngles(
double e1,
double e2,
double e3,
bool normalize);
113 #endif // EULER_PROPERTY_H
void updateFromChildren()
void statusUpdate(rviz::StatusProperty::Level, const QString &, const QString &)
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Eigen::Quaterniond getQuaternion() const
Eigen::Quaterniond quaternion_
void setEulerAxes(const QString &axes_spec)
void setEulerAngles(double euler[3], bool normalize)
void save(Config config) const override
bool ignore_child_updates_
EulerProperty(Property *parent=nullptr, const QString &name=QString(), const Eigen::Quaterniond &value=Eigen::Quaterniond::Identity(), const char *changed_slot=nullptr, QObject *receiver=nullptr)
void setQuaternion(const Eigen::Quaterniond &q)
SpinBoxFloatProperty * euler_[3]
void quaternionChanged(Eigen::Quaterniond q)
invalid_axes(const std::string &msg)
bool setValue(const QVariant &value) override
void load(const Config &config) override
Load the value of this property and/or its children from the given Config node.
void updateAngles(const Eigen::Quaterniond &q)
agni_tf_tools
Author(s): Robert Haschke
autogenerated on Tue Oct 15 2024 02:57:48