Visual Servoing Platform
version 3.1.0
|
#include <visp3/robot/vpViper650.h>
Public Types | |
enum | vpToolType { TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, TOOL_GENERIC_CAMERA, TOOL_CUSTOM } |
Protected Member Functions | |
Protected Member Functions Inherited from vpViper650 | |
void | setToolType (vpViper650::vpToolType tool) |
Protected Attributes | |
vpToolType | tool_current |
vpCameraParameters::vpCameraParametersProjType | projModel |
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 |
Modelisation of the ADEPT Viper 650 robot.
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.
Definition at line 102 of file vpViper650.h.
List of possible tools that can be attached to the robot end-effector.
Definition at line 127 of file vpViper650.h.
vpViper650::vpViper650 | ( | ) |
Default constructor. Sets the specific parameters like the Denavit Hartenberg parameters.
Definition at line 102 of file vpViper650.cpp.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::c56, vpViper::d1, vpViper::d4, vpViper::d6, init(), vpViper::joint_max, vpViper::joint_min, and vpMath::rad().
|
inlinevirtual |
Definition at line 139 of file vpViper650.h.
References vpCameraParameters::perspectiveProjWithoutDistortion.
|
inherited |
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 vpViper::eMc, and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::get_cMe(), vpRobotViper650::get_cMe(), vpRobotViper850::get_cMe(), vpViper::get_cVe(), vpSimulatorViper850::get_cVe(), vpRobotViper650::get_cVe(), vpRobotViper850::get_cVe(), vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), and vpSimulatorViper850::getPositioningVelocity().
|
inherited |
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 vpViper::get_cMe().
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), and vpSimulatorViper850::getPositioningVelocity().
|
inherited |
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(), vpViper::get_fJw(), vpViper::get_fMw(), vpViper::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().
|
inherited |
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 vpViper::eMc.
Referenced by vpViper::getInverseKinematics().
|
inherited |
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 vpViper::d7, and vpHomogeneousMatrix::eye().
|
inherited |
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(), vpViper::get_fJw(), vpViper::get_fMw(), vpViper::get_wMe(), and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::computeArticularVelocity(), vpSimulatorViper850::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpSimulatorViper850::getVelocity().
|
inherited |
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 vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d4, and vpArray2D< Type >::resize().
Referenced by vpViper::get_eJe(), and vpViper::get_fJe().
|
inherited |
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(), vpViper::getForwardKinematics(), vpSimulatorViper850::getPosition(), vpRobotViper650::getVelocity(), vpRobotViper850::getVelocity(), vpSimulatorViper850::setPosition(), vpRobotViper650::setPosition(), and vpRobotViper850::setPosition().
|
inherited |
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.
References vpViper::eMc, and vpViper::get_fMe().
|
inherited |
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 vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, and vpViper::d6.
Referenced by vpViper::get_fMc().
|
inherited |
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.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, and vpViper::d4.
Referenced by vpViper::get_eJe(), and vpViper::get_fJe().
|
inherited |
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 vpViper::d6, and vpHomogeneousMatrix::eye().
Referenced by vpViper::get_eJe(), vpViper::get_fJe(), and vpViper::getInverseKinematics().
void vpViper650::getCameraParameters | ( | vpCameraParameters & | cam, |
const unsigned int & | image_width, | ||
const unsigned int & | image_height | ||
) | const |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
image_width | : Image width used to compute camera calibration. |
image_height | : Image height used to compute camera calibration. |
The code below shows how to get the camera parameters of the camera attached to the robot.
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 539 of file vpViper650.cpp.
References vpException::badValue, CONST_CAMERA_FILENAME, CONST_GENERIC_CAMERA_NAME, CONST_MARLIN_F033C_CAMERA_NAME, CONST_PTGREY_FLEA2_CAMERA_NAME, CONST_SCHUNK_GRIPPER_CAMERA_NAME, getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, TOOL_CUSTOM, TOOL_GENERIC_CAMERA, TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, vpERROR_TRACE, and vpTRACE.
Referenced by getCameraParameters().
void vpViper650::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< unsigned char > & | I | ||
) | const |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
I | : A B&W image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 739 of file vpViper650.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
void vpViper650::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< vpRGBa > & | I | ||
) | const |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
I | : A color image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 807 of file vpViper650.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inline |
Get the current camera model projection type.
Definition at line 152 of file vpViper650.h.
|
inherited |
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 vpViper::c56.
|
inherited |
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.
References vpViper::get_fMc(), vpViper::joint_max, and vpViper::joint_min.
|
inherited |
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 vpViper::get_eMc(), vpViper::get_wMe(), vpViper::getInverseKinematicsWrist(), and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorViper850::initialiseCameraRelativeToObject(), vpSimulatorViper850::setPosition(), vpRobotViper650::setPosition(), and vpRobotViper850::setPosition().
|
inherited |
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 vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, vpArray2D< Type >::getRows(), vpViper::njoint, vpMath::rad(), vpColVector::resize(), and vpMath::sqr().
Referenced by vpViper::getInverseKinematics().
|
inherited |
Get maximal joint values.
Definition at line 1208 of file vpViper.cpp.
References vpViper::joint_max.
|
inherited |
Get minimal joint values.
Definition at line 1199 of file vpViper.cpp.
References vpViper::joint_min.
|
inline |
Get the current tool type.
Definition at line 160 of file vpViper650.h.
Referenced by getCameraParameters().
void vpViper650::init | ( | void | ) |
Initialize the robot with the default tool vpViper650::defaultTool.
Definition at line 135 of file vpViper650.cpp.
References defaultTool.
Referenced by init(), vpRobotViper650::init(), and vpViper650().
void vpViper650::init | ( | const std::string & | camera_extrinsic_parameters | ) |
Read files containing the constant parameters related to the robot tools in order to set the end-effector to tool transformation.
camera_extrinsic_parameters | : Filename containing the camera extrinsic parameters. |
Definition at line 150 of file vpViper650.cpp.
References parseConfigFile().
void vpViper650::init | ( | vpViper650::vpToolType | tool, |
vpCameraParameters::vpCameraParametersProjType | proj_model = vpCameraParameters::perspectiveProjWithoutDistortion |
||
) |
Set the constant parameters related to the robot kinematics and to the end-effector to camera transformation ( ) corresponding to the camera extrinsic parameters. These last parameters depend on the camera and projection model in use and are loaded from predefined files or parameters.
tool | : Camera in use. |
proj_model | : Projection model of the camera. |
Definition at line 179 of file vpViper650.cpp.
References vpException::badValue, vpHomogeneousMatrix::buildFrom(), CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME, CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME, CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME, CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME, CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME, CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME, CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME, CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME, vpViper::eMc, vpViper::erc, vpViper::etc, init(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpMath::rad(), setToolType(), TOOL_CUSTOM, TOOL_GENERIC_CAMERA, TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, and vpERROR_TRACE.
void vpViper650::init | ( | vpViper650::vpToolType | tool, |
const std::string & | filename | ||
) |
Set the type of tool attached to the robot and transformation between the end-effector and the tool ( ). This last parameter is loaded from a file.
tool | : Type of tool in use. |
filename | : Path of the configuration file containing the transformation between the end-effector frame and the tool frame. |
The configuration file should have the form below:
Definition at line 361 of file vpViper650.cpp.
References parseConfigFile(), and setToolType().
void vpViper650::init | ( | vpViper650::vpToolType | tool, |
const vpHomogeneousMatrix & | eMc_ | ||
) |
Set the type of tool attached to the robot and the transformation between the end-effector and the tool ( ).
tool | : Type of tool in use. |
eMc_ | : Homogeneous matrix representation of the transformation between the end-effector frame and the tool frame. |
Definition at line 382 of file vpViper650.cpp.
References vpViper::set_eMc(), and setToolType().
void vpViper650::parseConfigFile | ( | const std::string & | filename | ) |
This function gets the robot constant parameters from a file.
filename | : File name containing the robot constant parameters, like the hand-to-eye transformation. |
Definition at line 396 of file vpViper650.cpp.
References vpViper::erc, vpViper::etc, vpRobotException::readingParametersError, and vpViper::set_eMc().
Referenced by init().
|
virtualinherited |
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(), vpViper::eMc, vpViper::erc, vpViper::etc, and vpHomogeneousMatrix::extract().
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), init(), vpViper850::init(), parseConfigFile(), vpViper850::parseConfigFile(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
virtualinherited |
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(), vpViper::eMc, vpViper::erc, and vpViper::etc.
|
inlineprotected |
|
protectedinherited |
Definition at line 163 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 2
Definition at line 164 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 3
Definition at line 165 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
Mechanical coupling between joint 5 and joint 6.
Definition at line 169 of file vpViper.h.
Referenced by vpViper::getCoupl56(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
static |
Definition at line 116 of file vpViper650.h.
Referenced by getCameraParameters().
|
static |
Definition at line 115 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 114 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 109 of file vpViper650.h.
Referenced by init().
|
static |
Files where constant tranformation between end-effector and camera frame are stored.
Definition at line 108 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 111 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 110 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 113 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 112 of file vpViper650.h.
Referenced by init().
|
static |
Definition at line 124 of file vpViper650.h.
Referenced by getCameraParameters().
|
static |
Name of the camera attached to the end-effector.
Definition at line 121 of file vpViper650.h.
Referenced by getCameraParameters().
|
static |
Definition at line 122 of file vpViper650.h.
Referenced by getCameraParameters().
|
static |
Definition at line 123 of file vpViper650.h.
Referenced by getCameraParameters().
|
protectedinherited |
for joint 1
Definition at line 163 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 4
Definition at line 166 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpSimulatorViper850::singularityTest(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 6
Definition at line 167 of file vpViper.h.
Referenced by vpSimulatorViper850::compute_fMi(), vpViper::get_fMe(), vpViper::get_wMe(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for force/torque location
Definition at line 168 of file vpViper.h.
Referenced by vpViper::get_eMs(), and vpViper::vpViper().
|
static |
Default tool attached to the robot end effector.
Definition at line 136 of file vpViper650.h.
Referenced by init(), and vpRobotViper650::init().
|
protectedinherited |
End effector to camera transformation.
Definition at line 157 of file vpViper.h.
Referenced by vpSimulatorViper850::computeArticularVelocity(), vpViper::get_cMe(), vpViper::get_eMc(), vpViper::get_fMc(), vpSimulatorViper850::getVelocity(), init(), vpViper850::init(), vpSimulatorViper850::init(), vpViper::set_eMc(), and vpViper::vpViper().
|
protectedinherited |
Definition at line 160 of file vpViper.h.
Referenced by init(), vpViper850::init(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), parseConfigFile(), vpViper850::parseConfigFile(), vpViper::set_eMc(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
protectedinherited |
Definition at line 159 of file vpViper.h.
Referenced by init(), vpViper850::init(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), parseConfigFile(), vpViper850::parseConfigFile(), vpViper::set_eMc(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().
|
protectedinherited |
Definition at line 172 of file vpViper.h.
Referenced by vpViper::getForwardKinematics(), vpViper::getJointMax(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpSimulatorViper850::isInJointLimit(), vpSimulatorViper850::setJointLimit(), vpSimulatorViper850::updateArticularPosition(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
Definition at line 173 of file vpViper.h.
Referenced by vpViper::getForwardKinematics(), vpViper::getJointMin(), vpSimulatorViper850::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpSimulatorViper850::isInJointLimit(), vpSimulatorViper850::setJointLimit(), vpSimulatorViper850::updateArticularPosition(), vpViper::vpViper(), vpViper650(), and vpViper850::vpViper850().
|
staticinherited |
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(), vpViper::getInverseKinematicsWrist(), vpSimulatorViper850::init(), vpSimulatorViper850::readPosFile(), vpRobotViper650::readPosFile(), vpRobotViper850::readPosFile(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), and vpViper::vpViper().
|
protected |
Definition at line 176 of file vpViper650.h.
Referenced by getCameraParameters(), and init().
|
protected |
Current tool in use.
Definition at line 169 of file vpViper650.h.