EditConstraintDialog.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2019, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "ui_editConstraintDialog.h"
30 
32 #include <iostream>
33 
34 #ifndef M_PI
35 #define M_PI 3.14159265358979323846
36 #endif
37 
38 namespace rtabmap {
39 
40 EditConstraintDialog::EditConstraintDialog(const Transform & constraint, const cv::Mat & covariance, QWidget * parent) :
41  QDialog(parent)
42 {
43  _ui = new Ui_EditConstraintDialog();
44  _ui->setupUi(this);
45 
46  float x,y,z,roll,pitch,yaw;
47  constraint.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
48  _ui->x->setValue(x);
49  _ui->y->setValue(y);
50  _ui->z->setValue(z);
51  _ui->roll->setValue(roll);
52  _ui->pitch->setValue(pitch);
53  _ui->yaw->setValue(yaw);
54 
55  UASSERT(covariance.empty() || (covariance.cols == 6 && covariance.rows == 6 && covariance.type() == CV_64FC1));
56 
57  _ui->checkBox_radians->setChecked(true);
58  _ui->linear_sigma_x->setValue(covariance.empty() || covariance.at<double>(0,0)>=9999 || covariance.at<double>(0,0)<=0?0:sqrt(covariance.at<double>(0,0)));
59  _ui->linear_sigma_y->setValue(covariance.empty() || covariance.at<double>(1,1)>=9999 || covariance.at<double>(1,1)<=0?0:sqrt(covariance.at<double>(1,1)));
60  _ui->linear_sigma_z->setValue(covariance.empty() || covariance.at<double>(2,2)>=9999 || covariance.at<double>(2,2)<=0?0:sqrt(covariance.at<double>(2,2)));
61  _ui->angular_sigma_roll->setValue(covariance.empty() || covariance.at<double>(3,3)>=9999 || covariance.at<double>(3,3)<=0?0:sqrt(covariance.at<double>(3,3)));
62  _ui->angular_sigma_pitch->setValue(covariance.empty() || covariance.at<double>(4,4)>=9999 || covariance.at<double>(4,4)<=0?0:sqrt(covariance.at<double>(4,4)));
63  _ui->angular_sigma_yaw->setValue(covariance.empty() || covariance.at<double>(5,5)>=9999 || covariance.at<double>(5,5)<=0?0:sqrt(covariance.at<double>(5,5)));
64 
65  connect(_ui->checkBox_radians, SIGNAL(stateChanged(int)), this, SLOT(switchUnits()));
66 }
67 
69 {
70  delete _ui;
71 }
72 
74 {
75  _ui->groupBox_pose->setVisible(visible);
76 }
78 {
79  _ui->groupBox_covariance->setVisible(visible);
80 }
81 
83 {
84  double conversion = 180.0/M_PI;
85  if(_ui->checkBox_radians->isChecked())
86  {
87  conversion = M_PI/180.0;
88  }
89  QVector<QDoubleSpinBox*> boxes;
90  boxes.push_back(_ui->roll);
91  boxes.push_back(_ui->pitch);
92  boxes.push_back(_ui->yaw);
93  boxes.push_back(_ui->angular_sigma_roll);
94  boxes.push_back(_ui->angular_sigma_pitch);
95  boxes.push_back(_ui->angular_sigma_yaw);
96  for(int i=0; i<boxes.size(); ++i)
97  {
98  double value = boxes[i]->value()*conversion;
99  if(_ui->checkBox_radians->isChecked())
100  {
101  if(boxes[i]!=_ui->angular_sigma_roll && boxes[i]!=_ui->angular_sigma_pitch && boxes[i]!=_ui->angular_sigma_yaw)
102  {
103  boxes[i]->setMinimum(-M_PI);
104  }
105  boxes[i]->setMaximum(M_PI);
106  boxes[i]->setSuffix(" rad");
107  boxes[i]->setSingleStep(0.01);
108  }
109  else
110  {
111  if(boxes[i]!=_ui->angular_sigma_roll && boxes[i]!=_ui->angular_sigma_pitch && boxes[i]!=_ui->angular_sigma_yaw)
112  {
113  boxes[i]->setMinimum(-180);
114  }
115  boxes[i]->setMaximum(180);
116  boxes[i]->setSuffix(" deg");
117  boxes[i]->setSingleStep(1);
118  }
119  boxes[i]->setValue(value);
120  }
121 }
122 
124 {
125  double conversion = 1.0f;
126  if(!_ui->checkBox_radians->isChecked())
127  {
128  conversion = M_PI/180.0;
129  }
130  return Transform(_ui->x->value(), _ui->y->value(), _ui->z->value(), _ui->roll->value()*conversion, _ui->pitch->value()*conversion, _ui->yaw->value()*conversion);
131 }
132 
134 {
135  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
136  covariance.at<double>(0,0) = _ui->linear_sigma_x->value()==0?9999:_ui->linear_sigma_x->value()*_ui->linear_sigma_x->value();
137  covariance.at<double>(1,1) = _ui->linear_sigma_y->value()==0?9999:_ui->linear_sigma_y->value()*_ui->linear_sigma_y->value();
138  covariance.at<double>(2,2) = _ui->linear_sigma_z->value()==0?9999:_ui->linear_sigma_z->value()*_ui->linear_sigma_z->value();
139  double conversion = 1.0f;
140  if(!_ui->checkBox_radians->isChecked())
141  {
142  conversion = M_PI/180.0;
143  }
144  double sigma = _ui->angular_sigma_roll->value()*conversion;
145  covariance.at<double>(3,3) = sigma==0?9999:sigma*sigma;
146  sigma = _ui->angular_sigma_pitch->value()*conversion;
147  covariance.at<double>(4,4) = sigma==0?9999:sigma*sigma;
148  sigma = _ui->angular_sigma_yaw->value()*conversion;
149  covariance.at<double>(5,5) = sigma==0?9999:sigma*sigma;
150  return covariance;
151 }
152 
153 }
rtabmap::EditConstraintDialog::_ui
Ui_EditConstraintDialog * _ui
Definition: EditConstraintDialog.h:58
glm::yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
rtabmap::EditConstraintDialog::~EditConstraintDialog
virtual ~EditConstraintDialog()
Definition: EditConstraintDialog.cpp:68
rtabmap::EditConstraintDialog::EditConstraintDialog
EditConstraintDialog(const Transform &constraint, const cv::Mat &covariance=cv::Mat::eye(6, 6, CV_64FC1), QWidget *parent=0)
Definition: EditConstraintDialog.cpp:40
y
Matrix3f y
rtabmap::EditConstraintDialog::setPoseGroupVisible
void setPoseGroupVisible(bool visible)
Definition: EditConstraintDialog.cpp:73
rtabmap::EditConstraintDialog::switchUnits
void switchUnits()
Definition: EditConstraintDialog.cpp:82
rtabmap::Transform::getTranslationAndEulerAngles
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:258
glm::sqrt
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
UASSERT
#define UASSERT(condition)
z
z
x
x
rtabmap::EditConstraintDialog::getTransform
Transform getTransform() const
Definition: EditConstraintDialog.cpp:123
glm::pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ULogger.h
ULogger class and convenient macros.
rtabmap::Transform
Definition: Transform.h:41
rtabmap::EditConstraintDialog::setCovarianceGroupVisible
void setCovarianceGroupVisible(bool visible)
Definition: EditConstraintDialog.cpp:77
M_PI
#define M_PI
Definition: EditConstraintDialog.cpp:35
rtabmap
Definition: CameraARCore.cpp:35
value
value
i
int i
rtabmap::EditConstraintDialog::getCovariance
cv::Mat getCovariance() const
Definition: EditConstraintDialog.cpp:133
glm::roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
EditConstraintDialog.h


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:44