Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
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
57vpSimulatorPioneerPan::vpSimulatorPioneerPan() : wMc_(), wMm_(), xm_(0), ym_(0), theta_(0), q_pan_() { init(); }
58
69void 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 = NULL;
81 qmax = NULL;
82
83 wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
84}
85
91
100
120{
121 switch (frame) {
125 }
126
127 setRobotFrame(frame);
128
129 // v is a 3 dimension vector that contains vx, wz, qpan
130 if (v.size() != 3) {
131 vpERROR_TRACE("Bad dimension of the control vector");
132 throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
133 }
134
135 vpColVector v_max(3);
136
137 v_max[0] = getMaxTranslationVelocity();
138 v_max[1] = getMaxRotationVelocity();
139 v_max[2] = getMaxRotationVelocity();
140
141 vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
142
143 xm_ += delta_t_ * v_sat[0] * cos(theta_);
144 ym_ += delta_t_ * v_sat[0] * sin(theta_);
145 theta_ += delta_t_ * v_sat[1];
146 q_pan_ += delta_t_ * v_sat[2];
147
148 vpRotationMatrix wRm(0, 0, theta_);
149 vpTranslationVector wtm(xm_, ym_, 0);
150 wMm_.buildFrom(wtm, wRm);
151
152 // Update the end effector pose
154
155 // Update the camera pose
156 wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
157
158 // Update the jacobian
160
161 break;
162 }
164 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
165 "functionality not implemented");
167 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the reference frame:"
168 "functionality not implemented");
170 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
171 "functionality not implemented");
173 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
174 "functionality not implemented");
175 }
176}
177
183
184/*
185 Get the current position of the robot.
186
187 \param frame : Control frame type in which to get the position, either :
188 - in the camera cartesien frame,
189 - joint (articular) coordinates of each axes (not implemented)
190 - in a reference or fixed cartesien frame attached to the robot base
191 - in a mixt cartesien frame (translation in reference frame, and rotation in
192 camera frame)
193
194 \param position : Measured position of the robot:
195 - in camera cartesien frame, a 6 dimension vector, set to 0.
196
197 - in articular, this functionality is not implemented.
198
199 - in reference frame, a 6 dimension vector, the first 3 values correspond to
200 the translation tx, ty, tz in meters (like a vpTranslationVector), and the
201 last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
202*/
204{
205 q.resize(6);
206
207 switch (frame) {
209 q = 0;
210 break;
211
213 std::cout << "ARTICULAR_FRAME is not implemented in "
214 "vpSimulatorPioneer::getPosition()"
215 << std::endl;
216 break;
218 // Convert wMc_ to a position
219 // From fMc extract the pose
221 this->wMc_.extract(wRc);
222 vpRxyzVector rxyz;
223 rxyz.buildFrom(wRc);
224
225 for (unsigned int i = 0; i < 3; i++) {
226 q[i] = this->wMc_[i][3]; // translation x,y,z
227 q[i + 3] = rxyz[i]; // Euler rotation x,y,z
228 }
229
230 break;
231 }
233 std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
234 break;
236 std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
237 break;
238 }
239}
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:292
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
@ 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:152
void set_eJe(double q_pan)
void set_pMe(const double q)
vpHomogeneousMatrix mMp_
vpHomogeneousMatrix pMe_
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:100
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:142
double * qmin
Definition vpRobot.h:111
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:160
vpControlFrameType
Definition vpRobot.h:73
@ REFERENCE_FRAME
Definition vpRobot.h:74
@ ARTICULAR_FRAME
Definition vpRobot.h:76
@ MIXT_FRAME
Definition vpRobot.h:84
@ CAMERA_FRAME
Definition vpRobot.h:80
@ END_EFFECTOR_FRAME
Definition vpRobot.h:79
double * qmax
Definition vpRobot.h:112
int areJointLimitsAvailable
Definition vpRobot.h:110
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition vpRobot.h:108
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
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:104
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.
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void getPosition(vpHomogeneousMatrix &wMc) const
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
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:104
vpHomogeneousMatrix cMe_
Definition vpUnicycle.h:124
#define vpERROR_TRACE
Definition vpDebug.h:388