Visual Servoing Platform
version 3.2.0 under development (2019-01-22)
|
#include <visp3/robot/vpViper.h>
Static Public Attributes | |
static const unsigned int | njoint = 6 |
Protected Attributes | |
vpHomogeneousMatrix | eMc |
vpTranslationVector | etc |
vpRxyzVector | erc |
double | a1 |
double | d1 |
double | a2 |
double | a3 |
double | d4 |
double | d6 |
double | d7 |
double | c56 |
vpColVector | joint_max |
vpColVector | joint_min |
Friends | |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpViper &viper) |
Modelisation of the ADEPT Viper robot.
This robot has six degrees of freedom. The model of the robot is the following:
The non modified Denavit-Hartenberg representation of the robot is given in the table below, where are the variable joint positions.
In this modelisation, different frames have to be considered.
The forward kinematics of the robot is implemented in get_fMw(), get_fMe() and get_fMc().
The robot forward jacobian used to compute the cartesian velocities from joint ones is given and implemented in get_fJw(), get_fJe() and get_eJe().
vpViper::vpViper | ( | ) |
Default constructor.
Definition at line 65 of file vpViper.cpp.
References a1, a2, a3, c56, d1, d4, d6, d7, eMc, vpHomogeneousMatrix::eye(), joint_max, joint_min, njoint, vpMath::rad(), and vpColVector::resize().
void vpViper::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the geometric transformation between the camera frame and the end-effector frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
cMe | : Transformation between the camera frame and the end-effector frame. |
Definition at line 922 of file vpViper.cpp.
References eMc, and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::get_cMe(), vpRobotViper650::get_cMe(), vpRobotViper850::get_cMe(), get_cVe(), vpSimulatorViper850::get_cVe(), vpRobotViper650::get_cVe(), vpRobotViper850::get_cVe(), vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), and vpSimulatorViper850::getPositioningVelocity().
void vpViper::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) | const |
Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.
cVe | : Twist transformation . |
Definition at line 938 of file vpViper.cpp.
References vpVelocityTwistMatrix::buildFrom(), and get_cMe().
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), and vpSimulatorViper850::getPositioningVelocity().
void vpViper::get_eJe | ( | const vpColVector & | q, |
vpMatrix & | eJe | ||
) | const |
Get the robot jacobian which gives the velocity of the origin of the end-effector frame expressed in end-effector frame.
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
eJe | : Robot jacobian that express the velocity of the end-effector in the robot end-effector frame. |
Definition at line 970 of file vpViper.cpp.
References vpHomogeneousMatrix::extract(), get_fJw(), get_fMw(), get_wMe(), vpRotationMatrix::inverse(), vpHomogeneousMatrix::inverse(), and vpTranslationVector::skew().
Referenced by vpSimulatorViper850::computeArticularVelocity(), vpSimulatorViper850::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), and vpSimulatorViper850::getVelocity().
void vpViper::get_eMc | ( | vpHomogeneousMatrix & | eMc_ | ) | const |
Get the geometric transformation between the end-effector frame and the camera frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
eMc_ | : Transformation between the the end-effector frame and the camera frame. |
Definition at line 894 of file vpViper.cpp.
References eMc.
Referenced by getInverseKinematics().
void vpViper::get_eMs | ( | vpHomogeneousMatrix & | eMs | ) | const |
Get the geometric transformation between the end-effector frame and the force/torque sensor frame. This transformation is constant.
eMs | : Transformation between the the end-effector frame and the force/torque sensor frame. |
Definition at line 905 of file vpViper.cpp.
References d7, and vpHomogeneousMatrix::eye().
void vpViper::get_fJe | ( | const vpColVector & | q, |
vpMatrix & | fJe | ||
) | const |
Get the robot jacobian which gives the velocity of the origin of the end-effector frame expressed in the robot reference frame also called fix frame.
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
fJe | : Robot jacobian that express the velocity of the end-effector in the robot reference frame. |
Definition at line 1159 of file vpViper.cpp.
References vpHomogeneousMatrix::extract(), get_fJw(), get_fMw(), get_wMe(), and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::computeArticularVelocity(), vpSimulatorViper850::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpSimulatorViper850::getVelocity().
void vpViper::get_fJw | ( | const vpColVector & | q, |
vpMatrix & | fJw | ||
) | const |
Get the robot jacobian which express the velocity of the origin of the wrist frame in the robot reference frame also called fix frame.
with
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
fJw | : Robot jacobian that express the velocity of the point w (origin of the wrist frame) in the robot reference frame. |
Definition at line 1054 of file vpViper.cpp.
References a1, a2, a3, d4, and vpArray2D< Type >::resize().
vpHomogeneousMatrix vpViper::get_fMc | ( | const vpColVector & | q | ) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the joint positions of all the six joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Vector of six joint positions expressed in radians. |
Definition at line 600 of file vpViper.cpp.
Referenced by vpSimulatorViper850::compute_fMi(), getForwardKinematics(), vpSimulatorViper850::getPosition(), vpRobotViper650::getPosition(), vpRobotViper850::getPosition(), vpRobotViper650::getVelocity(), vpRobotViper850::getVelocity(), vpSimulatorViper850::setPosition(), vpRobotViper650::setPosition(), and vpRobotViper850::setPosition().
void vpViper::get_fMc | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the six joint positions.
q | : Vector of six joint positions expressed in radians. |
fMc | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame. |
Definition at line 629 of file vpViper.cpp.
void vpViper::get_fMe | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMe | ||
) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix .
By forward kinematics we mean here the position and the orientation of the end effector with respect to the base frame given the motor positions of all the six joints.
with
q | : A 6-dimension vector that contains the 6 joint positions expressed in radians. |
fMe | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame. |
Note that this transformation can also be computed by considering the wrist frame .
Definition at line 715 of file vpViper.cpp.
References a1, a2, a3, d1, d4, and d6.
Referenced by get_fMc().
void vpViper::get_fMw | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMw | ||
) | const |
Compute the transformation between the fix frame and the wrist frame. The wrist frame is located on the intersection of the 3 last rotations.
q | : A 6-dimension vector that contains the 6 joint positions expressed in radians. |
fMw | The homogeneous matrix corresponding to the transformation between the fix frame and the wrist frame (fMw). |
with
Definition at line 810 of file vpViper.cpp.
void vpViper::get_wMe | ( | vpHomogeneousMatrix & | wMe | ) | const |
Return the transformation between the wrist frame and the end-effector. The wrist frame is located on the intersection of the 3 last rotations.
wMe | The homogeneous matrix corresponding to the transformation between the wrist frame and the end-effector frame (wMe). |
Definition at line 874 of file vpViper.cpp.
References d6, and vpHomogeneousMatrix::eye().
Referenced by get_eJe(), get_fJe(), and getInverseKinematics().
double vpViper::getCoupl56 | ( | ) | const |
Return the coupling factor between join 5 and joint 6.
This factor should be only useful when motor positions are considered. Since the positions returned by the robot are joint positions which takes into account the coupling factor, it has not to be considered in the modelization of the robot.
Definition at line 1220 of file vpViper.cpp.
References c56.
vpHomogeneousMatrix vpViper::getForwardKinematics | ( | const vpColVector & | q | ) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the six joint positions.
This method is the same than get_fMc(const vpColVector & q).
q | : A six dimension vector corresponding to the robot joint positions expressed in radians. |
Definition at line 121 of file vpViper.cpp.
unsigned int vpViper::getInverseKinematics | ( | const vpHomogeneousMatrix & | fMc, |
vpColVector & | q, | ||
const bool & | verbose = false |
||
) | const |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
fMc | : Homogeneous matrix describing the transformation from base frame to the camera frame. |
q | : In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to . |
verbose | : Add extra printings. |
The code below shows how to compute the inverse geometric model:
Definition at line 563 of file vpViper.cpp.
References get_eMc(), get_wMe(), getInverseKinematicsWrist(), and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::initialiseCameraRelativeToObject(), vpSimulatorViper850::setPosition(), vpRobotViper650::setPosition(), and vpRobotViper850::setPosition().
unsigned int vpViper::getInverseKinematicsWrist | ( | const vpHomogeneousMatrix & | fMw, |
vpColVector & | q, | ||
const bool & | verbose = false |
||
) | const |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
fMw | : Homogeneous matrix describing the transformation from base frame to the wrist frame. |
q | : In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to . |
verbose | : Add extra printings. |
The code below shows how to compute the inverse geometric model:
Definition at line 222 of file vpViper.cpp.
References a1, a2, a3, d1, d4, vpArray2D< Type >::getRows(), njoint, vpMath::rad(), vpColVector::resize(), and vpMath::sqr().
Referenced by getInverseKinematics().
vpColVector vpViper::getJointMax | ( | ) | const |
Get maximal joint values.
Definition at line 1208 of file vpViper.cpp.
References joint_max.
vpColVector vpViper::getJointMin | ( | ) | const |
Get minimal joint values.
Definition at line 1199 of file vpViper.cpp.
References joint_min.
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).
eMc_ | : Transformation between the end-effector frame and the tool frame. |
Reimplemented in vpRobotViper850, and vpRobotViper650.
Definition at line 1230 of file vpViper.cpp.
References vpRxyzVector::buildFrom(), eMc, erc, etc, and vpHomogeneousMatrix::extract().
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpViper650::init(), vpViper850::init(), vpViper650::parseConfigFile(), vpViper850::parseConfigFile(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera frame).
etc_ | : Translation between the end-effector frame and the tool frame. |
erc_ | : Rotation between the end-effector frame and the tool frame using the Euler angles in radians with the XYZ convention. |
Reimplemented in vpRobotViper850, and vpRobotViper650.
Definition at line 1248 of file vpViper.cpp.
References vpHomogeneousMatrix::buildFrom(), eMc, erc, and etc.
|
friend |
Print on the output stream os the robot parameters (joint min/max, coupling factor between axis 5 and 6, hand-to-eye constant homogeneous matrix .
os | : Output stream. |
viper | : Robot parameters. |
Definition at line 1265 of file vpViper.cpp.
|
protected |
Definition at line 163 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fJw(), get_fMe(), get_fMw(), getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
for joint 2
Definition at line 164 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fJw(), get_fMe(), get_fMw(), getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
for joint 3
Definition at line 165 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fJw(), get_fMe(), get_fMw(), getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
Mechanical coupling between joint 5 and joint 6.
Definition at line 169 of file vpViper.h.
Referenced by getCoupl56(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
for joint 1
Definition at line 163 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fMe(), get_fMw(), getInverseKinematicsWrist(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
for joint 4
Definition at line 166 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fJw(), get_fMe(), get_fMw(), getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
for joint 6
Definition at line 167 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), get_fMe(), get_wMe(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
|
protected |
End effector to camera transformation.
Definition at line 157 of file vpViper.h.
Referenced by vpSimulatorViper850::computeArticularVelocity(), get_cMe(), get_eMc(), get_fMc(), vpSimulatorViper850::getVelocity(), vpViper650::init(), vpViper850::init(), vpSimulatorViper850::init(), set_eMc(), and vpViper().
|
protected |
Definition at line 160 of file vpViper.h.
Referenced by vpViper650::init(), vpViper850::init(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpViper650::parseConfigFile(), vpViper850::parseConfigFile(), set_eMc(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
protected |
Definition at line 159 of file vpViper.h.
Referenced by vpViper650::init(), vpViper850::init(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpViper650::parseConfigFile(), vpViper850::parseConfigFile(), set_eMc(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
protected |
Definition at line 172 of file vpViper.h.
Referenced by getForwardKinematics(), getJointMax(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpSimulatorViper850::isInJointLimit(), vpSimulatorViper850::setJointLimit(), vpSimulatorViper850::updateArticularPosition(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protected |
Definition at line 173 of file vpViper.h.
Referenced by getForwardKinematics(), getJointMin(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpSimulatorViper850::isInJointLimit(), vpSimulatorViper850::setJointLimit(), vpSimulatorViper850::updateArticularPosition(), vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
static |
Number of joint.
Definition at line 154 of file vpViper.h.
Referenced by vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), vpRobotViper650::getDisplacement(), vpRobotViper850::getDisplacement(), getInverseKinematicsWrist(), vpRobotViper650::getPosition(), vpRobotViper850::getPosition(), vpSimulatorViper850::init(), vpSimulatorViper850::readPosFile(), vpRobotViper650::readPosFile(), vpRobotViper850::readPosFile(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), and vpViper().