Visual Servoing Platform  version 3.6.1 under development (2024-03-29)
vpSimulatorPioneerPan.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 equipped with a pan head simulator without display.
33  *
34 *****************************************************************************/
35 
42 #include <visp3/core/vpDebug.h>
43 #include <visp3/core/vpExponentialMap.h>
44 #include <visp3/core/vpHomogeneousMatrix.h>
45 #include <visp3/robot/vpRobotException.h>
46 #include <visp3/robot/vpSimulatorPioneerPan.h>
47 
57 vpSimulatorPioneerPan::vpSimulatorPioneerPan() : wMc_(), wMm_(), xm_(0), ym_(0), theta_(0), q_pan_() { init(); }
58 
69 void vpSimulatorPioneerPan::init()
70 {
71  xm_ = 0;
72  ym_ = 0;
73  theta_ = 0;
74  q_pan_ = 0;
75 
76  nDof = 3;
77  eJeAvailable = true;
78  fJeAvailable = false;
80  qmin = nullptr;
81  qmax = nullptr;
82 
83  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
84 }
85 
94 
114 {
115  switch (frame) {
119  }
120 
121  setRobotFrame(frame);
122 
123  // v is a 3 dimension vector that contains vx, wz, qpan
124  if (v.size() != 3) {
125  vpERROR_TRACE("Bad dimension of the control vector");
126  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
127  }
128 
129  vpColVector v_max(3);
130 
131  v_max[0] = getMaxTranslationVelocity();
132  v_max[1] = getMaxRotationVelocity();
133  v_max[2] = getMaxRotationVelocity();
134 
135  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
136 
137  xm_ += delta_t_ * v_sat[0] * cos(theta_);
138  ym_ += delta_t_ * v_sat[0] * sin(theta_);
139  theta_ += delta_t_ * v_sat[1];
140  q_pan_ += delta_t_ * v_sat[2];
141 
142  vpRotationMatrix wRm(0, 0, theta_);
143  vpTranslationVector wtm(xm_, ym_, 0);
144  wMm_.buildFrom(wtm, wRm);
145 
146  // Update the end effector pose
147  set_pMe(q_pan_);
148 
149  // Update the camera pose
150  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
151 
152  // Update the jacobian
153  set_eJe(q_pan_);
154 
155  break;
156  }
158  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
159  "functionality not implemented");
161  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the reference frame:"
162  "functionality not implemented");
163  case vpRobot::MIXT_FRAME:
164  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
165  "functionality not implemented");
167  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
168  "functionality not implemented");
169  }
170 }
171 
177 
178 /*
179  Get the current position of the robot.
180 
181  \param frame : Control frame type in which to get the position, either :
182  - in the camera cartesien frame,
183  - joint (articular) coordinates of each axes (not implemented)
184  - in a reference or fixed cartesien frame attached to the robot base
185  - in a mixt cartesien frame (translation in reference frame, and rotation in
186  camera frame)
187 
188  \param position : Measured position of the robot:
189  - in camera cartesien frame, a 6 dimension vector, set to 0.
190 
191  - in articular, this functionality is not implemented.
192 
193  - in reference frame, a 6 dimension vector, the first 3 values correspond to
194  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
195  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
196 */
198 {
199  q.resize(6);
200 
201  switch (frame) {
203  q = 0;
204  break;
205 
207  std::cout << "ARTICULAR_FRAME is not implemented in "
208  "vpSimulatorPioneer::getPosition()"
209  << std::endl;
210  break;
212  // Convert wMc_ to a position
213  // From fMc extract the pose
214  vpRotationMatrix wRc;
215  this->wMc_.extract(wRc);
216  vpRxyzVector rxyz;
217  rxyz.buildFrom(wRc);
218 
219  for (unsigned int i = 0; i < 3; i++) {
220  q[i] = this->wMc_[i][3]; // translation x,y,z
221  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
222  }
223 
224  break;
225  }
226  case vpRobot::MIXT_FRAME:
227  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
228  break;
230  std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
231  break;
232  }
233 }
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:286
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1056
@ dimensionError
Bad dimension.
Definition: vpException.h:83
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void extract(vpRotationMatrix &R) const
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:146
void set_eJe(double q_pan)
Definition: vpPioneerPan.h:133
void set_pMe(const double q)
Definition: vpPioneerPan.h:208
vpHomogeneousMatrix mMp_
Definition: vpPioneerPan.h:222
vpHomogeneousMatrix pMe_
Definition: vpPioneerPan.h:223
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:102
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:153
double * qmin
Definition: vpRobot.h:113
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:160
vpControlFrameType
Definition: vpRobot.h:75
@ REFERENCE_FRAME
Definition: vpRobot.h:76
@ ARTICULAR_FRAME
Definition: vpRobot.h:78
@ MIXT_FRAME
Definition: vpRobot.h:86
@ CAMERA_FRAME
Definition: vpRobot.h:82
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:81
double * qmax
Definition: vpRobot.h:114
int areJointLimitsAvailable
Definition: vpRobot.h:112
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:110
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:65
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:270
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:198
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:106
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:248
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:204
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:176
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void getPosition(vpHomogeneousMatrix &wMc) const
vpHomogeneousMatrix wMm_
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
vpHomogeneousMatrix wMc_
robot / camera location in the world frame
Class that consider the case of a translation vector.
vpMatrix get_eJe() const
Definition: vpUnicycle.h:94
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:114
#define vpERROR_TRACE
Definition: vpDebug.h:382