EulerWidget.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 "EulerWidget.h"
33 #include "ui_euler.h"
34 
35 #include <angles/angles.h>
36 #include <QStandardItemModel>
37 #include <iostream>
38 
39 // ensure different axes for consecutive operations
40 static void disableAxis(QComboBox* w, unsigned int axis) {
41  const QStandardItemModel* model = qobject_cast<const QStandardItemModel*>(w->model());
42  for (unsigned int i = 0; i < 3; ++i) {
43  QStandardItem* item = model->item(i);
44  if (i == axis) {
45  item->setFlags(item->flags() & ~Qt::ItemIsEnabled);
46  if (w->currentIndex() == static_cast<int>(axis))
47  w->setCurrentIndex((axis + 1) % 3);
48  } else {
49  item->setFlags(item->flags() | Qt::ItemIsEnabled);
50  }
51  }
52 }
53 
54 EulerWidget::EulerWidget(QWidget* parent) : QWidget(parent), ui_(new Ui::EulerWidget) {
55  qRegisterMetaType<Eigen::Quaterniond>("Eigen::Quaterniond");
56 
57  ui_->setupUi(this);
58  ui_->a1->setCurrentIndex(0);
59  ui_->a2->setCurrentIndex(1);
60  disableAxis(ui_->a2, 0);
61  ui_->a3->setCurrentIndex(2);
62  disableAxis(ui_->a3, 1);
63 
64  q_ = Eigen::Quaterniond::Identity();
65  updateAngles();
66 
67  // react to axis changes
68  connect(ui_->a1, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged), this,
70  connect(ui_->a2, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged), this,
72  connect(ui_->a3, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged), this,
74 
75  // react to angle changes
76  connect(ui_->e1, static_cast<void (QDoubleSpinBox::*)(double)>(&QDoubleSpinBox::valueChanged), this,
78  connect(ui_->e2, static_cast<void (QDoubleSpinBox::*)(double)>(&QDoubleSpinBox::valueChanged), this,
80  connect(ui_->e3, static_cast<void (QDoubleSpinBox::*)(double)>(&QDoubleSpinBox::valueChanged), this,
82 }
83 
84 void EulerWidget::getGuiAxes(uint a[]) const {
85  a[0] = ui_->a1->currentIndex();
86  a[1] = ui_->a2->currentIndex();
87  a[2] = ui_->a3->currentIndex();
88 }
89 
90 void EulerWidget::getGuiAngles(double e[3]) const {
91  e[0] = angles::from_degrees(ui_->e1->value());
92  e[1] = angles::from_degrees(ui_->e2->value());
93  e[2] = angles::from_degrees(ui_->e3->value());
94 }
95 
96 
97 void EulerWidget::axisChanged(int axis) {
98  bool bFirstCall = !this->signalsBlocked();
99  this->blockSignals(true);
100 
101  // ensure different axes for consecutive operations
102  QComboBox* origin = dynamic_cast<QComboBox*>(sender());
103  if (origin == ui_->a1)
104  disableAxis(ui_->a2, axis);
105  if (origin == ui_->a2)
106  disableAxis(ui_->a3, axis);
107 
108  if (bFirstCall) {
109  updateAngles();
110  this->blockSignals(false);
111 
112  emit axesChanged(ui_->a1->currentIndex(), ui_->a2->currentIndex(), ui_->a3->currentIndex());
113  }
114 }
115 
116 void EulerWidget::angleChanged(double /*angle*/) {
117  double e[3];
118  getGuiAngles(e);
119  setEulerAngles(e[0], e[1], e[2], false);
120 }
121 
122 void EulerWidget::setEulerAngles(double e1, double e2, double e3, bool normalize) {
123  uint a[3];
124  getGuiAxes(a);
125  Eigen::Quaterniond q = Eigen::AngleAxisd(e1, Eigen::Vector3d::Unit(a[0])) *
126  Eigen::AngleAxisd(e2, Eigen::Vector3d::Unit(a[1])) *
127  Eigen::AngleAxisd(e3, Eigen::Vector3d::Unit(a[2]));
128  if (normalize)
129  setValue(q);
130  else {
131  // do not trigger angleChanged() again
132  ui_->e1->blockSignals(true);
133  ui_->e2->blockSignals(true);
134  ui_->e3->blockSignals(true);
135 
136  ui_->e1->setValue(angles::to_degrees(e1));
137  ui_->e2->setValue(angles::to_degrees(e2));
138  ui_->e3->setValue(angles::to_degrees(e3));
139 
140  ui_->e1->blockSignals(false);
141  ui_->e2->blockSignals(false);
142  ui_->e3->blockSignals(false);
143 
144  if (q_.isApprox(q))
145  return;
146  q_ = q;
147  emit valueChanged(q);
148  }
149 }
150 
151 void EulerWidget::setEulerAxes(uint a1, uint a2, uint a3) {
152  if (a1 > 2 || a2 > 2 || a3 > 2)
153  return;
154  if (static_cast<int>(a1) == ui_->a1->currentIndex() &&
155  static_cast<int>(a2) == ui_->a2->currentIndex() && static_cast<int>(a3) == ui_->a3->currentIndex())
156  return;
157 
158  this->blockSignals(true);
159  ui_->a3->setCurrentIndex(a3);
160  ui_->a2->setCurrentIndex(a2);
161  ui_->a1->setCurrentIndex(a1);
162  this->blockSignals(false);
163  updateAngles();
164 
165  emit axesChanged(a1, a2, a3);
166 }
167 
168 
169 void EulerWidget::setValue(const Eigen::Quaterniond& q) {
170  if (q_.isApprox(q))
171  return;
172  q_ = q;
173  updateAngles();
174  emit valueChanged(q);
175 }
176 
177 const Eigen::Quaterniond& EulerWidget::value() const {
178  return q_;
179 }
180 
181 
183  // ensure different axes for consecutive operations
184  uint a[3];
185  getGuiAxes(a);
186  Eigen::Vector3d e = q_.matrix().eulerAngles(a[0], a[1], a[2]);
187  setEulerAngles(e[0], e[1], e[2], false);
188 }
void getGuiAngles(double e[]) const
retrieve angles from GUI
Definition: EulerWidget.cpp:90
void axisChanged(int axis)
Definition: EulerWidget.cpp:97
EulerWidget(QWidget *parent=nullptr)
Definition: EulerWidget.cpp:54
void setEulerAxes(uint a1, uint a2, uint a3)
const Eigen::Quaterniond & value() const
void angleChanged(double angle)
Definition: EulerWidget.h:37
Ui::EulerWidget * ui_
Definition: EulerWidget.h:76
void axesChanged(uint a1, uint a2, uint a3)
euler axis selection changed
static double from_degrees(double degrees)
void setEulerAngles(double e1, double e2, double e3, bool normalize)
static double to_degrees(double radians)
void valueChanged(const Eigen::Quaterniond &q)
quaternion value has changed
Eigen::Quaterniond q_
Definition: EulerWidget.h:75
void setValue(const Eigen::Quaterniond &q)
static void disableAxis(QComboBox *w, unsigned int axis)
Definition: EulerWidget.cpp:40
void getGuiAxes(uint a[3]) const
retrieve indices of axes selected in GUI
Definition: EulerWidget.cpp:84
void updateAngles()


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