Visual Servoing Platform  version 3.2.0 under development (2019-01-22)

#include <visp3/robot/vpViper850.h>

+ Inheritance diagram for vpViper850:

Public Types

enum  vpToolType {
  TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, TOOL_GENERIC_CAMERA,
  TOOL_CUSTOM
}
 

Public Member Functions

 vpViper850 ()
 
virtual ~vpViper850 ()
 
Inherited functionalities from vpViper850
void init (void)
 
void init (const std::string &camera_extrinsic_parameters)
 
void init (vpViper850::vpToolType tool, vpCameraParameters::vpCameraParametersProjType projModel=vpCameraParameters::perspectiveProjWithoutDistortion)
 
void init (vpViper850::vpToolType tool, const std::string &filename)
 
void init (vpViper850::vpToolType tool, const vpHomogeneousMatrix &eMc_)
 
vpCameraParameters::vpCameraParametersProjType getCameraParametersProjType () const
 
void getCameraParameters (vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
 
void getCameraParameters (vpCameraParameters &cam, const vpImage< unsigned char > &I) const
 
void getCameraParameters (vpCameraParameters &cam, const vpImage< vpRGBa > &I) const
 
vpToolType getToolType () const
 
void parseConfigFile (const std::string &filename)
 
Inherited functionalities from vpViper
vpHomogeneousMatrix getForwardKinematics (const vpColVector &q) const
 
unsigned int getInverseKinematicsWrist (const vpHomogeneousMatrix &fMw, vpColVector &q, const bool &verbose=false) const
 
unsigned int getInverseKinematics (const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
 
vpHomogeneousMatrix get_fMc (const vpColVector &q) const
 
void get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
void get_fMw (const vpColVector &q, vpHomogeneousMatrix &fMw) const
 
void get_wMe (vpHomogeneousMatrix &wMe) const
 
void get_eMc (vpHomogeneousMatrix &eMc) const
 
void get_eMs (vpHomogeneousMatrix &eMs) const
 
void get_fMe (const vpColVector &q, vpHomogeneousMatrix &fMe) const
 
void get_cMe (vpHomogeneousMatrix &cMe) const
 
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
void get_fJw (const vpColVector &q, vpMatrix &fJw) const
 
void get_fJe (const vpColVector &q, vpMatrix &fJe) const
 
void get_eJe (const vpColVector &q, vpMatrix &eJe) const
 
virtual void set_eMc (const vpHomogeneousMatrix &eMc_)
 
virtual void set_eMc (const vpTranslationVector &etc_, const vpRxyzVector &erc_)
 
vpColVector getJointMin () const
 
vpColVector getJointMax () const
 
double getCoupl56 () const
 

Static Public Attributes

static const std::string CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
 
static const std::string CONST_CAMERA_FILENAME
 
static const char *const CONST_MARLIN_F033C_CAMERA_NAME = "Marlin-F033C-12mm"
 
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME = "PTGrey-Flea2-6mm"
 
static const char *const CONST_SCHUNK_GRIPPER_CAMERA_NAME = "Schunk-Gripper-PTGrey-Flea2-6mm"
 
static const char *const CONST_GENERIC_CAMERA_NAME = "Generic-camera"
 
static const vpToolType defaultTool = vpViper850::TOOL_PTGREY_FLEA2_CAMERA
 
static const unsigned int njoint = 6
 

Protected Member Functions

Protected Member Functions Inherited from vpViper650
void setToolType (vpViper850::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
 

Detailed Description

Modelisation of the ADEPT Viper 850 robot.

The model of the robot is the following:

model-viper.png
Model of the Viper 850 robot.

The non modified Denavit-Hartenberg representation of the robot is given in the table below, where $q_1^*, \ldots, q_6^*$ are the variable joint positions.

\[ \begin{tabular}{|c|c|c|c|c|} \hline Joint & $a_i$ & $d_i$ & $\alpha_i$ & $\theta_i$ \\ \hline 1 & $a_1$ & $d_1$ & $-\pi/2$ & $q_1^*$ \\ 2 & $a_2$ & 0 & 0 & $q_2^*$ \\ 3 & $a_3$ & 0 & $-\pi/2$ & $q_3^* - \pi$ \\ 4 & 0 & $d_4$ & $\pi/2$ & $q_4^*$ \\ 5 & 0 & 0 & $-\pi/2$ & $q_5^*$ \\ 6 & 0 & 0 & 0 & $q_6^*-\pi$ \\ 7 & 0 & $d_6$ & 0 & 0 \\ \hline \end{tabular} \]

In this modelisation, different frames have to be considered.

  • $ {\cal F}_f $: the reference frame, also called world frame
  • $ {\cal F}_w $: the wrist frame located at the intersection of the last three rotations, with $ ^f{\bf M}_w = ^0{\bf M}_6 $
  • $ {\cal F}_e $: the end-effector frame located at the interface of the two tool changers, with $^f{\bf M}_e = 0{\bf M}_7 $
  • $ {\cal F}_c $: the camera or tool frame, with $^f{\bf M}_c = ^f{\bf M}_e \; ^e{\bf M}_c $ where $ ^e{\bf M}_c $ is the result of a calibration stage. We can also consider a custom tool TOOL_CUSTOM and set this during robot initialisation or using set_eMc().
  • $ {\cal F}_s $: the force/torque sensor frame, with $d7=0.0666$.
Examples:
testViper850.cpp.

Definition at line 103 of file vpViper850.h.

Member Enumeration Documentation

List of possible tools that can be attached to the robot end-effector.

Enumerator
TOOL_MARLIN_F033C_CAMERA 

Marlin F033C camera.

TOOL_PTGREY_FLEA2_CAMERA 

Point Grey Flea 2 camera.

TOOL_SCHUNK_GRIPPER_CAMERA 

Camera attached to the Schunk gripper.

TOOL_GENERIC_CAMERA 

A generic camera.

TOOL_CUSTOM 

A user defined tool.

Definition at line 128 of file vpViper850.h.

Constructor & Destructor Documentation

vpViper850::vpViper850 ( )

Default constructor. Sets the specific parameters like the Denavit Hartenberg parameters.

Definition at line 102 of file vpViper850.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().

virtual vpViper850::~vpViper850 ( )
inlinevirtual

Member Function Documentation

void vpViper::get_cMe ( vpHomogeneousMatrix cMe) const
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.

Parameters
cMe: Transformation between the camera frame and the end-effector frame.
See also
get_eMc()

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().

void vpViper::get_cVe ( vpVelocityTwistMatrix cVe) const
inherited

Get the twist transformation $^c{\bf V}_e$ from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.

\[ ^c{\bf V}_e = \left(\begin{array}{cc} ^c{\bf R}_e & [^c{\bf t}_e]_\times ^c{\bf R}_e\\ {\bf 0}_{3\times 3} & ^c{\bf R}_e \end{array} \right) \]

Parameters
cVe: Twist transformation $^c{\bf V}_e$.

Definition at line 938 of file vpViper.cpp.

References vpVelocityTwistMatrix::buildFrom(), and vpViper::get_cMe().

Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), and vpSimulatorViper850::getPositioningVelocity().

void vpViper::get_eJe ( const vpColVector q,
vpMatrix eJe 
) const
inherited

Get the robot jacobian ${^e}{\bf J}_e$ which gives the velocity of the origin of the end-effector frame expressed in end-effector frame.

\[ {^e}{\bf J}_e = \left[\begin{array}{cc} {^w}{\bf R}_f & {[{^e}{\bf t}_w}]_\times \; {^w}{\bf R}_f \\ 0_{3\times3} & {^w}{\bf R}_f \end{array} \right] \; {^f}{\bf J}_w \]

Parameters
q: A six-dimension vector that contains the joint positions of the robot expressed in radians.
eJe: Robot jacobian ${^e}{\bf J}_e$ that express the velocity of the end-effector in the robot end-effector frame.
See also
get_fJw()

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().

void vpViper::get_eMc ( vpHomogeneousMatrix eMc_) const
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.

Parameters
eMc_: Transformation between the the end-effector frame and the camera frame.
See also
get_cMe()
Examples:
servoViper650FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent-SR300.cpp, and servoViper650FourPoints2DCamVelocityInteractionCurrent.cpp.

Definition at line 894 of file vpViper.cpp.

References vpViper::eMc.

Referenced by vpViper::getInverseKinematics().

void vpViper::get_eMs ( vpHomogeneousMatrix eMs) const
inherited

Get the geometric transformation between the end-effector frame and the force/torque sensor frame. This transformation is constant.

Parameters
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().

void vpViper::get_fJe ( const vpColVector q,
vpMatrix fJe 
) const
inherited

Get the robot jacobian ${^f}{\bf J}_e$ which gives the velocity of the origin of the end-effector frame expressed in the robot reference frame also called fix frame.

\[ {^f}{\bf J}_e = \left[\begin{array}{cc} I_{3\times3} & [{^f}{\bf R}_w \; {^e}{\bf t}_w]_\times \\ 0_{3\times3} & I_{3\times3} \end{array} \right] {^f}{\bf J}_w \]

Parameters
q: A six-dimension vector that contains the joint positions of the robot expressed in radians.
fJe: Robot jacobian ${^f}{\bf J}_e$ that express the velocity of the end-effector in the robot reference frame.
See also
get_fJw

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().

void vpViper::get_fJw ( const vpColVector q,
vpMatrix fJw 
) const
inherited

Get the robot jacobian ${^f}{\bf J}_w$ which express the velocity of the origin of the wrist frame in the robot reference frame also called fix frame.

\[ {^f}J_w = \left(\begin{array}{cccccc} J_{11} & J_{12} & J_{13} & 0 & 0 & 0 \\ J_{21} & J_{22} & J_{23} & 0 & 0 & 0 \\ 0 & J_{32} & J_{33} & 0 & 0 & 0 \\ 0 & -s1 & -s1 & c1s23 & J_{45} & J_{46} \\ 0 & c1 & c1 & s1s23 & J_{55} & J_{56} \\ 1 & 0 & 0 & c23 & s23s4 & J_{56} \\ \end{array} \right) \]

with

\[ \begin{array}{l} J_{11} = -s1(-c23a3+s23d4+a1+a2c2) \\ J_{21} = c1(-c23a3+s23d4+a1+a2c2) \\ J_{12} = c1(s23a3+c23d4-a2s2) \\ J_{22} = s1(s23a3+c23d4-a2s2) \\ J_{32} = c23a3-s23d4-a2c2 \\ J_{13} = c1(a3(s2c3+c2s3)+(-s2s3+c2c3)d4)\\ J_{23} = s1(a3(s2c3+c2s3)+(-s2s3+c2c3)d4)\\ J_{33} = -a3(s2s3-c2c3)-d4(s2c3+c2s3)\\ J_{45} = -c23c1s4-s1c4\\ J_{55} = c1c4-c23s1s4\\ J_{46} = (c1c23c4-s1s4)s5+c1s23c5\\ J_{56} = (s1c23c4+c1s4)s5+s1s23c5\\ J_{66} = -s23c4s5+c23c5\\ \end{array} \]

Parameters
q: A six-dimension vector that contains the joint positions of the robot expressed in radians.
fJw: Robot jacobian ${^f}{\bf J}_w$ that express the velocity of the point w (origin of the wrist frame) in the robot reference frame.
See also
get_fJe(), get_eJe()

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().

vpHomogeneousMatrix vpViper::get_fMc ( const vpColVector q) const
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.

\[ ^f{\bf M}_c = ^f{\bf M}_e \; ^e{\bf M}_c \]

This method is the same than getForwardKinematics(const vpColVector & q).

Parameters
q: Vector of six joint positions expressed in radians.
Returns
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame (fMc).
See also
getForwardKinematics(const vpColVector & q), get_fMe(), get_eMc()
Examples:
testRobotViper650-frames.cpp, testRobotViper850-frames.cpp, and testRobotViper850Pose.cpp.

Definition at line 600 of file vpViper.cpp.

Referenced by vpSimulatorViper850::compute_fMi(), vpViper::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
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.

\[ ^f{\bf M}_c = ^f{\bf M}_e \; {^e}{\bf M}_c \]

Parameters
q: Vector of six joint positions expressed in radians.
fMcThe homogeneous matrix $^f{\bf M}_c$corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame.
See also
get_fMe(), get_eMc()

Definition at line 629 of file vpViper.cpp.

References vpViper::eMc, and vpViper::get_fMe().

void vpViper::get_fMe ( const vpColVector q,
vpHomogeneousMatrix fMe 
) const
inherited

Compute the forward kinematics (direct geometric model) as an homogeneous matrix ${^f}{\bf M}_e$.

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.

\[ {^f}M_e = \left(\begin{array}{cccc} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \\ \end{array} \right) \]

with

\[ \begin{array}{l} r_{11} = c1(c23(c4c5c6-s4s6)-s23s5c6)-s1(s4c5c6+c4s6) \\ r_{21} = -s1(c23(-c4c5c6+s4s6)+s23s5c6)+c1(s4c5c6+c4s6) \\ r_{31} = s23(s4s6-c4c5c6)-c23s5c6 \\ \\ r_{12} = -c1(c23(c4c5s6+s4c6)-s23s5s6)+s1(s4c5s6-c4c6)\\ r_{22} = -s1(c23(c4c5s6+s4c6)-s23s5s6)-c1(s4c5s6-c4c6)\\ r_{32} = s23(c4c5s6+s4c6)+c23s5s6\\ \\ r_{13} = c1(c23c4s5+s23c5)-s1s4s5\\ r_{23} = s1(c23c4s5+s23c5)+c1s4s5\\ r_{33} = -s23c4s5+c23c5\\ \\ t_x = c1(c23(c4s5d6-a3)+s23(c5d6+d4)+a1+a2c2)-s1s4s5d6\\ t_y = s1(c23(c4s5d6-a3)+s23(c5d6+d4)+a1+a2c2)+c1s4s5d6\\ t_z = s23(a3-c4s5d6)+c23(c5d6+d4)-a2s2+d1\\ \end{array} \]

Parameters
q: A 6-dimension vector that contains the 6 joint positions expressed in radians.
fMeThe homogeneous matrix ${^f}{\bf M}_e$ 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 ${^f}{\bf M}_e = {^f}{\bf M}_w *{^w}{\bf M}_e$.

#include <visp3/robot/vpViper.h>
int main()
{
vpViper robot;
vpColVector q(6); // The measured six joint positions
vpHomogeneousMatrix fMe; // Transformation from fix frame to end-effector
robot.get_fMe(q, fMe); // Get the forward kinematics
// The forward kinematics can also be computed by considering the wrist frame
vpHomogeneousMatrix fMw; // Transformation from fix frame to wrist frame
robot.get_fMw(q, fMw);
vpHomogeneousMatrix wMe; // Transformation from wrist frame to end-effector
robot.get_wMe(wMe); // Constant transformation
// Compute the forward kinematics
fMe = fMw * wMe;
}
Examples:
testRobotViper650-frames.cpp, testRobotViper850-frames.cpp, testRobotViper850.cpp, testViper650.cpp, and testViper850.cpp.

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().

void vpViper::get_fMw ( const vpColVector q,
vpHomogeneousMatrix fMw 
) const
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.

Parameters
q: A 6-dimension vector that contains the 6 joint positions expressed in radians.
fMwThe homogeneous matrix corresponding to the transformation between the fix frame and the wrist frame (fMw).

\[ {^f}M_w = \left(\begin{array}{cccc} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \\ \end{array} \right) \]

with

\[ \begin{array}{l} r_{11} = c1(c23(c4c5c6-s4s6)-s23s5c6)-s1(s4c5c6+c4s6) \\ r_{21} = -s1(c23(-c4c5c6+s4s6)+s23s5c6)+c1(s4c5c6+c4s6) \\ r_{31} = s23(s4s6-c4c5c6)-c23s5c6 \\ \\ r_{12} = -c1(c23(c4c5s6+s4c6)-s23s5s6)+s1(s4c5s6-c4c6)\\ r_{22} = -s1(c23(c4c5s6+s4c6)-s23s5s6)-c1(s4c5s6-c4c6)\\ r_{32} = s23(c4c5s6+s4c6)+c23s5s6\\ \\ r_{13} = c1(c23c4s5+s23c5)-s1s4s5\\ r_{23} = s1(c23c4s5+s23c5)+c1s4s5\\ r_{33} = -s23c4s5+c23c5\\ \\ t_x = c1(-c23a3+s23d4+a1+a2c2)\\ t_y = s1(-c23a3+s23d4+a1+a2c2)\\ t_z = s23a3+c23d4-a2s2+d1\\ \end{array} \]

Examples:
testRobotViper650-frames.cpp, and testRobotViper850-frames.cpp.

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().

void vpViper::get_wMe ( vpHomogeneousMatrix wMe) const
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.

Parameters
wMeThe 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 vpViper850::getCameraParameters ( vpCameraParameters cam,
const unsigned int &  image_width,
const unsigned int &  image_height 
) const

Get the current intrinsic camera parameters obtained by calibration.

Warning
This method needs XML library to parse the file defined in vpViper850::CONST_CAMERA_FILENAME and containing the camera parameters. If XML is detected by ViSP, VISP_HAVE_XML2 macro is defined in include/visp3/core/vpConfig.h file.
Thid method needs also an access to the files containing the camera parameters in XML format. This access is available if VISP_HAVE_VIPER850_DATA macro is defined in include/visp3/core/vpConfig.h file.
  • If VISP_HAVE_VIPER850_DATA and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from const_camera_Viper850.xml config file.
  • If these two macros are not defined, this method set the camera parameters to default one.
Parameters
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.

#include <visp3/core/vpConfig.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotViper850.h>
#include <visp3/robot/vpViper850.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
#ifdef VISP_HAVE_DC1394
// Acquire an image to update image structure
g.acquire(I) ;
#endif
#ifdef VISP_HAVE_VIPER850
#else
vpViper850 robot;
#endif
// Get the intrinsic camera parameters depending on the image size
// Camera parameters are read from
// /udd/fspindle/robot/Viper850/current/include/const_camera_Viper850.xml
// if VISP_HAVE_VIPER850_DATA and VISP_HAVE_XML2 macros are defined
// in vpConfig.h file
try {
robot.getCameraParameters (cam, I.getWidth(), I.getHeight());
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.
Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, testRobotViper850.cpp, testRobotViper850Pose.cpp, and testViper850.cpp.

Definition at line 540 of file vpViper850.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 vpViper850::getCameraParameters ( vpCameraParameters cam,
const vpImage< unsigned char > &  I 
) const

Get the current intrinsic camera parameters obtained by calibration.

Warning
This method needs XML library to parse the file defined in vpViper850::CONST_CAMERA_FILENAME and containing the camera parameters. If XML is detected by ViSP, VISP_HAVE_XML2 macro is defined in include/visp3/core/vpConfig.h file.
Thid method needs also an access to the files containing the camera parameters in XML format. This access is available if VISP_HAVE_VIPER850_DATA macro is defined in include/visp3/core/vpConfig.h file.
  • If VISP_HAVE_VIPER850_DATA and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from const_camera_Viper850.xml config file.
  • If these two macros are not defined, this method set the camera parameters to default one.
Parameters
cam: In output, camera parameters to fill.
I: A B&W image send by the current camera in use.
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotViper850.h>
#include <visp3/robot/vpViper850.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
#ifdef VISP_HAVE_DC1394
// Acquire an image to update image structure
g.acquire(I) ;
#endif
#ifdef VISP_HAVE_VIPER850
#else
vpViper850 robot;
#endif
// Get the intrinsic camera parameters depending on the image size
try {
robot.getCameraParameters (cam, I);
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.

Definition at line 739 of file vpViper850.cpp.

References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

void vpViper850::getCameraParameters ( vpCameraParameters cam,
const vpImage< vpRGBa > &  I 
) const

Get the current intrinsic camera parameters obtained by calibration.

Warning
This method needs XML library to parse the file defined in vpViper850::CONST_CAMERA_FILENAME and containing the camera parameters. If XML is detected by ViSP, VISP_HAVE_XML2 macro is defined in include/visp3/core/vpConfig.h file.
Thid method needs also an access to the files containing the camera parameters in XML format. This access is available if VISP_HAVE_VIPER850_DATA macro is defined in include/visp3/core/vpConfig.h file.
  • If VISP_HAVE_VIPER850_DATA and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from const_camera_Viper850.xml config file.
  • If these two macros are not defined, this method set the camera parameters to default one.
Parameters
cam: In output, camera parameters to fill.
I: A color image send by the current camera in use.
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotViper850.h>
#include <visp3/robot/vpViper850.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
vpImage<vpRGBa> I(480, 640);
#ifdef VISP_HAVE_DC1394
// Acquire an image to update image structure
g.acquire(I) ;
#endif
#ifdef VISP_HAVE_VIPER850
#else
vpViper850 robot;
#endif
// Get the intrinsic camera parameters depending on the image size
try {
robot.getCameraParameters (cam, I);
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.

Definition at line 807 of file vpViper850.cpp.

References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

vpCameraParameters::vpCameraParametersProjType vpViper850::getCameraParametersProjType ( ) const
inline

Get the current camera model projection type.

Definition at line 153 of file vpViper850.h.

double vpViper::getCoupl56 ( ) const
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.

vpHomogeneousMatrix vpViper::getForwardKinematics ( const vpColVector q) const
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).

Parameters
q: A six dimension vector corresponding to the robot joint positions expressed in radians.
Returns
The homogeneous matrix $^f{\bf M}_c $ corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame.
See also
get_fMc(const vpColVector & q)
getInverseKinematics()

Definition at line 121 of file vpViper.cpp.

References vpViper::get_fMc(), vpViper::joint_max, and vpViper::joint_min.

unsigned int vpViper::getInverseKinematics ( const vpHomogeneousMatrix fMc,
vpColVector q,
const bool &  verbose = false 
) const
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.

Parameters
fMc: Homogeneous matrix $^f{\bf M}_c $ 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 $^f{\bf M}_c $.
verbose: Add extra printings.
Returns
Add printings if no solution was found.
The number of solutions (1 to 8) of the inverse geometric model. O, if no solution can be found.

The code below shows how to compute the inverse geometric model:

vpColVector q1(6), q2(6);
vpViper robot;
// Get the current joint position of the robot
robot.getPosition(vpRobot::ARTICULAR_FRAME, q1);
// Compute the pose of the camera in the reference frame using the
// direct geometric model
fMc = robot.getForwardKinematics(q1);
// this is similar to fMc = robot.get_fMc(q1);
// or robot.get_fMc(q1, fMc);
// Compute the inverse geometric model
int nbsol; // number of solutions (0, 1 to 8) of the inverse geometric model
// get the nearest solution to the current joint position
nbsol = robot.getInverseKinematics(fMc, q1);
if (nbsol == 0)
std::cout << "No solution of the inverse geometric model " << std::endl;
else if (nbsol >= 1)
std::cout << "Nearest solution: " << q1 << std::endl;
See also
getForwardKinematics(), getInverseKinematicsWrist
Examples:
testRobotViper650-frames.cpp, and testRobotViper850-frames.cpp.

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().

unsigned int vpViper::getInverseKinematicsWrist ( const vpHomogeneousMatrix fMw,
vpColVector q,
const bool &  verbose = false 
) const
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.

Parameters
fMw: Homogeneous matrix $^f{\bf M}_w $ 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 $^f{\bf M}_w $.
verbose: Add extra printings.
Returns
Add printings if no solution was found.
The number of solutions (1 to 8) of the inverse geometric model. O, if no solution can be found.

The code below shows how to compute the inverse geometric model:

vpColVector q1(6), q2(6);
vpViper robot;
// Get the current joint position of the robot
robot.getPosition(vpRobot::ARTICULAR_FRAME, q1);
// Compute the pose of the wrist in the reference frame using the
// direct geometric model
robot.get_fMw(q1, fMw);
// Compute the inverse geometric model
int nbsol; // number of solutions (0, 1 to 8) of the inverse geometric model
// get the nearest solution to the current joint position
nbsol = robot.getInverseKinematicsWrist(fMw, q1);
if (nbsol == 0)
std::cout << "No solution of the inverse geometric model " << std::endl;
else if (nbsol >= 1)
std::cout << "Nearest solution: " << q1 << std::endl;
See also
getForwardKinematics(), getInverseKinematics()

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().

vpColVector vpViper::getJointMax ( ) const
inherited

Get maximal joint values.

Returns
A 6-dimension vector that contains the maximal joint values for the 6 dof. All the values are expressed in radians.
Examples:
servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, and servoViper850Point2DArtVelocity-jointAvoidance-large.cpp.

Definition at line 1208 of file vpViper.cpp.

References vpViper::joint_max.

vpColVector vpViper::getJointMin ( ) const
inherited

Get minimal joint values.

Returns
A 6-dimension vector that contains the minimal joint values for the 6 dof. All the values are expressed in radians.
Examples:
servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, and servoViper850Point2DArtVelocity-jointAvoidance-large.cpp.

Definition at line 1199 of file vpViper.cpp.

References vpViper::joint_min.

vpToolType vpViper850::getToolType ( ) const
inline

Get the current tool type.

Definition at line 161 of file vpViper850.h.

Referenced by getCameraParameters(), and vpSimulatorViper850::getCameraParameters().

void vpViper850::init ( void  )

Initialize the robot with the default tool vpViper850::defaultTool.

Examples:
testViper850.cpp.

Definition at line 136 of file vpViper850.cpp.

References defaultTool.

Referenced by init(), vpRobotViper850::init(), and vpViper850().

void vpViper850::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.

Parameters
camera_extrinsic_parameters: Filename containing the camera extrinsic parameters.

Definition at line 151 of file vpViper850.cpp.

References parseConfigFile().

Set the constant parameters related to the robot kinematics and to the end-effector to camera transformation ( $^e{\bf M}c$) 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.

Warning
If the macro VISP_HAVE_VIPER850_DATA is defined in vpConfig.h this function reads the camera extrinsic parameters from the file corresponding to the specified camera type and projection type. Otherwise corresponding default parameters are loaded.
Parameters
tool: Camera in use.
proj_model: Projection model of the camera.
See also
init(vpViper850::vpToolType, const std::string&), init(vpViper850::vpToolType, const vpHomogeneousMatrix&)

Definition at line 180 of file vpViper850.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 vpViper850::init ( vpViper850::vpToolType  tool,
const std::string &  filename 
)

Set the type of tool attached to the robot and transformation between the end-effector and the tool ( $^e{\bf M}c$). This last parameter is loaded from a file.

Parameters
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:

# Start with any number of consecutive lines
# beginning with the symbol '#'
#
# The 3 following lines contain the name of the camera,
# the rotation parameters of the geometric transformation
# using the Euler angles in degrees with convention XYZ and
# the translation parameters expressed in meters
CAMERA CameraName
eMc_ROT_XYZ 10.0 -90.0 20.0
eMc_TRANS_XYZ 0.05 0.01 0.06
See also
init(vpViper850::vpToolType, vpCameraParameters::vpCameraParametersProjType), init(vpViper850::vpToolType, const vpHomogeneousMatrix&)

Definition at line 362 of file vpViper850.cpp.

References parseConfigFile(), and setToolType().

void vpViper850::init ( vpViper850::vpToolType  tool,
const vpHomogeneousMatrix eMc_ 
)

Set the type of tool attached to the robot and the transformation between the end-effector and the tool ( $^e{\bf M}c$).

Parameters
tool: Type of tool in use.
eMc_: Homogeneous matrix representation of the transformation between the end-effector frame and the tool frame.
See also
init(vpViper850::vpToolType, vpCameraParameters::vpCameraParametersProjType), init(vpViper850::vpToolType, const std::string&)

Definition at line 383 of file vpViper850.cpp.

References vpViper::set_eMc(), and setToolType().

void vpViper850::parseConfigFile ( const std::string &  filename)

This function gets the robot constant parameters from a file.

Parameters
filename: File name containing the robot constant parameters, like the hand-to-eye transformation.

Definition at line 397 of file vpViper850.cpp.

References vpViper::erc, vpViper::etc, vpRobotException::readingParametersError, and vpViper::set_eMc().

Referenced by init().

void vpViper::set_eMc ( const vpHomogeneousMatrix eMc_)
virtualinherited

Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).

Parameters
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(), vpViper650::init(), init(), vpViper650::parseConfigFile(), parseConfigFile(), vpRobotViper650::set_eMc(), and vpRobotViper850::set_eMc().

void vpViper::set_eMc ( const vpTranslationVector etc_,
const vpRxyzVector erc_ 
)
virtualinherited

Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera frame).

Parameters
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.

void vpViper850::setToolType ( vpViper850::vpToolType  tool)
inlineprotected

Set the current tool type.

Definition at line 170 of file vpViper850.h.

Referenced by init(), and vpSimulatorViper850::init().

Member Data Documentation

double vpViper::c56
protectedinherited

Mechanical coupling between joint 5 and joint 6.

Definition at line 169 of file vpViper.h.

Referenced by vpViper::getCoupl56(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850().

const std::string vpViper850::CONST_CAMERA_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/const_camera_Viper850.xml")

Definition at line 117 of file vpViper850.h.

Referenced by getCameraParameters().

const std::string vpViper850::CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Viper850.cnf")

Definition at line 116 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Viper850.cnf")

Definition at line 115 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf")

Definition at line 110 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) +
std::string("/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf")

Files where constant tranformation between end-effector and camera frame are stored.

Definition at line 109 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf")

Definition at line 112 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) +
std::string("/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf")

Definition at line 111 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) +
std::string("/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf")

Definition at line 114 of file vpViper850.h.

Referenced by init().

const std::string vpViper850::CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_VIPER850_DATA_PATH) + std::string("/include/"
"const_eMc_schunk_gripper_without_distortion_Viper850."
"cnf")

Definition at line 113 of file vpViper850.h.

Referenced by init().

const char *const vpViper850::CONST_GENERIC_CAMERA_NAME = "Generic-camera"
static

Definition at line 125 of file vpViper850.h.

Referenced by getCameraParameters().

const char *const vpViper850::CONST_MARLIN_F033C_CAMERA_NAME = "Marlin-F033C-12mm"
static

Name of the camera attached to the end-effector.

Definition at line 122 of file vpViper850.h.

Referenced by getCameraParameters(), and vpSimulatorViper850::getCameraParameters().

const char *const vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME = "PTGrey-Flea2-6mm"
static

Definition at line 123 of file vpViper850.h.

Referenced by getCameraParameters(), and vpSimulatorViper850::getCameraParameters().

const char *const vpViper850::CONST_SCHUNK_GRIPPER_CAMERA_NAME = "Schunk-Gripper-PTGrey-Flea2-6mm"
static

Definition at line 124 of file vpViper850.h.

Referenced by getCameraParameters().

double vpViper::d6
protectedinherited
double vpViper::d7
protectedinherited

for force/torque location

Definition at line 168 of file vpViper.h.

Referenced by vpViper::get_eMs(), and vpViper::vpViper().

const vpViper850::vpToolType vpViper850::defaultTool = vpViper850::TOOL_PTGREY_FLEA2_CAMERA
static

Default tool attached to the robot end effector.

Examples:
testRobotViper850Pose.cpp.

Definition at line 137 of file vpViper850.h.

Referenced by init(), vpSimulatorViper850::init(), and vpRobotViper850::init().

vpCameraParameters::vpCameraParametersProjType vpViper850::projModel
protected

Definition at line 177 of file vpViper850.h.

Referenced by getCameraParameters(), init(), and vpSimulatorViper850::init().

vpToolType vpViper850::tool_current
protected

Current tool in use.

Definition at line 170 of file vpViper850.h.