euler_property.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, Bielefeld University, CITEC
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Robert Haschke <rhaschke@techfak.uni-bielefeld.de>
30  */
31 
32 #include <QStringList>
33 #include <QDoubleSpinBox>
36 #include <angles/angles.h>
37 #include <boost/format.hpp>
38 #include <boost/assign/list_of.hpp>
39 #include "euler_property.h"
40 
41 namespace rviz {
42 
44 {
45 public:
47  QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option) override;
48 };
49 
50 QWidget* SpinBoxFloatProperty::createEditor(QWidget* parent, const QStyleOptionViewItem& /*option*/) {
51  auto editor = new QDoubleSpinBox(parent);
52  editor->setFrame(false);
53  editor->setRange(getMin(), getMax());
54  editor->setSingleStep(1);
55  editor->setAccelerated(true);
56  editor->setDecimals(0);
57  connect(editor, static_cast<void (QDoubleSpinBox::*)(double)>(&QDoubleSpinBox::valueChanged), this,
59  // do not react to text edits immediately, but only when editing is finished
60  editor->setKeyboardTracking(false);
61  return editor;
62 }
63 
64 EulerProperty::invalid_axes::invalid_axes(const std::string& msg) : std::invalid_argument(msg) {
65 }
66 
68  const QString& name,
69  const Eigen::Quaterniond& value,
70  const char* changed_slot,
71  QObject* receiver)
72  : Property(name,
73  QVariant(),
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).",
78  parent,
79  changed_slot,
80  receiver)
81  , quaternion_(value)
82  , ignore_child_updates_(false)
83  , angles_read_only_(false)
84  , update_string_(true) {
85  euler_[0] = new SpinBoxFloatProperty("", 0, "rotation angle about first axis", this);
86  euler_[1] = new SpinBoxFloatProperty("", 0, "rotation angle about second axis", this);
87  euler_[2] = new SpinBoxFloatProperty("", 0, "rotation angle about third axis", this);
88  setEulerAxes("rpy");
89 
90  for (int i = 0; i < 3; ++i) {
93  }
94 }
95 
96 void EulerProperty::setQuaternion(const Eigen::Quaterniond& q) {
97  if (quaternion_.isApprox(q))
98  return;
99  updateAngles(q); // this will also emit changed signals (in setEulerAngles)
100 }
101 
102 void EulerProperty::setEulerAngles(double euler[], bool normalize) {
103  Eigen::Quaterniond q;
104  if (fixed_)
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]));
108  else
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]));
112 
113  if (normalize)
114  setQuaternion(q);
115  else {
116  for (int i = 0; i < 3; ++i) {
117  float deg = angles::to_degrees(euler[i]);
118  if (!Eigen::internal::isApprox(deg, euler_[i]->getFloat())) {
119  update_string_ = true;
121  euler_[i]->setValue(deg);
122  }
123  }
124 
125  if (!quaternion_.isApprox(q)) {
126  Q_EMIT aboutToChange();
127  quaternion_ = q;
128  Q_EMIT quaternionChanged(q);
129  } else if (update_string_) {
130  Q_EMIT aboutToChange();
131  } else { // there is nothing to update at all
132  return;
133  }
134  updateString();
135  Q_EMIT changed();
136  }
137 }
138 
139 void EulerProperty::setEulerAngles(double e1, double e2, double e3, bool normalize) {
140  double euler[3] = {e1, e2, e3};
141  setEulerAngles(euler, normalize);
142 }
143 
144 void EulerProperty::setEulerAxes(const QString& axes_spec) {
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;
148 
149  if (axes_string_ == axes_spec)
150  return;
151  QString sAxes = axes_spec;
152  if (sAxes == "rpy") {
153  sAxes = "sxyz";
154  names = &rpyNames;
155  } else if (sAxes == "ypr") {
156  sAxes = "rzyx";
157  names = &rpyNames;
158  }
159 
160  // static or rotated frame order?
161  QString::iterator pc = sAxes.begin();
162  bool fixed;
163  if (*pc == 's')
164  fixed = true;
165  else if (*pc == 'r')
166  fixed = false;
167  else {
168  fixed = false;
169  --pc;
170  }
171  ++pc; // advance to first axis char
172 
173  // need to have 3 axes specs
174  if (sAxes.end() - pc != 3)
175  throw invalid_axes(
176  (boost::format("Invalid axes spec: %s. Expecting 3 chars from [xyz]") % axes_spec.toStdString())
177  .str());
178 
179  // parse axes specs into indexes
180  uint axes[3];
181  for (uint i = 0; i < 3; ++i, ++pc) {
182  int idx = pc->toLatin1() - 'x';
183  if (idx < 0 || idx > 2)
184  throw invalid_axes(
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");
188  axes[i] = idx;
189  }
190 
191  // everything OK: accept changes
192  axes_string_ = axes_spec;
193  fixed_ = fixed;
194  for (int i = 0; i < 3; ++i) {
195  axes_[i] = axes[i];
196  euler_[i]->setName((*names)[axes[i]]);
197  }
198 
199  // finally compute euler angles matching the new axes
200  update_string_ = true;
202 }
203 
204 bool EulerProperty::setValue(const QVariant& value) {
205  static const QString statusAxes("Euler axes");
206  static const QString statusAngles("Euler angles");
207 
208  const QRegExp axesSpec("\\s*([a-z]+)\\s*:?");
209  QString s = value.toString();
210 
211  // parse axes spec
212  if (axesSpec.indexIn(s) != -1) {
213  try {
214  setEulerAxes(axesSpec.cap(1));
215  Q_EMIT statusUpdate(StatusProperty::Ok, statusAxes, axes_string_);
216  } catch (const invalid_axes& e) {
217  Q_EMIT statusUpdate(StatusProperty::Warn, statusAxes, e.what());
218  return false;
219  }
220  s = s.mid(axesSpec.matchedLength());
221  }
222 
223  // in read-only mode only allow to change axes, but not angles
224  if (angles_read_only_) {
225  Q_EMIT statusUpdate(StatusProperty::Warn, statusAngles, "read-only");
226  return true;
227  }
228 
229  if (s.trimmed().isEmpty())
230  return true; // allow change of axes only
231 
232  // parse angles
233  QStringList strings = s.split(';');
234  double euler[3] = {0, 0, 0};
235  bool ok = true;
236  for (int i = 0; i < 3 && ok; ++i) {
237  if (i < strings.size())
238  euler[i] = angles::from_degrees(strings[i].toDouble(&ok));
239  else // providing a single value will set all angles to this (1st) value
240  euler[i] = euler[0];
241  }
242  if (!ok) {
243  Q_EMIT statusUpdate(StatusProperty::Warn, statusAngles, "failed to parse angle value");
244  return false;
245  }
246  if (strings.size() != 3 && strings.size() != 1) {
247  Q_EMIT statusUpdate(StatusProperty::Warn, statusAngles, "expecting 3 semicolon-separated values");
248  return false;
249  }
250 
251  Q_EMIT statusUpdate(StatusProperty::Ok, statusAngles, "");
252  setEulerAngles(euler, false);
253  return true;
254 }
255 
258  return;
259  double euler[3];
260  for (int i = 0; i < 3; ++i)
261  euler[i] = angles::from_degrees(euler_[i]->getValue().toFloat());
262 
263  ignore_child_updates_ = true;
264  setEulerAngles(euler, false);
265  ignore_child_updates_ = false;
266 }
267 
270  return;
271  Q_EMIT aboutToChange();
272 }
273 
274 void EulerProperty::updateAngles(const Eigen::Quaterniond& q) {
275  Eigen::Vector3d e;
276  if (fixed_) {
277  e = q.matrix().eulerAngles(axes_[2], axes_[1], axes_[0]);
278  std::swap(e[0], e[2]);
279  } else
280  e = q.matrix().eulerAngles(axes_[0], axes_[1], axes_[2]);
281  setEulerAngles(e.data(), false);
282 }
283 
285  QString s = QString("%1: %2; %3; %4")
286  .arg(axes_string_)
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", "");
291  update_string_ = false; // reset update flag
292 }
293 
294 void EulerProperty::load(const Config& config) {
295  QString axes;
296  float euler[3];
297  if (config.mapGetString("axes", &axes) && config.mapGetFloat("e1", euler + 0) &&
298  config.mapGetFloat("e2", euler + 1) && config.mapGetFloat("e3", euler + 2)) {
299  // Setting the value once is better than letting the Property class
300  // load all parameters independently, which would result in 4 update calls
301  setEulerAxes(axes);
302  for (int i = 0; i < 3; ++i)
303  euler[i] = angles::from_degrees(euler[i]);
304  setEulerAngles(euler[0], euler[1], euler[2], false);
305  }
306 }
307 
308 void EulerProperty::save(Config config) const {
309  // Saving the child values explicitly avoids having Property::save()
310  // save the summary string version of the property.
311  config.mapSetValue("axes", axes_string_);
312  config.mapSetValue("e1", euler_[0]->getValue());
313  config.mapSetValue("e2", euler_[1]->getValue());
314  config.mapSetValue("e3", euler_[2]->getValue());
315 }
316 
317 void EulerProperty::setReadOnly(bool read_only) {
318  // read-only mode should allow for changing axes, but not angles
319  angles_read_only_ = read_only;
320  // do not pass read-only to base class, but only to children
321  for (int i = 0; i < 3; ++i)
322  euler_[i]->setReadOnly(read_only);
323 }
324 
325 } // end namespace rviz
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_
XmlRpcServer s
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)
QVariant value_
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()
void aboutToChange()
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)


agni_tf_tools
Author(s): Robert Haschke
autogenerated on Tue Apr 13 2021 02:29:55