36 #include <QStandardItemModel> 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);
45 item->setFlags(item->flags() & ~Qt::ItemIsEnabled);
46 if (w->currentIndex() ==
static_cast<int>(axis))
47 w->setCurrentIndex((axis + 1) % 3);
49 item->setFlags(item->flags() | Qt::ItemIsEnabled);
55 qRegisterMetaType<Eigen::Quaterniond>(
"Eigen::Quaterniond");
58 ui_->a1->setCurrentIndex(0);
59 ui_->a2->setCurrentIndex(1);
61 ui_->a3->setCurrentIndex(2);
64 q_ = Eigen::Quaterniond::Identity();
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,
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,
85 a[0] =
ui_->a1->currentIndex();
86 a[1] =
ui_->a2->currentIndex();
87 a[2] =
ui_->a3->currentIndex();
98 bool bFirstCall = !this->signalsBlocked();
99 this->blockSignals(
true);
102 QComboBox* origin =
dynamic_cast<QComboBox*
>(sender());
103 if (origin ==
ui_->a1)
105 if (origin ==
ui_->a2)
110 this->blockSignals(
false);
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]));
132 ui_->e1->blockSignals(
true);
133 ui_->e2->blockSignals(
true);
134 ui_->e3->blockSignals(
true);
140 ui_->e1->blockSignals(
false);
141 ui_->e2->blockSignals(
false);
142 ui_->e3->blockSignals(
false);
152 if (a1 > 2 || a2 > 2 || a3 > 2)
154 if (static_cast<int>(a1) ==
ui_->a1->currentIndex() &&
155 static_cast<int>(a2) ==
ui_->a2->currentIndex() &&
static_cast<int>(a3) ==
ui_->a3->currentIndex())
158 this->blockSignals(
true);
159 ui_->a3->setCurrentIndex(a3);
160 ui_->a2->setCurrentIndex(a2);
161 ui_->a1->setCurrentIndex(a1);
162 this->blockSignals(
false);
186 Eigen::Vector3d e =
q_.matrix().eulerAngles(a[0], a[1], a[2]);
static double from_degrees(double degrees)
static double to_degrees(double radians)