25
25
//
26
26
27
27
#include < QStatusBar>
28
+ #include < rl/math/Constants.h>
28
29
#include < rl/math/Rotation.h>
29
- #include < rl/math/Unit.h>
30
30
#include < rl/mdl/Exception.h>
31
31
#include < rl/mdl/Kinematic.h>
32
32
#include < rl/mdl/JacobianInverseKinematics.h>
@@ -93,7 +93,7 @@ OperationalModel::data(const QModelIndex& index, int role) const
93
93
case 3 :
94
94
case 4 :
95
95
case 5 :
96
- return QString::number (orientation (index .column () - 3 ) * rl::math::RAD2DEG , ' f' , 2 ) + QChar (176 );
96
+ return QString::number (orientation (index .column () - 3 ) * rl::math::constants::rad2deg , ' f' , 2 ) + QChar (176 );
97
97
break ;
98
98
default :
99
99
break ;
@@ -110,7 +110,7 @@ OperationalModel::data(const QModelIndex& index, int role) const
110
110
case 3 :
111
111
case 4 :
112
112
case 5 :
113
- return orientation (index .column () - 3 ) * rl::math::RAD2DEG ;
113
+ return orientation (index .column () - 3 ) * rl::math::constants::rad2deg ;
114
114
break ;
115
115
default :
116
116
break ;
@@ -217,19 +217,19 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r
217
217
transform.linear () = (
218
218
rl::math::AngleAxis (orientation.z (), rl::math::Vector3::UnitZ ()) *
219
219
rl::math::AngleAxis (orientation.y (), rl::math::Vector3::UnitY ()) *
220
- rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::DEG2RAD , rl::math::Vector3::UnitX ())
220
+ rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::constants::deg2rad , rl::math::Vector3::UnitX ())
221
221
).toRotationMatrix ();
222
222
break ;
223
223
case 4 :
224
224
transform.linear () = (
225
225
rl::math::AngleAxis (orientation.z (), rl::math::Vector3::UnitZ ()) *
226
- rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::DEG2RAD , rl::math::Vector3::UnitY ()) *
226
+ rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::constants::deg2rad , rl::math::Vector3::UnitY ()) *
227
227
rl::math::AngleAxis (orientation.x (), rl::math::Vector3::UnitX ())
228
228
).toRotationMatrix ();
229
229
break ;
230
230
case 5 :
231
231
transform.linear () = (
232
- rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::DEG2RAD , rl::math::Vector3::UnitZ ()) *
232
+ rl::math::AngleAxis (value.value <rl::math::Real>() * rl::math::constants::deg2rad , rl::math::Vector3::UnitZ ()) *
233
233
rl::math::AngleAxis (orientation.y (), rl::math::Vector3::UnitY ()) *
234
234
rl::math::AngleAxis (orientation.x (), rl::math::Vector3::UnitX ())
235
235
).toRotationMatrix ();
@@ -287,7 +287,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r
287
287
288
288
if (solved)
289
289
{
290
- MainWindow::instance ()->statusBar ()->showMessage (" IK solved in " + QString::number (std::chrono::duration<double >(stop - start).count () * rl::math::UNIT2MILLI ) + " ms" , 2000 );
290
+ MainWindow::instance ()->statusBar ()->showMessage (" IK solved in " + QString::number (std::chrono::duration<double >(stop - start).count () * rl::math::constants::unit2milli ) + " ms" , 2000 );
291
291
292
292
kinematic->forwardPosition ();
293
293
0 commit comments