#include <rotation_property.h>

| Public Slots | |
| void | setEulerAngles (double euler[3], bool normalize) | 
| void | setEulerAngles (double e1, double e2, double e3, bool normalize) | 
| void | setEulerAxes (const QString &axes) | 
| void | setQuaternion (const Eigen::Quaterniond &q) | 
| Signals | |
| void | quaternionChanged (Eigen::Quaterniond q) | 
| void | statusUpdate (int, const QString &, const QString &) | 
| Public Member Functions | |
| Eigen::Quaterniond | getQuaternion () const | 
| virtual void | load (const rviz::Config &config) | 
| Load the value of this property and/or its children from the given Config node. | |
| RotationProperty (Property *parent=0, const QString &name=QString(), const Eigen::Quaterniond &value=Eigen::Quaterniond::Identity(), const char *changed_slot=0, QObject *receiver=0) | |
| virtual void | save (rviz::Config config) const | 
| virtual void | setReadOnly (bool read_only) | 
| Overridden from Property to propagate read-only-ness to children. | |
| virtual bool | setValue (const QVariant &value) | 
| Private Slots | |
| void | updateFromEuler () | 
| void | updateFromQuaternion () | 
| Private Member Functions | |
| void | updateString () | 
| Private Attributes | |
| rviz::EulerProperty * | euler_property_ | 
| bool | ignore_quaternion_property_updates_ | 
| rviz::QuaternionProperty * | quaternion_property_ | 
| bool | show_euler_string_ | 
Definition at line 45 of file rotation_property.h.
| agni_tf_tools::RotationProperty::RotationProperty | ( | Property * | parent = 0, | 
| const QString & | name = QString(), | ||
| const Eigen::Quaterniond & | value = Eigen::Quaterniond::Identity(), | ||
| const char * | changed_slot = 0, | ||
| QObject * | receiver = 0 | ||
| ) | 
Definition at line 39 of file rotation_property.cpp.
| Eigen::Quaterniond agni_tf_tools::RotationProperty::getQuaternion | ( | ) | const | 
Definition at line 64 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::load | ( | const rviz::Config & | config | ) |  [virtual] | 
Load the value of this property and/or its children from the given Config node.
Reimplemented from rviz::Property.
Definition at line 148 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::quaternionChanged | ( | Eigen::Quaterniond | q | ) |  [signal] | 
signal emitted when quaternion value has changed
| void agni_tf_tools::RotationProperty::save | ( | rviz::Config | config | ) | const  [virtual] | 
Reimplemented from rviz::Property.
Definition at line 154 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::setEulerAngles | ( | double | euler[3], | 
| bool | normalize | ||
| ) |  [slot] | 
| void agni_tf_tools::RotationProperty::setEulerAngles | ( | double | e1, | 
| double | e2, | ||
| double | e3, | ||
| bool | normalize | ||
| ) |  [slot] | 
Definition at line 113 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::setEulerAxes | ( | const QString & | axes | ) |  [slot] | 
Definition at line 118 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::setQuaternion | ( | const Eigen::Quaterniond & | q | ) |  [slot] | 
Definition at line 69 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::setReadOnly | ( | bool | read_only | ) |  [virtual] | 
Overridden from Property to propagate read-only-ness to children.
Reimplemented from rviz::Property.
Definition at line 160 of file rotation_property.cpp.
| bool agni_tf_tools::RotationProperty::setValue | ( | const QVariant & | value | ) |  [virtual] | 
Reimplemented from rviz::Property.
Definition at line 123 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::statusUpdate | ( | int | , | 
| const QString & | , | ||
| const QString & | |||
| ) |  [signal] | 
signal emitted to indicate error status, e.g. to a rviz::Display
| void agni_tf_tools::RotationProperty::updateFromEuler | ( | ) |  [private, slot] | 
Definition at line 78 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::updateFromQuaternion | ( | ) |  [private, slot] | 
Definition at line 89 of file rotation_property.cpp.
| void agni_tf_tools::RotationProperty::updateString | ( | ) |  [private] | 
Definition at line 136 of file rotation_property.cpp.
Definition at line 84 of file rotation_property.h.
Definition at line 86 of file rotation_property.h.
Definition at line 85 of file rotation_property.h.
| bool agni_tf_tools::RotationProperty::show_euler_string_  [private] | 
Definition at line 87 of file rotation_property.h.