22 #include <mrpt/poses/CPose2D.h> 23 #include <mrpt/poses/CPose3D.h> 24 #include <mrpt/poses/CPosePDFGaussian.h> 25 #include <mrpt/poses/CPose3DPDFGaussian.h> 26 #include <mrpt/poses/CPosePDFGaussianInf.h> 27 #include <mrpt/poses/CPose3DPDFGaussianInf.h> 28 #include <mrpt/math/CQuaternion.h> 29 #include <mrpt/math/lightweight_geom_data.h> 30 #include <geometry_msgs/PoseWithCovariance.h> 31 #include <geometry_msgs/Pose.h> 32 #include <geometry_msgs/Quaternion.h> 33 #include <mrpt/math/CMatrixFixedNumeric.h> 36 #include <mrpt/version.h> 37 #if MRPT_VERSION<0x199 38 #include <mrpt/utils/mrpt_macros.h> 40 #include <mrpt/core/exceptions.h> 48 for (
int r = 0; r < 3; r++)
49 for (
int c = 0; c < 3; c++) _des(r, c) = _src[r][c];
56 for (
int r = 0; r < 3; r++)
57 for (
int c = 0; c < 3; c++) _des[r][c] = _src(r, c);
62 const mrpt::poses::CPose3DPDFGaussian& _src,
tf::Transform& _des)
64 return convert(_src.mean, _des);
68 const mrpt::poses::CPose3DPDFGaussian& _src,
84 const unsigned int indxs_map[6] = {0, 1, 2,
87 for (
int i = 0; i < 6; i++)
89 for (
int j = 0; j < 6; j++)
91 _des.covariance[indxs_map[i] * 6 + indxs_map[j]] = _src.cov(i, j);
98 const mrpt::poses::CPose3DPDFGaussianInf& _src,
101 mrpt::poses::CPose3DPDFGaussian mrpt_gaussian;
102 mrpt_gaussian.copyFrom(_src);
113 _src.getRotationMatrix(R);
124 _des.
x() = t[0], _des.
y() = t[1], _des.
z() = t[2];
128 _des.setRotationMatrix(R);
136 _des.position.x = _src[0];
137 _des.position.y = _src[1];
138 _des.position.z = _src[2];
141 _src.getAsQuaternion(q);
143 _des.orientation.x = q.x();
144 _des.orientation.y = q.y();
145 _des.orientation.z = q.z();
146 _des.orientation.w = q.r();
155 _des.position.x = _src.x();
156 _des.position.y = _src.y();
159 const double yaw = _src.phi();
160 if (std::abs(yaw) < 1e-10)
162 _des.orientation.x = 0.;
163 _des.orientation.y = 0.;
164 _des.orientation.z = .5 * yaw;
165 _des.orientation.w = 1.;
169 const double s = ::sin(yaw * .5);
170 const double c = ::cos(yaw * .5);
171 _des.orientation.x = 0.;
172 _des.orientation.y = 0.;
173 _des.orientation.z = s;
174 _des.orientation.w = c;
183 _des.x(_src.position.x);
184 _des.y(_src.position.y);
187 convert(_src.orientation, quat);
189 double roll, pitch, yaw;
190 quat.rpy(roll, pitch, yaw);
198 const mrpt::poses::CPosePDFGaussian& _src,
218 _des.covariance[0] = _src.cov(0, 0);
219 _des.covariance[1] = _src.cov(0, 1);
220 _des.covariance[5] = _src.cov(0, 2);
221 _des.covariance[6] = _src.cov(1, 0);
222 _des.covariance[7] = _src.cov(1, 1);
223 _des.covariance[11] = _src.cov(1, 2);
224 _des.covariance[30] = _src.cov(2, 0);
225 _des.covariance[31] = _src.cov(2, 1);
226 _des.covariance[35] = _src.cov(2, 2);
232 const mrpt::poses::CPosePDFGaussianInf& _src,
235 mrpt::poses::CPosePDFGaussian mrpt_gaussian;
236 mrpt_gaussian.copyFrom(_src);
244 mrpt::poses::CPose3DPDFGaussian& _des)
248 const unsigned int indxs_map[6] = {0, 1, 2, 5, 4, 3};
250 for (
int i = 0; i < 6; i++)
252 for (
int j = 0; j < 6; j++)
254 _des.cov(i, j) = _src.covariance[indxs_map[i] * 6 + indxs_map[j]];
263 mrpt::poses::CPose3DPDFGaussianInf& _des)
265 mrpt::poses::CPose3DPDFGaussian mrpt_gaussian;
267 _src, mrpt_gaussian);
268 _des.copyFrom(mrpt_gaussian);
275 mrpt::poses::CPosePDFGaussian& _des)
279 _des.cov(0, 0) = _src.covariance[0];
280 _des.cov(0, 1) = _src.covariance[1];
281 _des.cov(0, 2) = _src.covariance[5];
282 _des.cov(1, 0) = _src.covariance[0 + 6];
283 _des.cov(1, 1) = _src.covariance[1 + 6];
284 _des.cov(1, 2) = _src.covariance[5 + 6];
285 _des.cov(2, 0) = _src.covariance[0 + 30];
286 _des.cov(2, 1) = _src.covariance[1 + 30];
287 _des.cov(2, 2) = _src.covariance[5 + 30];
294 mrpt::poses::CPosePDFGaussianInf& _des)
296 mrpt::poses::CPosePDFGaussian mrpt_gaussian;
299 _des.copyFrom(mrpt_gaussian);
329 _src.orientation.w, _src.orientation.x, _src.orientation.y,
331 _des = mrpt::poses::CPose3D(
332 q, _src.position.x, _src.position.y, _src.position.z);
352 mrpt::poses::CPose3D(mrpt::math::TPose3D(_src)), _des);
math::CQuaternion< double > CQuaternionDouble
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const