32 #include <QStringList>    33 #include <QDoubleSpinBox>    37 #include <boost/format.hpp>    38 #include <boost/assign/list_of.hpp>    47   QWidget* 
createEditor(QWidget* parent, 
const QStyleOptionViewItem& option) 
override;
    51   auto editor = 
new QDoubleSpinBox(parent);
    52   editor->setFrame(
false);
    54   editor->setSingleStep(1);
    55   editor->setAccelerated(
true);
    56   editor->setDecimals(0);
    57   connect(editor, 
static_cast<void (QDoubleSpinBox::*)(
double)
>(&QDoubleSpinBox::valueChanged), 
this,
    60   editor->setKeyboardTracking(
false);
    69                              const Eigen::Quaterniond& value,
    70                              const char* changed_slot,
    74              "Angles specified in degrees.\n"    75              "Choose axes with spec like xyz, zxz, or rpy.\n"    76              "Composition w.r.t. the static or rotating frame\n"    77              "is selected by prefixing with 's' or 'r' (default).",
    90   for (
int i = 0; i < 3; ++i) {
   103   Eigen::Quaterniond q;
   105     q = Eigen::AngleAxisd(euler[2], Eigen::Vector3d::Unit(
axes_[2])) *
   106         Eigen::AngleAxisd(euler[1], Eigen::Vector3d::Unit(
axes_[1])) *
   107         Eigen::AngleAxisd(euler[0], Eigen::Vector3d::Unit(
axes_[0]));
   109     q = Eigen::AngleAxisd(euler[0], Eigen::Vector3d::Unit(
axes_[0])) *
   110         Eigen::AngleAxisd(euler[1], Eigen::Vector3d::Unit(
axes_[1])) *
   111         Eigen::AngleAxisd(euler[2], Eigen::Vector3d::Unit(
axes_[2]));
   116     for (
int i = 0; i < 3; ++i) {
   118       if (!Eigen::internal::isApprox(deg, 
euler_[i]->getFloat())) {
   140   double euler[3] = {e1, e2, e3};
   145   static const std::vector<QString> xyzNames = boost::assign::list_of(
"x")(
"y")(
"z");
   146   static const std::vector<QString> rpyNames = boost::assign::list_of(
"roll")(
"pitch")(
"yaw");
   147   const std::vector<QString>* names = &xyzNames;
   151   QString sAxes = axes_spec;
   152   if (sAxes == 
"rpy") {
   155   } 
else if (sAxes == 
"ypr") {
   161   QString::iterator pc = sAxes.begin();
   174   if (sAxes.end() - pc != 3)
   176         (boost::format(
"Invalid axes spec: %s. Expecting 3 chars from [xyz]") % axes_spec.toStdString())
   181   for (uint i = 0; i < 3; ++i, ++pc) {
   182     int idx = pc->toLatin1() - 
'x';
   183     if (idx < 0 || idx > 2)
   185           (boost::format(
"invalid axis char: %c (only xyz allowed)") % pc->unicode()).str());
   186     if (i > 0 && axes[i - 1] == static_cast<uint>(idx))
   187       throw invalid_axes(
"consecutive axes need to be different");
   194   for (
int i = 0; i < 3; ++i) {
   205   static const QString statusAxes(
"Euler axes");
   206   static const QString statusAngles(
"Euler angles");
   208   const QRegExp axesSpec(
"\\s*([a-z]+)\\s*:?");
   209   QString 
s = value.toString();
   212   if (axesSpec.indexIn(s) != -1) {
   220     s = s.mid(axesSpec.matchedLength());
   229   if (s.trimmed().isEmpty())
   233   QStringList strings = s.split(
';');
   234   double euler[3] = {0, 0, 0};
   236   for (
int i = 0; i < 3 && ok; ++i) {
   237     if (i < strings.size())
   246   if (strings.size() != 3 && strings.size() != 1) {
   260   for (
int i = 0; i < 3; ++i)
   278     std::swap(e[0], e[2]);
   285   QString 
s = QString(
"%1: %2; %3; %4")
   287                   .arg(
euler_[0]->getFloat(), 0, 
'f', 1)
   288                   .arg(
euler_[1]->getFloat(), 0, 
'f', 1)
   289                   .arg(
euler_[2]->getFloat(), 0, 
'f', 1);
   290   value_ = s.replace(
".0", 
"");
   302     for (
int i = 0; i < 3; ++i)
   321   for (
int i = 0; i < 3; ++i)
 
EulerProperty(Property *parent=nullptr, const QString &name=QString(), const Eigen::Quaterniond &value=Eigen::Quaterniond::Identity(), const char *changed_slot=nullptr, QObject *receiver=nullptr)
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children. 
SpinBoxFloatProperty * euler_[3]
void quaternionChanged(Eigen::Quaterniond q)
Eigen::Quaterniond quaternion_
bool mapGetFloat(const QString &key, float *value_out) const 
virtual void setName(const QString &name)
void statusUpdate(rviz::StatusProperty::Level, const QString &, const QString &)
void setEulerAngles(double euler[3], bool normalize)
invalid_axes(const std::string &msg)
bool mapGetString(const QString &key, QString *value_out) const 
virtual bool setValue(const QVariant &new_value)
void mapSetValue(const QString &key, QVariant value)
bool setFloat(float new_value)
void save(Config config) const override
QWidget * createEditor(QWidget *parent, const QStyleOptionViewItem &option) 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)
static double from_degrees(double degrees)
bool setValue(const QVariant &value) override
void setQuaternion(const Eigen::Quaterniond &q)
void setEulerAxes(const QString &axes_spec)
static double to_degrees(double radians)
TFSIMD_FORCE_INLINE Vector3 & normalize()
bool ignore_child_updates_
void updateFromChildren()
virtual QVariant getValue() const 
FloatProperty(const QString &name=QString(), float default_value=0, const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)