Visual Servoing Platform  version 3.0.0
vpSimulatorPioneer.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Pioneer mobile robot simulator without display.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 
45 #include <visp3/core/vpHomogeneousMatrix.h>
46 #include <visp3/robot/vpSimulatorPioneer.h>
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpExponentialMap.h>
50 
51 
57  : wMc_(), wMe_(), xm_(0), ym_(0), theta_(0)
58 {
59  init() ;
60 }
61 
69 void vpSimulatorPioneer::init()
70 {
71  xm_ = 0;
72  ym_ = 0;
73  theta_ = 0;
74 
75  nDof = 2;
76  eJeAvailable = true;
77  fJeAvailable = false;
79  qmin = NULL;
80  qmax = NULL;
81 
82  wMc_ = wMe_ * cMe_.inverse();
83 }
84 
85 
91 {
92 }
93 
101 void
103 {
104  _eJe = vpUnicycle::get_eJe();
105 }
106 
107 
121 void
123  const vpColVector &v)
124 {
125  switch (frame)
126  {
130  }
131  setRobotFrame(frame);
132 
133  // v is a 2 dimension vector that contains v,w
134  if (v.size() != 2) {
135  vpERROR_TRACE ("Bad dimension of the control vector");
137  "Bad dimension of the control vector");
138  }
139 
140  vpColVector v_max(2);
141 
142  v_max[0] = getMaxTranslationVelocity();
143  v_max[1] = getMaxRotationVelocity();
144 
145  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
146 
147  xm_ += delta_t_ * v_sat[0] * cos(theta_);
148  ym_ += delta_t_ * v_sat[0] * sin(theta_);
149  theta_ += delta_t_ * v_sat[1];
150 
151  vpRotationMatrix wRe(0, 0, theta_);
152  vpTranslationVector wte(xm_, ym_, 0);
153  wMe_.buildFrom(wte, wRe);
154  wMc_ = wMe_ * cMe_.inverse();
155 
156  break ;
157  }
158  break ;
160  vpERROR_TRACE ("Cannot set a velocity in the camera frame: "
161  "functionality not implemented");
163  "Cannot set a velocity in the camera frame:"
164  "functionality not implemented");
165  break ;
167  vpERROR_TRACE ("Cannot set a velocity in the reference frame: "
168  "functionality not implemented");
170  "Cannot set a velocity in the articular frame:"
171  "functionality not implemented");
172  case vpRobot::MIXT_FRAME:
173  vpERROR_TRACE ("Cannot set a velocity in the mixt frame: "
174  "functionality not implemented");
176  "Cannot set a velocity in the mixt frame:"
177  "functionality not implemented");
178 
179  break ;
180  }
181 }
182 
187 void
189 {
190  wMc = this->wMc_ ;
191 }
192 
193 /*
194  Get the current position of the robot.
195 
196  \param frame : Control frame type in which to get the position, either :
197  - in the camera cartesien frame,
198  - joint (articular) coordinates of each axes (not implemented)
199  - in a reference or fixed cartesien frame attached to the robot base
200  - in a mixt cartesien frame (translation in reference frame, and rotation in camera frame)
201 
202  \param position : Measured position of the robot:
203  - in camera cartesien frame, a 6 dimension vector, set to 0.
204 
205  - in articular, this functionality is not implemented.
206 
207  - in reference frame, a 6 dimension vector, the first 3 values correspond to
208  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
209  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
210 */
212 {
213  q.resize (6);
214 
215  switch (frame) {
216  case vpRobot::CAMERA_FRAME :
217  q = 0;
218  break;
219 
221  std::cout << "ARTICULAR_FRAME is not implemented in vpSimulatorPioneer::getPosition()" << std::endl;
222  break;
223  case vpRobot::REFERENCE_FRAME : {
224  // Convert wMc_ to a position
225  // From fMc extract the pose
226  vpRotationMatrix wRc;
227  this->wMc_.extract(wRc);
228  vpRxyzVector rxyz;
229  rxyz.buildFrom(wRc);
230 
231  for (unsigned int i=0; i < 3; i++) {
232  q[i] = this->wMc_[i][3]; // translation x,y,z
233  q[i+3] = rxyz[i]; // Euler rotation x,y,z
234  }
235 
236  break;
237  }
238  case vpRobot::MIXT_FRAME :
239  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
240  }
241 }
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
vpRxyzVector buildFrom(const vpRotationMatrix &R)
Error that can be emited by the vpRobot class and its derivates.
vpHomogeneousMatrix wMe_
Implementation of an homogeneous matrix and operations on such kind of matrices.
double * qmax
Definition: vpRobot.h:111
#define vpERROR_TRACE
Definition: vpDebug.h:391
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
void getPosition(vpHomogeneousMatrix &wMc) const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
vpControlFrameType
Definition: vpRobot.h:76
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:156
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
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:103
Initialize the velocity controller.
Definition: vpRobot.h:68
vpMatrix get_eJe() const
Definition: vpUnicycle.h:111
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix wMc_
int areJointLimitsAvailable
Definition: vpRobot.h:109
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:136
int nDof
number of degrees of freedom
Definition: vpRobot.h:99
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:138
double * qmin
Definition: vpRobot.h:110
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:107
Class that consider the case of a translation vector.
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:217