ViSP  2.10.0

#include <vpRobotViper850.h>

+ Inheritance diagram for vpRobotViper850:

Public Types

enum  vpControlModeType { AUTO, MANUAL, ESTOP }
 
enum  vpToolType { TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, TOOL_GENERIC_CAMERA }
 
enum  vpRobotStateType { STATE_STOP, STATE_VELOCITY_CONTROL, STATE_POSITION_CONTROL, STATE_ACCELERATION_CONTROL }
 
enum  vpControlFrameType { REFERENCE_FRAME, ARTICULAR_FRAME, CAMERA_FRAME, MIXT_FRAME }
 

Public Member Functions

 vpRobotViper850 (bool verbose=true)
 
virtual ~vpRobotViper850 (void)
 
void biasForceTorqueSensor () const
 
void closeGripper () const
 
void disableJoint6Limits () const
 
void enableJoint6Limits () const
 
void getDisplacement (vpRobot::vpControlFrameType frame, vpColVector &displacement)
 
vpControlModeType getControlMode () const
 
void getForceTorque (vpColVector &H) const
 
double getMaxRotationVelocityJoint6 () const
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
 
double getPositioningVelocity (void) const
 
bool getPowerState () const
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame, double &timestamp)
 
double getTime () const
 
void get_cMe (vpHomogeneousMatrix &cMe) const
 
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
void get_eJe (vpMatrix &eJe)
 
void get_fJe (vpMatrix &fJe)
 
void init (void)
 
void init (vpViper850::vpToolType tool, vpCameraParameters::vpCameraParametersProjType projModel=vpCameraParameters::perspectiveProjWithoutDistortion)
 
void move (const char *filename)
 
void openGripper ()
 
void powerOn ()
 
void powerOff ()
 
void setMaxRotationVelocity (double w_max)
 
void setMaxRotationVelocityJoint6 (double w6_max)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position)
 
void setPosition (const vpRobot::vpControlFrameType frame, const double pos1, const double pos2, const double pos3, const double pos4, const double pos5, const double pos6)
 
void setPosition (const char *filename)
 
void setPositioningVelocity (const double velocity)
 
vpRobot::vpRobotStateType setRobotState (vpRobot::vpRobotStateType newState)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
 
void stopMotion ()
 
void init (const char *camera_extrinsic_parameters)
 
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 char *filename)
 
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_fMe (const vpColVector &q, vpHomogeneousMatrix &fMe) 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
 
vpColVector getJointMin () const
 
vpColVector getJointMax () const
 
double getCoupl56 () const
 
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxTranslationVelocity (const double maxVt)
 
void setVerbose (bool verbose)
 

Static Public Member Functions

static bool readPosFile (const char *filename, vpColVector &q)
 
static bool savePosFile (const char *filename, const vpColVector &q)
 
static vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
 

Static Public Attributes

static const double defaultPositioningVelocity = 15.0
 
static const char *const CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf"
 
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf"
 
static const char *const CONST_CAMERA_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_camera_Viper850.xml"
 
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

void setToolType (vpViper850::vpToolType tool)
 
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void) const
 

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 c56
 
vpColVector joint_max
 
vpColVector joint_min
 
double maxTranslationVelocity
 
double maxRotationVelocity
 
int nDof
 
vpMatrix eJe
 
int eJeAvailable
 
vpMatrix fJe
 
int fJeAvailable
 
int areJointLimitsAvailable
 
double * qmin
 
double * qmax
 
bool verbose_
 

Static Protected Attributes

static const double maxTranslationVelocityDefault = 0.2
 
static const double maxRotationVelocityDefault = 0.7
 

Detailed Description

Control of Irisa's Viper S850 robot named Viper850.

Implementation of the vpRobot class in order to control Irisa's Viper850 robot. This robot is an ADEPT six degrees of freedom arm. A firewire camera is mounted on the end-effector to allow eye-in-hand visual servoing. The control of this camera is achieved by the vp1394TwoGrabber class.

This class allows to control the Viper850 arm robot in position and velocity:

All the translations are expressed in meters for positions and m/s for the velocities. Rotations are expressed in radians for the positions, and rad/s for the rotation velocities.

The direct and inverse kinematics models are implemented in the vpViper850 class.

Warning
A Ctrl-C, a segmentation fault or other system errors are catched by this class to stop the robot.

To communicate with the robot, you may first create an instance of this class by calling the default constructor:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
#endif
}

This initialize the robot kinematics with the $^e{\bf M}_c$ extrinsic camera parameters obtained with a projection model without distortion. To set the robot kinematics with the $^e{\bf M}_c$ transformation obtained with a camera perspective model including distortion you need to initialize the robot with:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distortion parameter
#endif
}

You can get the intrinsic camera parameters of an image acquired by the camera attached to the robot, with:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpCameraParameters.h>
int main()
{
#if defined(VISP_HAVE_VIPER850) && defined(VISP_HAVE_DC1394_2)
g.acquire(I);
// ...
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distortion.
#endif
}

To control the robot in position, you may set the controller to position control and than send the position to reach in a specific frame like here in the joint space:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set a joint position
q[0] = vpMath::rad(10); // Joint 1 position, in rad
q[1] = 0.2; // Joint 2 position, in rad
q[2] = 0.3; // Joint 3 position, in rad
q[3] = M_PI/8; // Joint 4 position, in rad
q[4] = M_PI/4; // Joint 5 position, in rad
q[5] = M_PI; // Joint 6 position, in rad
// Initialize the controller to position control
// Moves the robot in the joint space
#endif
}

The robot moves to the specified position with the default positioning velocity vpRobotViper850::defaultPositioningVelocity. The setPositioningVelocity() method allows to change the maximal velocity used to reach the desired position.

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set q[i] with i in [0:5]
// Initialize the controller to position control
// Set the max velocity to 40%
// Moves the robot in the joint space
#endif
}

To control the robot in velocity, you may set the controller to velocity control and than send the velocities. To end the velocity control and stop the robot you have to set the controller to the stop state. Here is an example of a velocity control in the joint space:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector qvel(6);
// Set a joint velocity
qvel[0] = 0.1; // Joint 1 velocity in rad/s
qvel[1] = vpMath::rad(15); // Joint 2 velocity in rad/s
qvel[2] = 0; // Joint 3 velocity in rad/s
qvel[3] = M_PI/8; // Joint 4 velocity in rad/s
qvel[4] = 0; // Joint 5 velocity in rad/s
qvel[5] = 0; // Joint 6 velocity in rad/s
// Initialize the controller to position control
for ( ; ; ) {
// Apply a velocity in the joint space
// Compute new velocities qvel...
}
// Stop the robot
#endif
}

It is also possible to measure the robot current position with getPosition() method and the robot current velocities with the getVelocity() method.

For convenience, there is also the ability to read/write joint positions from a position file with readPosFile() and savePosFile() methods.

Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, testRobotViper850.cpp, and testRobotViper850Pose.cpp.

Definition at line 276 of file vpRobotViper850.h.

Member Enumeration Documentation

Robot control frames.

Enumerator
REFERENCE_FRAME 

Corresponds to a fixed reference frame attached to the robot structure.

ARTICULAR_FRAME 

Corresponds to the joint space.

CAMERA_FRAME 

Corresponds to a frame attached to the camera mounted on the robot end-effector.

MIXT_FRAME 

Corresponds to a "virtual" frame where translations are expressed in the reference frame, and rotations in the camera frame.

Definition at line 78 of file vpRobot.h.

Control mode.

Enumerator
AUTO 

Automatic control mode (default).

MANUAL 

Manual control mode activated when the dead man switch is in use.

ESTOP 

Emergency stop activated.

Definition at line 285 of file vpRobotViper850.h.

enum vpRobot::vpRobotStateType
inherited

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

Definition at line 66 of file vpRobot.h.

enum vpViper850::vpToolType
inherited

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.

Definition at line 91 of file vpViper850.h.

Constructor & Destructor Documentation

vpRobotViper850::vpRobotViper850 ( bool  verbose = true)

The only available constructor.

This contructor calls init() to initialise the connection with the MotionBox or low level controller, send the default $^e{\bf M}_c$ homogeneous matrix and power on the robot.

It also set the robot state to vpRobot::STATE_STOP.

To set the extrinsic camera parameters related to the $^e{\bf M}_c$ matrix obtained with a camera perspective projection model including the distorsion, use the code below:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpCameraParameters.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distorsion parameter

Now, you can get the intrinsic camera parameters associated to an image acquired by the camera attached to the robot, with:

// Get an image from the camera attached to the robot
#ifdef VISP_HAVE_DC1394_2
g.acquire(I);
#endif
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distorsion.
#endif
}
See also
vpCameraParameters, init(vpViper850::vpViper850CameraRobotType, vpCameraParameters::vpCameraParametersProjType)

Definition at line 177 of file vpRobotViper850.cpp.

References defaultPositioningVelocity, init(), vpRobot::maxRotationVelocity, setRobotState(), vpRobot::setVerbose(), vpRobot::STATE_STOP, and vpRobot::verbose_.

vpRobotViper850::~vpRobotViper850 ( void  )
virtual

Destructor.

Free allocated resources.

Definition at line 456 of file vpRobotViper850.cpp.

References setRobotState(), and vpRobot::STATE_STOP.

Member Function Documentation

void vpRobotViper850::biasForceTorqueSensor ( ) const

Bias the force/torque sensor.

Warning
This function waits 500 ms after the bias request to be sure the next measures take into account the bias.
Exceptions
vpRobotException::lowLevelError: If the force/torque sensor bias cannot be done on the low level controller.
See also
getForceTorque()

Definition at line 2193 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, vpERROR_TRACE, and vpTime::wait().

void vpRobotViper850::closeGripper ( ) const

Close the electric two fingers Schunk gripper.

See also
openGripper()

Definition at line 2292 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

void vpRobotViper850::disableJoint6Limits ( ) const
Warning
Each call to this function should be done carefully.

Disable the joint limits on axis number 6. When joint 6 is outside the limits, a call to this function allows to bring the robot to a position inside the limits. Don't forget then to call enableJoint6Limits() to reduce the working space for joint 6.

See also
enableJoint6Limits()

Definition at line 2332 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

void vpRobotViper850::enableJoint6Limits ( ) const

Enable the joint limits on axis number 6. This is the default.

See also
disbleJoint6Limits()

Definition at line 2310 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

void vpRobotViper850::get_cMe ( vpHomogeneousMatrix cMe) const

Get the geometric transformation $^c{\bf M}_e$ 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.

Definition at line 738 of file vpRobotViper850.cpp.

References vpViper::get_cMe().

void vpRobotViper850::get_cVe ( vpVelocityTwistMatrix cVe) const

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.

Parameters
cVe: Twist transformation.
Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, and servoViper850Point2DArtVelocity.cpp.

Definition at line 718 of file vpRobotViper850.cpp.

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

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 985 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(), get_eJe(), and vpSimulatorViper850::getVelocity().

void vpRobotViper850::get_eJe ( vpMatrix eJe)
virtual

Get the robot jacobian expressed in the end-effector frame.

To compute $^e{\bf J}_e$, we communicate with the low level controller to get the joint position of the robot.

Parameters
eJe: Robot jacobian $^e{\bf J}_e$ expressed in the end-effector frame.

Implements vpRobot.

Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, and servoViper850Point2DArtVelocity.cpp.

Definition at line 756 of file vpRobotViper850.cpp.

References vpViper::get_eJe(), vpViper::njoint, vpMath::rad(), and vpERROR_TRACE.

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

Definition at line 914 of file vpViper.cpp.

References vpViper::eMc.

Referenced by vpViper::getInverseKinematics().

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 1177 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(), get_fJe(), and vpSimulatorViper850::getVelocity().

void vpRobotViper850::get_fJe ( vpMatrix fJe)
virtual

Get the robot jacobian expressed in the robot reference frame also called fix frame.

To compute $^f{\bf J}_e$, we communicate with the low level controller to get the joint position of the robot.

Parameters
fJe: Robot jacobian $^f{\bf J}_e$ expressed in the reference frame.

Implements vpRobot.

Definition at line 793 of file vpRobotViper850.cpp.

References vpViper::get_fJe(), vpViper::njoint, and vpERROR_TRACE.

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 1071 of file vpViper.cpp.

References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d4, and vpMatrix::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:
testRobotViper850Pose.cpp.

Definition at line 615 of file vpViper.cpp.

Referenced by vpSimulatorViper850::compute_fMi(), vpViper::getForwardKinematics(), vpSimulatorViper850::getPosition(), getVelocity(), vpRobotViper650::getVelocity(), vpSimulatorViper850::setPosition(), vpRobotViper650::setPosition(), and 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 645 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 <visp/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:
testRobotViper850.cpp, and testViper850.cpp.

Definition at line 732 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} \]

Definition at line 828 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 893 of file vpViper.cpp.

References vpViper::d6, and vpHomogeneousMatrix::setIdentity().

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
inherited

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/visp/vpConfig.h file.
Thid method needs also an access to the file located on Inria's NAS server and containing the camera parameters in XML format. This access is available if VISP_HAVE_ACCESS_TO_NAS macro is defined in include/visp/vpConfig.h file.
  • If VISP_HAVE_ACCESS_TO_NAS and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from /udd/fspindle/robot/Viper850/current/include/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 <visp/vpConfig.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpViper850.h>
#include <visp/vpRobotViper850.h>
int main()
{
#ifdef VISP_HAVE_DC1394_2
// 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_ACCESS_TO_NAS 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.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, testRobotViper850.cpp, testRobotViper850Pose.cpp, and testViper850.cpp.

Definition at line 580 of file vpViper850.cpp.

References vpViper850::CONST_CAMERA_FILENAME, vpViper850::CONST_GENERIC_CAMERA_NAME, vpViper850::CONST_MARLIN_F033C_CAMERA_NAME, vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME, vpViper850::CONST_SCHUNK_GRIPPER_CAMERA_NAME, vpViper850::getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, vpViper850::projModel, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, vpViper850::TOOL_GENERIC_CAMERA, vpViper850::TOOL_MARLIN_F033C_CAMERA, vpViper850::TOOL_PTGREY_FLEA2_CAMERA, vpViper850::TOOL_SCHUNK_GRIPPER_CAMERA, vpERROR_TRACE, and vpTRACE.

Referenced by vpViper850::getCameraParameters().

void vpViper850::getCameraParameters ( vpCameraParameters cam,
const vpImage< unsigned char > &  I 
) const
inherited

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/visp/vpConfig.h file.
Thid method needs also an access to the file located on Inria's NAS server and containing the camera parameters in XML format. This access is available if VISP_HAVE_ACCESS_TO_NAS macro is defined in include/visp/vpConfig.h file.
  • If VISP_HAVE_ACCESS_TO_NAS and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from /udd/fspindle/robot/Viper850/current/include/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 <visp/vpConfig.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpViper850.h>
#include <visp/vpRobotViper850.h>
int main()
{
#ifdef VISP_HAVE_DC1394_2
// 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 803 of file vpViper850.cpp.

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

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

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/visp/vpConfig.h file.
Thid method needs also an access to the file located on Inria's NAS server and containing the camera parameters in XML format. This access is available if VISP_HAVE_ACCESS_TO_NAS macro is defined in include/visp/vpConfig.h file.
  • If VISP_HAVE_ACCESS_TO_NAS and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from /udd/fspindle/robot/Viper850/current/include/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 <visp/vpConfig.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpViper850.h>
#include <visp/vpRobotViper850.h>
int main()
{
vpImage<vpRGBa> I(480, 640);
#ifdef VISP_HAVE_DC1394_2
// 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 873 of file vpViper850.cpp.

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

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

Get the current camera model projection type.

Definition at line 114 of file vpViper850.h.

vpControlModeType vpRobotViper850::getControlMode ( ) const
inline
Returns
The control mode indicating if the robot is in automatic, manual (usage of the dead man switch) or emergnecy stop mode.

Definition at line 352 of file vpRobotViper850.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 1248 of file vpViper.cpp.

References vpViper::c56.

void vpRobotViper850::getDisplacement ( vpRobot::vpControlFrameType  frame,
vpColVector displacement 
)
virtual

Get the robot displacement since the last call of this method.

Warning
This functionnality is not implemented for the moment in the cartesian space. It is only available in the joint space (vpRobot::ARTICULAR_FRAME).
Parameters
frame: The frame in which the measured displacement is expressed.
displacement: The measured displacement since the last call of this method. The dimension of displacement is always
  1. Translations are expressed in meters, rotations in radians.

In camera or reference frame, rotations are expressed with the Euler Rxyz representation.

See also
getArticularDisplacement(), getCameraDisplacement()

Implements vpRobot.

Definition at line 2120 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpViper::njoint, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.

void vpRobotViper850::getForceTorque ( vpColVector H) const

Get the rough force/torque sensor measures.

Parameters
H[Fx, Fy, Fz, Tx, Ty, Tz] Forces/torques measured by the sensor.

The code below shows how to get the force/torque measures after a sensor bias.

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpTime.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector H; // force/torque measures [Fx, Fy, Fz, Tx, Ty, Tz]
// Bias the force/torque sensor
for (unsigned int i=0; i< 10; i++) {
robot.getForceTorque(H) ;
std::cout << "Measured force/torque: " << H.t() << std::endl;
}
#endif
}
Exceptions
vpRobotException::lowLevelError: If the force/torque measures cannot be get from the low level controller.
See also
biasForceTorqueSensor()

Definition at line 2250 of file vpRobotViper850.cpp.

References vpMatrix::data, vpRobotException::lowLevelError, vpColVector::resize(), and vpERROR_TRACE.

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 129 of file vpViper.cpp.

References vpViper::get_fMc().

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

Definition at line 577 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 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 232 of file vpViper.cpp.

References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, vpMatrix::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, and servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp.

Definition at line 1232 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, and servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp.

Definition at line 1219 of file vpViper.cpp.

References vpViper::joint_min.

double vpRobotViper850::getMaxRotationVelocityJoint6 ( ) const

Get the maximal rotation velocity on joint 6 that is used only during velocity joint control.

Returns
Maximum rotation velocity on joint 6 expressed in rad/s.

Definition at line 2394 of file vpRobotViper850.cpp.

Referenced by setVelocity().

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited
vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)
inherited

Return the current robot position in the specified frame.

Definition at line 222 of file vpRobot.cpp.

void vpRobotViper850::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector position,
double &  timestamp 
)

Get the current position of the robot.

Parameters
frame: Control frame type in which to get the position, either :
  • in the camera cartesien frame,
  • joint (articular) coordinates of each axes
  • in a reference or fixed cartesien frame attached to the robot base
  • in a mixt cartesien frame (translation in reference frame, and rotation in camera frame)
position: Measured position of the robot:
  • in camera cartesien frame, a 6 dimension vector, set to 0.
  • in articular, a 6 dimension vector corresponding to the joint position of each dof in radians.
  • in reference frame, a 6 dimension vector, the first 3 values correspond to the translation tx, ty, tz in meters (like a vpTranslationVector), and the last 3 values to the rx, ry, rz rotation (like a vpRxyzVector). The code below show how to convert this position into a vpHomogenousMatrix:
timestamp: Time in second since last robot power on.
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpTranslationVector.h>
#include <visp/vpRxyzVector.h>
#include <visp/vpRotationMatrix.h>
#include <visp/vpHomogeneousMatrix.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector position;
double timestamp;
robot.getPosition(vpRobot::REFERENCE_FRAME, position, timestamp);
vpTranslationVector ftc; // reference frame to camera frame translations
vpRxyzVector frc; // reference frame to camera frame rotations
// Update the transformation between reference frame and camera frame
for (unsigned int i=0; i < 3; i++) {
ftc[i] = position[i]; // tx, ty, tz
frc[i] = position[i+3]; // ry, ry, rz
}
// Create a rotation matrix from the Rxyz rotation angles
vpRotationMatrix fRc(frc); // reference frame to camera frame rotation matrix
// Create the camera to fix frame transformation in terms of a
// homogenous matrix
vpHomogeneousMatrix fMc(ftc, fRc);
#endif
}
Exceptions
vpRobotException::lowLevelError: If the position cannot be get from the low level controller.
See also
setPosition(const vpRobot::vpControlFrameType frame, const vpColVector & r)

Definition at line 1287 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpMatrix::data, vpColVector::deg2rad(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpMath::rad(), vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.

void vpRobotViper850::getPosition ( const vpRobot::vpControlFrameType  frame,
vpPoseVector position 
)

Get the current position of the robot.

Similar as getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &, double &).

The difference is here that the timestamp is not used.

Definition at line 1415 of file vpRobotViper850.cpp.

References getPosition().

void vpRobotViper850::getPosition ( const vpRobot::vpControlFrameType  frame,
vpPoseVector position,
double &  timestamp 
)

Get the current position of the robot.

Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &, double &).

The difference is here that the position is returned using a ThetaU representation.

Definition at line 1385 of file vpRobotViper850.cpp.

References getPosition().

double vpRobotViper850::getPositioningVelocity ( void  ) const

Get the maximal velocity percentage used for a position control.

See also
setPositioningVelocity()

Definition at line 867 of file vpRobotViper850.cpp.

bool vpRobotViper850::getPowerState ( void  ) const

Get the robot power state indication if power is on or off.

Returns
true if power is on. false if power is off.
Exceptions
vpRobotException::lowLevelError: If the low level controller returns an error.
See also
powerOn(), powerOff()

Definition at line 685 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited
double vpRobotViper850::getTime ( ) const

Returns the robot controller current time (in second) since last robot power on.

Definition at line 1352 of file vpRobotViper850.cpp.

vpToolType vpViper850::getToolType ( ) const
inlineinherited

Get the current tool type.

Definition at line 126 of file vpViper850.h.

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

void vpRobotViper850::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector velocity,
double &  timestamp 
)

Get the robot velocities.

Parameters
frame: Frame in wich velocities are mesured.
velocity: Measured velocities. Translations are expressed in m/s and rotations in rad/s.
timestamp: Time in second since last robot power on.
Warning
In camera frame, reference frame and mixt frame, the representation of the rotation is ThetaU. In that cases, $velocity = [\dot x, \dot y, \dot z, \dot {\theta U}_x, \dot {\theta U}_y, \dot {\theta U}_z]$.
The first time this method is called, velocity is set to 0. The first call is used to intialise the velocity computation for the next call.
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set requested joint velocities
vpColVector q_dot(6);
q_dot[0] = 0.1; // Joint 1 velocity in rad/s
q_dot[1] = 0.2; // Joint 2 velocity in rad/s
q_dot[2] = 0.3; // Joint 3 velocity in rad/s
q_dot[3] = M_PI/8; // Joint 4 velocity in rad/s
q_dot[4] = M_PI/4; // Joint 5 velocity in rad/s
q_dot[5] = M_PI/16;// Joint 6 velocity in rad/s
// Moves the joint in velocity
// Initialisation of the velocity measurement
vpColVector q_dot_mes; // Measured velocities
robot.getVelocity(vpRobot::ARTICULAR_FRAME, q_dot_mes); // q_dot_mes =0
// q_dot_mes is resized to 6, the number of joint
while (1) {
vpTime::wait(40); // wait 40 ms
// here q_dot_mes is equal to [0.1, 0.2, 0.3, M_PI/8, M_PI/4, M_PI/16]
}
#endif
}

Definition at line 1682 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpThetaUVector::buildFrom(), vpRobot::CAMERA_FRAME, vpMatrix::data, vpColVector::deg2rad(), vpHomogeneousMatrix::extract(), vpViper::get_fMc(), vpExponentialMap::inverse(), vpHomogeneousMatrix::inverse(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.

vpColVector vpRobotViper850::getVelocity ( const vpRobot::vpControlFrameType  frame)

Get robot velocities.

The behavior is the same than getVelocity(const vpRobot::vpControlFrameType, double &) except that the timestamp is not returned.

Definition at line 1864 of file vpRobotViper850.cpp.

References getVelocity().

vpColVector vpRobotViper850::getVelocity ( const vpRobot::vpControlFrameType  frame,
double &  timestamp 
)

Get the robot velocities.

Parameters
frame: Frame in wich velocities are mesured.
timestamp: Time in second since last robot power on.
Returns
Measured velocities. Translations are expressed in m/s and rotations in rad/s.
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set requested joint velocities
vpColVector q_dot(6);
q_dot[0] = 0.1; // Joint 1 velocity in rad/s
q_dot[1] = 0.2; // Joint 2 velocity in rad/s
q_dot[2] = 0.3; // Joint 3 velocity in rad/s
q_dot[3] = M_PI/8; // Joint 4 velocity in rad/s
q_dot[4] = M_PI/4; // Joint 5 velocity in rad/s
q_dot[5] = M_PI/16;// Joint 6 velocity in rad/s
// Moves the joint in velocity
// Initialisation of the velocity measurement
vpColVector q_dot_mes; // Measured velocities
robot.getVelocity(vpRobot::ARTICULAR_FRAME, q_dot_mes); // q_dot_mes =0
// q_dot_mes is resized to 6, the number of joint
double timestamp;
while (1) {
q_dot_mes = robot.getVelocity(vpRobot::ARTICULAR_FRAME, timestamp);
vpTime::wait(40); // wait 40 ms
// here q_dot_mes is equal to [0.1, 0.2, 0.3, M_PI/8, M_PI/4, M_PI/16]
}
#endif
}

Definition at line 1848 of file vpRobotViper850.cpp.

References getVelocity().

void vpViper850::init ( const char *  camera_extrinsic_parameters)
inherited

Read files containing the constant parameters related to the robot tools in order to set the end-effector to camera transformation.

Warning
This function is only available if the macro VISP_HAVE_ACCESS_TO_NAS is defined in vpConfig.h.
Parameters
camera_extrinsic_parameters: Filename containing the camera extrinsic parameters.

Definition at line 196 of file vpViper850.cpp.

References vpViper850::parseConfigFile().

void vpRobotViper850::init ( void  )
virtual

Initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.

Warning
This method sets the camera extrinsic parameters (matrix eMc) to the one obtained by calibration with a camera projection model without distorsion by calling init(vpViper850::defaultCameraRobot). If you want to set the extrinsic camera parameters to those obtained with a camera perspective model including the distorsion you have to call the init(vpViper850::vpViper850CameraRobotType, vpCameraParameters::vpCameraParametersProjType) method.
See also
vpCameraParameters, init(vpViper850::vpViper850CameraRobotType, vpCameraParameters::vpCameraParametersProjType)

Implements vpRobot.

Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, testRobotViper850.cpp, and testRobotViper850Pose.cpp.

Definition at line 253 of file vpRobotViper850.cpp.

References AUTO, vpRobotException::constructionError, vpMatrix::data, vpViper850::defaultTool, vpColVector::deg2rad(), ESTOP, vpViper::joint_max, vpViper::joint_min, MANUAL, vpColVector::resize(), and vpRobot::verbose_.

Referenced by vpRobotViper850().

Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.

The eMc parameters depend on the camera and the projection model in use.

Parameters
tool: Tool to use.
projModel: Projection model associated to the camera.

To set the extrinsic camera parameters related to the $^e{\bf M}_c$ matrix obtained with a camera perspective projection model including the distorsion, use the code below:

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpCameraParameters.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distorsion parameter

Now, you can get the intrinsic camera parameters associated to an image acquired by the camera attached to the robot, with:

// Get an image from the camera attached to the robot
#ifdef VISP_HAVE_DC1394_2
g.acquire(I);
#endif
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distorsion.
#endif
}
See also
vpCameraParameters, init()

Definition at line 411 of file vpRobotViper850.cpp.

References vpMatrix::data, vpColVector::deg2rad(), vpViper::erc, vpViper::etc, vpViper850::init(), vpViper::joint_max, vpViper::joint_min, and vpViper850::setToolType().

void vpRobotViper850::move ( const char *  filename)

Moves the robot to the joint position specified in the filename. The positioning velocity is set to 10% of the robot maximal velocity.

Parameters
filenameFile containing a joint position.
See also
readPosFile

Definition at line 2049 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.

void vpRobotViper850::openGripper ( )

Open the electric two fingers Schunk gripper.

See also
closeGripper()

Definition at line 2272 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

void vpViper850::parseConfigFile ( const char *  filename)
inherited

This function gets the robot constant parameters from a file.

Warning
This function is only available if the macro VISP_HAVE_ACCESS_TO_NAS is defined in vpConfig.h.
Parameters
filename: File name containing the robot constant parameters, like the hand-to-eye transformation.

Definition at line 420 of file vpViper850.cpp.

References vpHomogeneousMatrix::buildFrom(), vpViper::eMc, vpViper::erc, vpViper::etc, vpRobotException::readingParametersError, and vpERROR_TRACE.

Referenced by vpViper850::init().

void vpRobotViper850::powerOff ( void  )

Power off the robot.

Exceptions
vpRobotException::lowLevelError: If the low level controller returns an error during robot stopping.
See also
powerOn(), getPowerState()

Definition at line 648 of file vpRobotViper850.cpp.

References vpRobotException::lowLevelError, and vpERROR_TRACE.

void vpRobotViper850::powerOn ( void  )

Power on the robot.

Exceptions
vpRobotException::lowLevelError: If the low level controller returns an error during robot power on.
See also
powerOff(), getPowerState()

Definition at line 573 of file vpRobotViper850.cpp.

References AUTO, ESTOP, vpRobotException::lowLevelError, MANUAL, and vpERROR_TRACE.

Referenced by setRobotState().

bool vpRobotViper850::readPosFile ( const char *  filename,
vpColVector q 
)
static

Read joint positions in a specific Viper850 position file.

This position file has to start with a header. The six joint positions are given after the "R:" keyword. The first 3 values correspond to the joint translations X,Y,Z expressed in meters. The 3 last values correspond to the joint rotations A,B,C expressed in degres to be more representative for the user. Theses values are then converted in radians in q. The character "#" starting a line indicates a comment.

A typical content of such a file is given below:

#Viper - Position - Version 1.0
# file: "myposition.pos "
#
# R: A B C D E F
# Joint position in degrees
#
R: 0.1 0.3 -0.25 -80.5 80 0
Parameters
filename: Name of the position file to read.
q: The six joint positions. Values are expressed in radians.
Returns
true if the positions were successfully readen in the file. false, if an error occurs.

The code below shows how to read a position from a file and move the robot to this position.

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Enable the position control of the robot
// Get the current robot joint positions
vpColVector q; // Current joint position
// Save this position in a file named "current.pos"
robot.savePosFile("current.pos", q);
// Get the position from a file and move to the registered position
robot.readPosFile("current.pos", q); // Set the joint position from the file
robot.setPositioningVelocity(5); // Positioning velocity set to 5%
robot.setPosition(vpRobot::ARTICULAR_FRAME, q); // Move to the joint position
#endif
}
See also
savePosFile()

Definition at line 1939 of file vpRobotViper850.cpp.

References vpColVector::deg2rad(), vpViper::njoint, and vpColVector::resize().

Referenced by move(), and setPosition().

vpColVector vpRobot::saturateVelocities ( const vpColVector v_in,
const vpColVector v_max,
bool  verbose = false 
)
staticinherited

Saturate velocities.

Parameters
v_in: Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
v_max: Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
verbose: Print a message indicating which axis causes the saturation.
Returns
Saturated velocities.
Exceptions
vpRobotException::dimensionError: If the input vectors have different dimensions.

The code below shows how to use this static method in order to saturate a velocity skew vector.

#include <iostream>
#include <visp/vpRobot.h>
int main()
{
// Set a velocity skew vector
v[0] = 0.1; // vx in m/s
v[1] = 0.2; // vy
v[2] = 0.3; // vz
v[3] = vpMath::rad(10); // wx in rad/s
v[4] = vpMath::rad(-10); // wy
v[5] = vpMath::rad(20); // wz
// Set the maximal allowed velocities
vpColVector v_max(6);
for (int i=0; i<3; i++)
v_max[i] = 0.3; // in translation (m/s)
for (int i=3; i<6; i++)
v_max[i] = vpMath::rad(10); // in rotation (rad/s)
// Compute the saturated velocity skew vector
vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
std::cout << "v : " << v.t() << std::endl;
std::cout << "v max: " << v_max.t() << std::endl;
std::cout << "v sat: " << v_sat.t() << std::endl;
return 0;
}

Definition at line 167 of file vpRobot.cpp.

References vpException::dimensionError, and vpColVector::size().

Referenced by vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and setVelocity().

bool vpRobotViper850::savePosFile ( const char *  filename,
const vpColVector q 
)
static

Save joint (articular) positions in a specific Viper850 position file.

This position file starts with a header on the first line. After convertion of the rotations in degrees, the joint position q is written on a line starting with the keyword "R: ". See readPosFile() documentation for an example of such a file.

Parameters
filename: Name of the position file to create.
q: The six joint positions to save in the filename. Values are expressed in radians.
Warning
All the six joint rotations written in the file are converted in degrees to be more representative for the user.
Returns
true if the positions were successfully saved in the file. false, if an error occurs.
See also
readPosFile()

Definition at line 2009 of file vpRobotViper850.cpp.

References vpMath::deg().

void vpRobotViper850::setMaxRotationVelocity ( double  w_max)

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

Parameters
w_max: Maximum rotation velocity expressed in rad/s.

Definition at line 2353 of file vpRobotViper850.cpp.

References vpRobot::setMaxRotationVelocity(), and setMaxRotationVelocityJoint6().

void vpRobotViper850::setMaxRotationVelocityJoint6 ( double  w6_max)

Set the maximal rotation velocity on joint 6 that is used only during velocity joint control.

This function affects only the velocities that are sent as joint velocities.

Parameters
w6_max: Maximum rotation velocity expressed in rad/s on joint 6.

Definition at line 2381 of file vpRobotViper850.cpp.

Referenced by setMaxRotationVelocity().

void vpRobot::setMaxTranslationVelocity ( const double  v_max)
inherited

Set the maximal translation velocity that can be sent to the robot during a velocity control.

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples:
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, and simulateFourPoints2DPolarCamVelocity.cpp.

Definition at line 242 of file vpRobot.cpp.

Referenced by vpSimulatorAfma6::setPosition().

void vpRobotViper850::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector position 
)
virtual

Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.

Warning
This method is blocking. It returns only when the position is reached by the robot.
Parameters
position: A six dimension vector corresponding to the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. If the position is out of range, an exception is provided.
frame: Frame in which the position is expressed.
  • In the joint space, positions are the six joint rotations starting from the base to the end-effector.
  • In the camera and the reference frame, positions are respectively X,Y,Z translations and 3 rotations arround the X, Y and Z axis. Rotations are represented by a vpRxyzVector.
  • Mixt frame is not implemented. By mixt frame we mean, translations expressed in the reference frame, and rotations in the camera frame.
Exceptions
vpRobotException::lowLevelError: vpRobot::MIXT_FRAME not implemented.
vpRobotException::positionOutOfRangeError: The requested position is out of range.
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector position(6);
// Set positions in the camera frame
position[0] = 0.1; // x axis, in meter
position[1] = 0.2; // y axis, in meter
position[2] = 0.3; // z axis, in meter
position[3] = M_PI/8; // rotation around x axis, in rad
position[4] = M_PI/4; // rotation around y axis, in rad
position[5] = M_PI; // rotation around z axis, in rad
// Set the max velocity to 20%
// Moves the robot in the camera frame
#endif
}

To catch the exception if the position is out of range, modify the code like:

try {
}
catch (vpRobotException e) {
std::cout << "The position is out of range" << std::endl;
}

Implements vpRobot.

Definition at line 951 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpMatrix::data, vpMath::deg(), vpColVector::deg2rad(), vpViper::get_fMc(), vpViper::getInverseKinematics(), vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpViper::njoint, vpRobotException::positionOutOfRangeError, vpColVector::rad2deg(), vpRobot::REFERENCE_FRAME, setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpERROR_TRACE.

Referenced by move(), and setPosition().

void vpRobotViper850::setPosition ( const vpRobot::vpControlFrameType  frame,
const double  pos1,
const double  pos2,
const double  pos3,
const double  pos4,
const double  pos5,
const double  pos6 
)

Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.

This method owerloads setPosition(const vpRobot::vpControlFrameType, const vpColVector &).

Warning
This method is blocking. It returns only when the position is reached by the robot.
Parameters
pos1,pos2,pos3,pos4,pos5,pos6: The six coordinates of the position to reach. All the positions are expressed in meters for the translations and radians for the rotations.
frame: Frame in which the position is expressed.
  • In the joint space, positions are respectively X (pos1), Y (pos2), Z (pos3), A (pos4), B (pos5), C (pos6), with X,Y,Z the translations, and A,B,C the rotations of the end-effector.
  • In the camera and the reference frame, rotations [pos4, pos5, pos6] are represented by a vpRxyzVector.
  • Mixt frame is not implemented. By mixt frame we mean, translations expressed in the reference frame, and rotations in the camera frame.
Exceptions
vpRobotException::lowLevelError: vpRobot::MIXT_FRAME not implemented.
vpRobotException::positionOutOfRangeError: The requested position is out of range.
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
// Set positions in the camera frame
double pos1 = 0.1; // x axis, in meter
double pos2 = 0.2; // y axis, in meter
double pos3 = 0.3; // z axis, in meter
double pos4 = M_PI/8; // rotation around x axis, in rad
double pos5 = M_PI/4; // rotation around y axis, in rad
double pos6 = M_PI; // rotation around z axis, in rad
// Set the max velocity to 20%
// Moves the robot in the camera frame
robot.setPosition(vpRobot::CAMERA_FRAME, pos1, pos2, pos3, pos4, pos5, pos6);
#endif
}
See also
setPosition()

Definition at line 1138 of file vpRobotViper850.cpp.

References setPosition(), and vpERROR_TRACE.

void vpRobotViper850::setPosition ( const char *  filename)

Move to an absolute joint position with a given percent of max velocity. The robot state is set to position control. The percent of max velocity is to set with setPositioningVelocity(). The position to reach is defined in the position file.

Parameters
filename: Name of the position file to read. The readPosFile() documentation shows a typical content of such a position file.

This method has the same behavior than the sample code given below;

#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
robot.readPosFile("MyPositionFilename.pos", q);
#endif
}
Exceptions
vpRobotException::lowLevelError: vpRobot::MIXT_FRAME not implemented.
vpRobotException::positionOutOfRangeError: The requested position is out of range.
See also
setPositioningVelocity()

Definition at line 1203 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobotException::lowLevelError, readPosFile(), setPosition(), setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpERROR_TRACE.

void vpRobotViper850::setPositioningVelocity ( const double  velocity)

Set the maximal velocity percentage to use for a position control.

The default positioning velocity is defined by vpRobotViper850::defaultPositioningVelocity. This method allows to change this default positioning velocity

Parameters
velocity: Percentage of the maximal velocity. Values should be in ]0:100].
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector position(6);
position = 0; // position in rad
// Set the max velocity to 20%
// Moves the robot to the joint position [0,0,0,0,0,0]
#endif
}
See also
getPositioningVelocity()

Definition at line 856 of file vpRobotViper850.cpp.

Referenced by move().

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

Set the current tool type.

Definition at line 136 of file vpViper850.h.

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

void vpRobotViper850::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector vel 
)
virtual

Apply a velocity to the robot.

Parameters
frame: Control frame in which the velocity is expressed. Velocities could be expressed in articular, camera frame, reference frame or mixt frame.
vel: Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector is always 6.
  • In articular, $ vel = [\dot{q}_1, \dot{q}_2, \dot{q}_3, \dot{q}_4, \dot{q}_5, \dot{q}_6]^t $ correspond to joint velocities.
  • In camera frame, $ vel = [^{c} v_x, ^{c} v_y, ^{c} v_z, ^{c} \omega_x, ^{c} \omega_y, ^{c} \omega_z]^t $ is expressed in the camera frame.
  • In reference frame, $ vel = [^{r} v_x, ^{r} v_y, ^{r} v_z, ^{r} \omega_x, ^{r} \omega_y, ^{r} \omega_z]^t $ is expressed in the reference frame.
  • In mixt frame, $ vel = [^{r} v_x, ^{r} v_y, ^{r} v_z, ^{c} \omega_x, ^{c} \omega_y, ^{c} \omega_z]^t $. In mixt frame, translations $ v_x, v_y, v_z $ are expressed in the reference frame and rotations $ \omega_x, \omega_y, \omega_z $ in the camera frame.
Exceptions
vpRobotException::wrongStateError: If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity().
Warning
Velocities could be saturated if one of them exceed the maximal autorized speed (see vpRobot::maxTranslationVelocity and vpRobot::maxRotationVelocity). To change these values use setMaxTranslationVelocity() and setMaxRotationVelocity().
#include <visp/vpConfig.h>
#include <visp/vpRobotViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
#ifdef VISP_HAVE_VIPER850
vpColVector qvel(6);
// Set a joint velocity
qvel[0] = 0.1; // Joint 1 velocity in rad/s
qvel[1] = vpMath::rad(15); // Joint 2 velocity in rad/s
qvel[2] = 0; // Joint 3 velocity in rad/s
qvel[3] = M_PI/8; // Joint 4 velocity in rad/s
qvel[4] = 0; // Joint 5 velocity in rad/s
qvel[5] = 0; // Joint 6 velocity in rad/s
// Initialize the controller to position control
while (1) {
// Apply a velocity in the joint space
// Compute new velocities qvel...
}
// Stop the robot
#endif
}

Implements vpRobot.

Examples:
servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, and servoViper850Point2DCamVelocityKalman.cpp.

Definition at line 1508 of file vpRobotViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpMatrix::data, vpRobot::getMaxRotationVelocity(), getMaxRotationVelocityJoint6(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::MIXT_FRAME, vpViper::njoint, vpColVector::rad2deg(), vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), vpERROR_TRACE, and vpRobotException::wrongStateError.

Member Data Documentation

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 111 of file vpRobot.h.

Referenced by vpRobot::operator=().

double vpViper::c56
protectedinherited

Mechanical coupling between joint 5 and joint 6.

Definition at line 157 of file vpViper.h.

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

const char *const vpViper850::CONST_CAMERA_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_camera_Viper850.xml"
staticinherited

Definition at line 80 of file vpViper850.h.

Referenced by vpViper850::getCameraParameters().

const char *const vpViper850::CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_with_distortion_Viper850.cnf"
staticinherited

Definition at line 79 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_generic_without_distortion_Viper850.cnf"
staticinherited

Definition at line 78 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_MARLIN_F033C_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_with_distortion_Viper850.cnf"
staticinherited

Definition at line 73 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_MarlinF033C_without_distortion_Viper850.cnf"
staticinherited

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

Definition at line 72 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_PTGREY_FLEA2_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_with_distortion_Viper850.cnf"
staticinherited

Definition at line 75 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_PTGREY_FLEA2_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_PTGreyFlea2_without_distortion_Viper850.cnf"
staticinherited

Definition at line 74 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_SCHUNK_GRIPPER_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_with_distortion_Viper850.cnf"
staticinherited

Definition at line 77 of file vpViper850.h.

Referenced by vpViper850::init().

const char *const vpViper850::CONST_EMC_SCHUNK_GRIPPER_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Viper850/current/include/const_eMc_schunk_gripper_without_distortion_Viper850.cnf"
staticinherited

Definition at line 76 of file vpViper850.h.

Referenced by vpViper850::init().

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

Definition at line 88 of file vpViper850.h.

Referenced by vpViper850::getCameraParameters().

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

Name of the camera attached to the end-effector.

Definition at line 85 of file vpViper850.h.

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

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

Definition at line 87 of file vpViper850.h.

Referenced by vpViper850::getCameraParameters().

double vpViper::d6
protectedinherited
const double vpRobotViper850::defaultPositioningVelocity = 15.0
static

Default positioning velocity in percentage of the maximum velocity. This value is set to 15. The member function setPositioningVelocity() allows to change this value.

Definition at line 296 of file vpRobotViper850.h.

Referenced by vpRobotViper850().

const vpViper850::vpToolType vpViper850::defaultTool = vpViper850::TOOL_PTGREY_FLEA2_CAMERA
staticinherited

Default tool attached to the robot end effector.

Examples:
testRobotViper850Pose.cpp.

Definition at line 99 of file vpViper850.h.

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

vpMatrix vpRobot::eJe
protectedinherited

robot Jacobian expressed in the end-effector frame

Definition at line 103 of file vpRobot.h.

Referenced by vpRobotCamera::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().

int vpRobot::eJeAvailable
protectedinherited

is the robot Jacobian expressed in the end-effector frame available

Definition at line 105 of file vpRobot.h.

Referenced by vpRobot::operator=().

vpMatrix vpRobot::fJe
protectedinherited

robot Jacobian expressed in the robot reference frame available

Definition at line 107 of file vpRobot.h.

Referenced by vpRobot::operator=().

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 109 of file vpRobot.h.

Referenced by vpRobot::operator=().

double vpRobot::maxRotationVelocity
protectedinherited

Definition at line 97 of file vpRobot.h.

Referenced by vpRobot::operator=(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850().

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 98 of file vpRobot.h.

double vpRobot::maxTranslationVelocity
protectedinherited

Definition at line 95 of file vpRobot.h.

Referenced by vpRobot::operator=().

const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 96 of file vpRobot.h.

int vpRobot::nDof
protectedinherited

number of degrees of freedom

Definition at line 101 of file vpRobot.h.

Referenced by vpRobot::operator=().

vpCameraParameters::vpCameraParametersProjType vpViper850::projModel
protectedinherited
double* vpRobot::qmax
protectedinherited

Definition at line 113 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

double* vpRobot::qmin
protectedinherited

Definition at line 112 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

vpToolType vpViper850::tool_current
protectedinherited

Current tool in use.

Definition at line 138 of file vpViper850.h.