Visual Servoing Platform  version 3.6.1 under development (2024-04-27)
vpPoseVector.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Pose object. A pose is a size 6 vector [t, tu]^T where tu is
33  * a rotation vector (theta u representation) and t is a translation vector.
34  *
35 *****************************************************************************/
36 
43 #include <assert.h>
44 #include <sstream>
45 
46 #include <visp3/core/vpDebug.h>
47 #include <visp3/core/vpException.h>
48 #include <visp3/core/vpMath.h>
49 #include <visp3/core/vpMatrixException.h>
50 #include <visp3/core/vpPoseVector.h>
51 
63 
79 vpPoseVector::vpPoseVector(double tx, double ty, double tz, double tux, double tuy, double tuz)
80  : vpArray2D<double>(6, 1)
81 {
82  (*this)[0] = tx;
83  (*this)[1] = ty;
84  (*this)[2] = tz;
85 
86  (*this)[3] = tux;
87  (*this)[4] = tuy;
88  (*this)[5] = tuz;
89 }
90 
102 {
103  buildFrom(tv, tu);
104 }
105 
119 {
120  buildFrom(tv, R);
121 }
122 
134 
150 void vpPoseVector::set(double tx, double ty, double tz, double tux, double tuy, double tuz)
151 {
152  (*this)[0] = tx;
153  (*this)[1] = ty;
154  (*this)[2] = tz;
155 
156  (*this)[3] = tux;
157  (*this)[4] = tuy;
158  (*this)[5] = tuz;
159 }
160 
177 vpPoseVector vpPoseVector::buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz)
178 {
179  (*this)[0] = tx;
180  (*this)[1] = ty;
181  (*this)[2] = tz;
182 
183  (*this)[3] = tux;
184  (*this)[4] = tuy;
185  (*this)[5] = tuz;
186  return *this;
187 }
188 
201 {
203  M.extract(R);
205  M.extract(tv);
206  buildFrom(tv, R);
207  return *this;
208 }
209 
222 {
223  for (unsigned int i = 0; i < 3; ++i) {
224  (*this)[i] = tv[i];
225  (*this)[i + 3] = tu[i];
226  }
227  return *this;
228 }
229 
244 {
245  vpThetaUVector tu;
246  tu.buildFrom(R);
247 
248  buildFrom(tv, tu);
249  return *this;
250 }
251 
256 {
257  tv[0] = (*this)[0];
258  tv[1] = (*this)[1];
259  tv[2] = (*this)[2];
260 }
261 
266 {
267  tu[0] = (*this)[3];
268  tu[1] = (*this)[4];
269  tu[2] = (*this)[5];
270 }
275 {
276  vpRotationMatrix R((*this)[3], (*this)[4], (*this)[5]);
277  q.buildFrom(R);
278 }
282 void vpPoseVector::extract(vpRotationMatrix &R) const { R.buildFrom((*this)[3], (*this)[4], (*this)[5]); }
288 {
289  vpTranslationVector tr((*this)[0], (*this)[1], (*this)[2]);
290  return tr;
291 }
292 
298 {
299  vpRotationMatrix R((*this)[3], (*this)[4], (*this)[5]);
300  return R;
301 }
302 
308 {
309  vpThetaUVector tu((*this)[3], (*this)[4], (*this)[5]);
310  return tu;
311 }
312 
335 {
336  for (unsigned int i = 0; i < 6; ++i) {
337  if (i < 3) {
338  std::cout << (*this)[i] << " ";
339  }
340  else {
341  std::cout << vpMath::deg((*this)[i]) << " ";
342  }
343  }
344  std::cout << std::endl;
345 }
346 
358 void vpPoseVector::save(std::ofstream &f) const
359 {
360  if (!f.fail()) {
361  f << *this;
362  }
363  else {
364  throw(vpException(vpException::ioError, "Cannot save the pose vector: ofstream not opened"));
365  }
366 }
367 
378 void vpPoseVector::load(std::ifstream &f)
379 {
380  if (!f.fail()) {
381  for (unsigned int i = 0; i < 6; ++i) {
382  f >> (*this)[i];
383  }
384  }
385  else {
386  throw(vpException(vpException::ioError, "Cannot read pose vector: ifstream not opened"));
387  }
388 }
389 
390 /*
391  Transpose the pose vector. The resulting vector becomes a row vector.
392 
393 */
395 {
396  vpRowVector v(rowNum);
397  memcpy(v.data, data, rowNum * sizeof(double));
398  return v;
399 }
400 
420 int vpPoseVector::print(std::ostream &s, unsigned int length, char const *intro) const
421 {
422  typedef std::string::size_type size_type;
423 
424  unsigned int m = getRows();
425  unsigned int n = 1;
426 
427  std::vector<std::string> values(m * n);
428  std::ostringstream oss;
429  std::ostringstream ossFixed;
430  std::ios_base::fmtflags original_flags = oss.flags();
431 
432  // --comment: ossFixed less less std fixed
433  ossFixed.setf(std::ios::fixed, std::ios::floatfield);
434 
435  size_type maxBefore = 0; // the length of the integral part
436  size_type maxAfter = 0; // number of decimals plus
437  // one place for the decimal point
438  for (unsigned int i = 0; i < m; ++i) {
439  oss.str("");
440  oss << (*this)[i];
441  if (oss.str().find("e") != std::string::npos) {
442  ossFixed.str("");
443  ossFixed << (*this)[i];
444  oss.str(ossFixed.str());
445  }
446 
447  values[i] = oss.str();
448  size_type thislen = values[i].size();
449  size_type p = values[i].find('.');
450 
451  if (p == std::string::npos) {
452  maxBefore = vpMath::maximum(maxBefore, thislen);
453  // maxAfter remains the same
454  }
455  else {
456  maxBefore = vpMath::maximum(maxBefore, p);
457  maxAfter = vpMath::maximum(maxAfter, thislen - p - 1);
458  }
459  }
460 
461  size_type totalLength = length;
462  // increase totalLength according to maxBefore
463  totalLength = vpMath::maximum(totalLength, maxBefore);
464  // decrease maxAfter according to totalLength
465  maxAfter = std::min<size_type>(maxAfter, totalLength - maxBefore);
466  if (maxAfter == 1) {
467  maxAfter = 0;
468  }
469 
470  // the following line is useful for debugging
471  // std::cerr <<totalLength <<" " <<maxBefore <<" " <<maxAfter <<"\n";
472 
473  if (intro) {
474  s << intro;
475  }
476  s << "[" << m << "," << n << "]=\n";
477 
478  for (unsigned int i = 0; i < m; ++i) {
479  s << " ";
480  size_type p = values[i].find('.');
481  s.setf(std::ios::right, std::ios::adjustfield);
482  s.width(static_cast<std::streamsize>(maxBefore));
483  s << values[i].substr(0, p).c_str();
484 
485  if (maxAfter > 0) {
486  s.setf(std::ios::left, std::ios::adjustfield);
487  if (p != std::string::npos) {
488  s.width(static_cast<std::streamsize>(maxAfter));
489  s << values[i].substr(p, maxAfter).c_str();
490  }
491  else {
492  assert(maxAfter > 1);
493  s.width(static_cast<std::streamsize>(maxAfter));
494  s << ".0";
495  }
496  }
497 
498  s << ' ';
499 
500  s << std::endl;
501  }
502 
503  s.flags(original_flags); // restore s to standard state
504 
505  return static_cast<int>(maxBefore + maxAfter);
506 }
507 
512 std::vector<double> vpPoseVector::toStdVector() const
513 {
514  std::vector<double> v(this->size());
515 
516  unsigned int this_size = this->size();
517  for (unsigned int i = 0; i < this_size; ++i) {
518  v[i] = data[i];
519  }
520  return v;
521 }
522 
523 #ifdef VISP_HAVE_NLOHMANN_JSON
524 #include <visp3/core/vpJsonParsing.h>
525 const std::string vpPoseVector::jsonTypeName = "vpPoseVector";
526 void vpPoseVector::convert_to_json(nlohmann::json &j) const
527 {
528  const vpArray2D<double> *asArray = (vpArray2D<double>*) this;
529  to_json(j, *asArray);
530  j["type"] = vpPoseVector::jsonTypeName;
531 }
532 void vpPoseVector::parse_json(const nlohmann::json &j)
533 {
534  vpArray2D<double> *asArray = (vpArray2D<double>*) this;
535  if (j.is_object() && j.contains("type")) { // Specific conversions
536  const bool converted = convertFromTypeAndBuildFrom<vpPoseVector, vpHomogeneousMatrix>(j, *this);
537  if (!converted) {
538  from_json(j, *asArray);
539  }
540  }
541  else { // Generic 2D array conversion
542  from_json(j, *asArray);
543  }
544 
545  if ((getCols() != 1) && (getRows() != 6)) {
546  throw vpException(vpException::badValue, "From JSON, tried to read something that is not a 6D pose vector");
547  }
548 }
549 #endif
Implementation of a generic 2D array used as base class for matrices and vectors.
Definition: vpArray2D.h:126
unsigned int getCols() const
Definition: vpArray2D.h:327
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:139
unsigned int rowNum
Number of rows in the array.
Definition: vpArray2D.h:129
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:339
unsigned int getRows() const
Definition: vpArray2D.h:337
error that can be emitted by ViSP classes.
Definition: vpException.h:59
@ ioError
I/O error.
Definition: vpException.h:79
@ badValue
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:85
Implementation of an homogeneous matrix and operations on such kind of matrices.
void extract(vpRotationMatrix &R) const
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:252
static double deg(double rad)
Definition: vpMath.h:117
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:189
vpTranslationVector getTranslationVector() const
std::vector< double > toStdVector() const
void load(std::ifstream &f)
void save(std::ofstream &f) const
friend void from_json(const nlohmann::json &j, vpPoseVector &cam)
Definition: vpPoseVector.h:323
vpRowVector t() const
friend void to_json(nlohmann::json &j, const vpPoseVector &cam)
Definition: vpPoseVector.h:319
void extract(vpRotationMatrix &R) const
void set(double tx, double ty, double tz, double tux, double tuy, double tuz)
vpThetaUVector getThetaUVector() const
static const std::string jsonTypeName
Definition: vpPoseVector.h:293
vpPoseVector buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz)
void print() const
vpRotationMatrix getRotationMatrix() const
Implementation of a rotation vector as quaternion angle minimal representation.
vpQuaternionVector buildFrom(const double qx, const double qy, const double qz, const double qw)
Implementation of a rotation matrix and operations on such kind of matrices.
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
Implementation of row vector and the associated operations.
Definition: vpRowVector.h:107
Implementation of a rotation vector as axis-angle minimal representation.
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
Class that consider the case of a translation vector.