Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
vpSimulatorPioneer.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
46 #include <visp3/core/vpDebug.h>
47 #include <visp3/core/vpExponentialMap.h>
48 #include <visp3/core/vpHomogeneousMatrix.h>
49 #include <visp3/robot/vpRobotException.h>
50 #include <visp3/robot/vpSimulatorPioneer.h>
51 
56 vpSimulatorPioneer::vpSimulatorPioneer() : wMc_(), wMe_(), xm_(0), ym_(0), theta_(0) { init(); }
57 
65 void vpSimulatorPioneer::init()
66 {
67  xm_ = 0;
68  ym_ = 0;
69  theta_ = 0;
70 
71  nDof = 2;
72  eJeAvailable = true;
73  fJeAvailable = false;
75  qmin = NULL;
76  qmax = NULL;
77 
78  wMc_ = wMe_ * cMe_.inverse();
79 }
80 
86 
95 
114 {
115  switch (frame) {
119  }
120  setRobotFrame(frame);
121 
122  // v is a 2 dimension vector that contains v,w
123  if (v.size() != 2) {
124  vpERROR_TRACE("Bad dimension of the control vector");
125  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
126  }
127 
128  vpColVector v_max(2);
129 
130  v_max[0] = getMaxTranslationVelocity();
131  v_max[1] = getMaxRotationVelocity();
132 
133  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
134 
135  xm_ += delta_t_ * v_sat[0] * cos(theta_);
136  ym_ += delta_t_ * v_sat[0] * sin(theta_);
137  theta_ += delta_t_ * v_sat[1];
138 
139  vpRotationMatrix wRe(0, 0, theta_);
140  vpTranslationVector wte(xm_, ym_, 0);
141  wMe_.buildFrom(wte, wRe);
142  wMc_ = wMe_ * cMe_.inverse();
143 
144  break;
145  } break;
147  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
148  "functionality not implemented");
149  break;
151  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the articular frame:"
152  "functionality not implemented");
153  case vpRobot::MIXT_FRAME:
154  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
155  "functionality not implemented");
156 
157  break;
159  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
160  "functionality not implemented");
161 
162  break;
163  }
164 }
165 
171 
172 /*
173  Get the current position of the robot.
174 
175  \param frame : Control frame type in which to get the position, either :
176  - in the camera cartesien frame,
177  - joint (articular) coordinates of each axes (not implemented)
178  - in a reference or fixed cartesien frame attached to the robot base
179  - in a mixt cartesien frame (translation in reference frame, and rotation in
180  camera frame)
181 
182  \param position : Measured position of the robot:
183  - in camera cartesien frame, a 6 dimension vector, set to 0.
184 
185  - in articular, this functionality is not implemented.
186 
187  - in reference frame, a 6 dimension vector, the first 3 values correspond to
188  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
189  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
190 */
192 {
193  q.resize(6);
194 
195  switch (frame) {
197  q = 0;
198  break;
199 
201  std::cout << "ARTICULAR_FRAME is not implemented in "
202  "vpSimulatorPioneer::getPosition()"
203  << std::endl;
204  break;
206  // Convert wMc_ to a position
207  // From fMc extract the pose
208  vpRotationMatrix wRc;
209  this->wMc_.extract(wRc);
210  vpRxyzVector rxyz;
211  rxyz.buildFrom(wRc);
212 
213  for (unsigned int i = 0; i < 3; i++) {
214  q[i] = this->wMc_[i][3]; // translation x,y,z
215  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
216  }
217 
218  break;
219  }
220  case vpRobot::MIXT_FRAME:
221  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
222  break;
224  std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
225  break;
226  }
227 }
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:153
vpRxyzVector buildFrom(const vpRotationMatrix &R)
Error that can be emited by the vpRobot class and its derivates.
void getPosition(vpHomogeneousMatrix &wMc) const
vpHomogeneousMatrix wMe_
Implementation of an homogeneous matrix and operations on such kind of matrices.
double * qmax
Definition: vpRobot.h:114
#define vpERROR_TRACE
Definition: vpDebug.h:393
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:251
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
vpHomogeneousMatrix inverse() const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
vpControlFrameType
Definition: vpRobot.h:75
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:291
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:273
void extract(vpRotationMatrix &R) const
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
Implementation of a rotation matrix and operations on such kind of matrices.
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:106
Initialize the velocity controller.
Definition: vpRobot.h:66
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:144
vpMatrix get_eJe() const
Definition: vpUnicycle.h:107
vpHomogeneousMatrix wMc_
int areJointLimitsAvailable
Definition: vpRobot.h:112
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:127
int nDof
number of degrees of freedom
Definition: vpRobot.h:102
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:310
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
double * qmin
Definition: vpRobot.h:113
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:207
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:110
Class that consider the case of a translation vector.