Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 #ifndef EULER_PROPERTY_H
00033 #define EULER_PROPERTY_H
00034 
00035 #include <Eigen/Geometry>
00036 #include <stdexcept>
00037 
00038 #include "rviz/properties/property.h"
00039 
00040 namespace rviz
00041 {
00042 
00043 class FloatProperty;
00044 
00045 class EulerProperty: public Property
00046 {
00047   Q_OBJECT
00048 public:
00049   class invalid_axes : public std::invalid_argument {
00050   public:
00051     invalid_axes(const std::string &msg);
00052   };
00053 
00054   EulerProperty(Property* parent = 0,
00055                 const QString& name = QString(),
00056                 const Eigen::Quaterniond& value = Eigen::Quaterniond::Identity(),
00057                 const char *changed_slot = 0,
00058                 QObject* receiver = 0);
00059 
00060   Eigen::Quaterniond getQuaternion() const {return quaternion_;}
00061   virtual bool setValue(const QVariant& value);
00062 
00065   virtual void load(const Config& config);
00066   virtual void save(Config config) const;
00067 
00069   virtual void setReadOnly(bool read_only);
00070   bool getAnglesReadOnly() {return angles_read_only_;}
00071 
00072 public Q_SLOTS:
00073   void setQuaternion(const Eigen::Quaterniond &q);
00074   void setEulerAngles(double euler[3], bool normalize);
00075   void setEulerAngles(double e1, double e2, double e3, bool normalize);
00080   void setEulerAxes(const QString &axes_spec);
00081 
00082 private Q_SLOTS:
00083   void updateFromChildren();
00084   void emitAboutToChange();
00085 
00086 Q_SIGNALS:
00088   void quaternionChanged(Eigen::Quaterniond q);
00090   void statusUpdate(int, const QString&, const QString&);
00091 
00092 private:
00093   void updateAngles(const Eigen::Quaterniond &q);
00094   void updateString();
00095 
00096   Eigen::Quaterniond quaternion_;
00097   QString   axes_string_;
00098   uint      axes_[3]; 
00099   bool      fixed_;
00100   FloatProperty* euler_[3];
00101   bool ignore_child_updates_;
00102   bool angles_read_only_;
00103   bool update_string_; 
00104 };
00105 
00106 } 
00107 
00108 #endif // EULER_PROPERTY_H