Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpSimulatorPioneer.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  * Pioneer mobile robot simulator without display.
33  *
34 *****************************************************************************/
35 
43 #include <visp3/core/vpDebug.h>
44 #include <visp3/core/vpExponentialMap.h>
45 #include <visp3/core/vpHomogeneousMatrix.h>
46 #include <visp3/robot/vpRobotException.h>
47 #include <visp3/robot/vpSimulatorPioneer.h>
48 
54 vpSimulatorPioneer::vpSimulatorPioneer() : wMc_(), wMe_(), xm_(0), ym_(0), theta_(0) { init(); }
55 
63 void vpSimulatorPioneer::init()
64 {
65  xm_ = 0;
66  ym_ = 0;
67  theta_ = 0;
68 
69  nDof = 2;
70  eJeAvailable = true;
71  fJeAvailable = false;
73  qmin = nullptr;
74  qmax = nullptr;
75 
76  wMc_ = wMe_ * cMe_.inverse();
77 }
78 
87 
106 {
107  switch (frame) {
111  }
112  setRobotFrame(frame);
113 
114  // v is a 2 dimension vector that contains v,w
115  if (v.size() != 2) {
116  vpERROR_TRACE("Bad dimension of the control vector");
117  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
118  }
119 
120  vpColVector v_max(2);
121 
122  v_max[0] = getMaxTranslationVelocity();
123  v_max[1] = getMaxRotationVelocity();
124 
125  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
126 
127  xm_ += delta_t_ * v_sat[0] * cos(theta_);
128  ym_ += delta_t_ * v_sat[0] * sin(theta_);
129  theta_ += delta_t_ * v_sat[1];
130 
131  vpRotationMatrix wRe(0, 0, theta_);
132  vpTranslationVector wte(xm_, ym_, 0);
133  wMe_.build(wte, wRe);
134  wMc_ = wMe_ * cMe_.inverse();
135 
136  break;
137  } break;
139  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
140  "functionality not implemented");
141  break;
143  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the articular frame:"
144  "functionality not implemented");
145  case vpRobot::MIXT_FRAME:
146  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
147  "functionality not implemented");
148 
149  break;
151  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
152  "functionality not implemented");
153 
154  break;
155  }
156 }
157 
163 
164 /*
165  Get the current position of the robot.
166 
167  \param frame : Control frame type in which to get the position, either :
168  - in the camera cartesian frame,
169  - joint (articular) coordinates of each axes (not implemented)
170  - in a reference or fixed cartesian frame attached to the robot base
171  - in a mixt cartesian frame (translation in reference frame, and rotation in
172  camera frame)
173 
174  \param position : Measured position of the robot:
175  - in camera cartesian frame, a 6 dimension vector, set to 0.
176 
177  - in articular, this functionality is not implemented.
178 
179  - in reference frame, a 6 dimension vector, the first 3 values correspond to
180  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
181  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
182 */
184 {
185  q.resize(6);
186 
187  switch (frame) {
189  q = 0;
190  break;
191 
193  std::cout << "ARTICULAR_FRAME is not implemented in "
194  "vpSimulatorPioneer::getPosition()"
195  << std::endl;
196  break;
198  // Convert wMc_ to a position
199  // From fMc extract the pose
200  vpRotationMatrix wRc;
201  this->wMc_.extract(wRc);
202  vpRxyzVector rxyz;
203  rxyz.build(wRc);
204 
205  for (unsigned int i = 0; i < 3; i++) {
206  q[i] = this->wMc_[i][3]; // translation x,y,z
207  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
208  }
209 
210  break;
211  }
212  case vpRobot::MIXT_FRAME:
213  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
214  break;
216  std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
217  break;
218  }
219 }
220 END_VISP_NAMESPACE
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
@ dimensionError
Bad dimension.
Definition: vpException.h:71
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
int nDof
number of degrees of freedom
Definition: vpRobot.h:104
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
double * qmin
Definition: vpRobot.h:115
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ MIXT_FRAME
Definition: vpRobot.h:88
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
double * qmax
Definition: vpRobot.h:116
int areJointLimitsAvailable
Definition: vpRobot.h:114
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:112
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:274
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:108
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:252
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
vpRxyzVector & build(const vpRotationMatrix &R)
vpHomogeneousMatrix wMc_
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
void getPosition(vpHomogeneousMatrix &wMc) const
vpHomogeneousMatrix wMe_
Class that consider the case of a translation vector.
vpMatrix get_eJe() const
Definition: vpUnicycle.h:96
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:116
#define vpERROR_TRACE
Definition: vpDebug.h:409