ViSP  2.10.0

#include <vpSimulatorViper850.h>

+ Inheritance diagram for vpSimulatorViper850:

Public Types

enum  vpDisplayRobotType { MODEL_3D, MODEL_DH }
 
enum  vpRobotStateType { STATE_STOP, STATE_VELOCITY_CONTROL, STATE_POSITION_CONTROL, STATE_ACCELERATION_CONTROL }
 
enum  vpControlFrameType { REFERENCE_FRAME, ARTICULAR_FRAME, CAMERA_FRAME, MIXT_FRAME }
 
enum  vpToolType { TOOL_MARLIN_F033C_CAMERA, TOOL_PTGREY_FLEA2_CAMERA, TOOL_SCHUNK_GRIPPER_CAMERA, TOOL_GENERIC_CAMERA }
 

Public Member Functions

 vpSimulatorViper850 ()
 
 vpSimulatorViper850 (bool display)
 
virtual ~vpSimulatorViper850 ()
 
void getCameraParameters (vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
 
void getCameraParameters (vpCameraParameters &cam, const vpImage< unsigned char > &I)
 
void getCameraParameters (vpCameraParameters &cam, const vpImage< vpRGBa > &I)
 
void getDisplacement (const vpRobot::vpControlFrameType frame, vpColVector &displacement)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q, double &timestamp)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
 
double getPositioningVelocity (void)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &q, double &timestamp)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame, double &timestamp)
 
void get_cMe (vpHomogeneousMatrix &cMe)
 
void get_cVe (vpVelocityTwistMatrix &cVe)
 
void get_eJe (vpMatrix &eJe)
 
void get_fJe (vpMatrix &fJe)
 
void init (vpViper850::vpToolType tool, vpCameraParameters::vpCameraParametersProjType projModel=vpCameraParameters::perspectiveProjWithoutDistortion)
 
bool initialiseCameraRelativeToObject (const vpHomogeneousMatrix &cMo)
 
void initialiseObjectRelativeToCamera (const vpHomogeneousMatrix &cMo)
 
void move (const char *filename)
 
void setCameraParameters (const vpCameraParameters &cam)
 
void setJointLimit (const vpColVector &limitMin, const vpColVector &limitMax)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q)
 
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 vel)
 
vpRobot::vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
 
void stopMotion ()
 
vpCameraParameters getExternalCameraParameters () const
 
vpHomogeneousMatrix getExternalCameraPosition () const
 
void getInternalView (vpImage< vpRGBa > &I)
 
void getInternalView (vpImage< unsigned char > &I)
 
vpHomogeneousMatrix get_cMo ()
 
vpHomogeneousMatrix get_fMo () const
 
void initScene (const vpSceneObject &obj, const vpSceneDesiredObject &desiredObject)
 
void initScene (const char *obj, const char *desiredObject)
 
void initScene (const vpSceneObject &obj)
 
void initScene (const char *obj)
 
void setCameraColor (const vpColor col)
 
void setConstantSamplingTimeMode (const bool _constantSamplingTimeMode)
 
void setCurrentViewColor (const vpColor col)
 
void setDesiredViewColor (const vpColor col)
 
void setDesiredCameraPosition (const vpHomogeneousMatrix cdMo_)
 
void setDisplayRobotType (const vpDisplayRobotType dispType)
 
void setExternalCameraPosition (const vpHomogeneousMatrix camMf_)
 
void setGraphicsThickness (unsigned int thickness)
 
void setSamplingTime (const double &delta_t)
 
void setSingularityManagement (const bool sm)
 
void setVerbose (bool verbose)
 
void set_fMo (const vpHomogeneousMatrix &fMo_)
 
void getExternalImage (vpImage< unsigned char > &I)
 
void getExternalImage (vpImage< unsigned char > &I, const vpHomogeneousMatrix &camMf)
 
void getExternalImage (vpImage< vpRGBa > &I, const vpHomogeneousMatrix &camMf)
 
double getSamplingTime () const
 
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxRotationVelocity (const double maxVr)
 
void setMaxTranslationVelocity (const double maxVt)
 
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_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
 
vpColVector getJointMin () const
 
vpColVector getJointMax () const
 
double getCoupl56 () const
 

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)
 

Public Attributes

vpImage< vpRGBaI
 

Static Public Attributes

static const double defaultPositioningVelocity = 25.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 Types

enum  vpSceneObject {
  THREE_PTS, CUBE, PLATE, SMALL_PLATE,
  RECTANGLE, SQUARE_10CM, DIAMOND, TRAPEZOID,
  THREE_LINES, ROAD, TIRE, PIPE,
  CIRCLE, SPHERE, CYLINDER, PLAN,
  POINT_CLOUD
}
 
enum  vpSceneDesiredObject { D_STANDARD, D_CIRCLE, D_TOOL }
 
enum  vpCameraTrajectoryDisplayType { CT_LINE, CT_POINT }
 

Protected Member Functions

void computeArticularVelocity ()
 
void compute_fMi ()
 
void findHighestPositioningSpeed (vpColVector &q)
 
void getExternalImage (vpImage< vpRGBa > &I)
 
void get_fMi (vpHomogeneousMatrix *fMit)
 
void init ()
 
void initArms ()
 
void initDisplay ()
 
int isInJointLimit (void)
 
bool singularityTest (const vpColVector q, vpMatrix &J)
 
void updateArticularPosition ()
 
vpCameraParameters getExternalCameraParameters (const vpImage< unsigned char > &I) const
 
vpCameraParameters getExternalCameraParameters (const vpImage< vpRGBa > &I) const
 
vpHomogeneousMatrix get_cMo () const
 
void initScene (const vpSceneObject &obj, const vpSceneDesiredObject &desiredObject, const std::list< vpImageSimulator > &imObj)
 
void initScene (const char *obj, const char *desiredObject, const std::list< vpImageSimulator > &imObj)
 
void initScene (const vpSceneObject &obj, const std::list< vpImageSimulator > &imObj)
 
void initScene (const char *obj, const std::list< vpImageSimulator > &imObj)
 
void setCameraColor (const vpColor &col)
 
void setCurrentViewColor (const vpColor &col)
 
void setDesiredViewColor (const vpColor &col)
 
void setDesiredCameraPosition (const vpHomogeneousMatrix &cdMo_)
 
void setExternalCameraPosition (const vpHomogeneousMatrix &cam_Mf)
 
vpColVector get_artCoord ()
 
void set_artCoord (const vpColVector &coord)
 
vpColVector get_artVel ()
 
void set_artVel (const vpColVector &vel)
 
vpColVector get_velocity ()
 
void set_velocity (const vpColVector &vel)
 
void set_displayBusy (const bool &status)
 
bool get_displayBusy ()
 
void deleteCameraPositionHistory ()
 
void displayTrajectory (const vpImage< unsigned char > &I, const std::list< vpHomogeneousMatrix > &list_cMo, const std::list< vpHomogeneousMatrix > &list_fMo, const vpHomogeneousMatrix &camMf)
 
void displayTrajectory (const vpImage< vpRGBa > &I, const std::list< vpHomogeneousMatrix > &list_cMo, const std::list< vpHomogeneousMatrix > &list_fMo, const vpHomogeneousMatrix &camMf)
 
vpCameraParameters getInternalCameraParameters (const vpImage< unsigned char > &I) const
 
vpCameraParameters getInternalCameraParameters (const vpImage< vpRGBa > &I) const
 
void getInternalImage (vpImage< unsigned char > &I)
 
void getInternalImage (vpImage< vpRGBa > &I)
 
void get_cMo_History (std::list< vpHomogeneousMatrix > &cMo_history)
 
void get_fMo_History (std::list< vpHomogeneousMatrix > &fMo_history)
 
void setCameraPositionRelObj (const vpHomogeneousMatrix &cMo_)
 
void setCameraPositionRelWorld (const vpHomogeneousMatrix &fMc_)
 
void setCameraSizeFactor (const float factor)
 
void setCameraTrajectoryColor (const vpColor &col)
 
void setCameraTrajectoryDisplayType (const vpCameraTrajectoryDisplayType &camTraj_type)
 
void setDisplayCameraTrajectory (const bool &do_display)
 
void setExternalCameraParameters (const vpCameraParameters &cam)
 
void setInternalCameraParameters (const vpCameraParameters &cam)
 
void setNbPtTrajectory (const unsigned int nbPt)
 
void display_scene (Matrix mat, Bound_scene &sc, const vpImage< vpRGBa > &I, const vpColor &color)
 
void display_scene (Matrix mat, Bound_scene &sc, const vpImage< unsigned char > &I, const vpColor &color)
 
vpHomogeneousMatrix navigation (const vpImage< vpRGBa > &I, bool &changed)
 
vpHomogeneousMatrix navigation (const vpImage< unsigned char > &I, bool &changed)
 
vpImagePoint projectCameraTrajectory (const vpImage< vpRGBa > &I, const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &fMo)
 
vpImagePoint projectCameraTrajectory (const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &fMo)
 
vpImagePoint projectCameraTrajectory (const vpImage< vpRGBa > &I, const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &fMo, const vpHomogeneousMatrix &cMf)
 
vpImagePoint projectCameraTrajectory (const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &fMo, const vpHomogeneousMatrix &cMf)
 
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void) const
 
void setToolType (vpViper850::vpToolType tool)
 
Deprecated functions
vp_deprecated void initScene (vpSceneObject obj, vpSceneDesiredObject desiredObject, vpList< vpImageSimulator > &imObj)
 
vp_deprecated void initScene (const char *obj, const char *desiredObject, vpList< vpImageSimulator > &imObj)
 
vp_deprecated void initScene (vpSceneObject obj, vpList< vpImageSimulator > &imObj)
 
vp_deprecated void initScene (const char *obj, vpList< vpImageSimulator > &imObj)
 
vp_deprecated void displayTrajectory (const vpImage< unsigned char > &I, vpList< vpHomogeneousMatrix > &list_cMo, vpList< vpHomogeneousMatrix > &list_fMo, vpHomogeneousMatrix camMf)
 
vp_deprecated void displayTrajectory (const vpImage< vpRGBa > &I, vpList< vpHomogeneousMatrix > &list_cMo, vpList< vpHomogeneousMatrix > &list_fMo, vpHomogeneousMatrix camMf)
 
vp_deprecated vpList< vpHomogeneousMatrixget_cMo_History ()
 
vp_deprecated vpList< vpHomogeneousMatrixget_fMo_History ()
 

Static Protected Member Functions

static void * launcher (void *arg)
 

Protected Attributes

double tcur
 
double tprev
 
Bound_scene * robotArms
 
unsigned int size_fMi
 
vpHomogeneousMatrixfMi
 
vpColVector artCoord
 
vpColVector artVel
 
vpColVector velocity
 
pthread_t thread
 
pthread_attr_t attr
 
pthread_mutex_t mutex_fMi
 
pthread_mutex_t mutex_artVel
 
pthread_mutex_t mutex_artCoord
 
pthread_mutex_t mutex_velocity
 
pthread_mutex_t mutex_display
 
bool displayBusy
 
bool robotStop
 
bool jointLimit
 
unsigned int jointLimitArt
 
bool singularityManagement
 
vpCameraParameters cameraParam
 
vpDisplayX display
 
vpDisplayRobotType displayType
 
bool displayAllowed
 
bool constantSamplingTimeMode
 
bool setVelocityCalled
 
bool verbose_
 
Bound_scene scene
 
Bound_scene desiredScene
 
Bound_scene camera
 
std::list< vpImageSimulatorobjectImage
 
vpHomogeneousMatrix fMo
 
vpHomogeneousMatrix fMc
 
vpHomogeneousMatrix camMf
 
vpHomogeneousMatrix refMo
 
vpHomogeneousMatrix cMo
 
vpHomogeneousMatrix cdMo
 
vpSceneObject object
 
vpSceneDesiredObject desiredObject
 
vpColor camColor
 
vpColor camTrajColor
 
vpColor curColor
 
vpColor desColor
 
bool sceneInitialized
 
bool displayCameraTrajectory
 
std::list< vpImagePointcameraTrajectory
 
std::list< vpHomogeneousMatrixposeList
 
std::list< vpHomogeneousMatrixfMoList
 
unsigned int nbrPtLimit
 
vpImagePoint old_iPr
 
vpImagePoint old_iPz
 
vpImagePoint old_iPt
 
bool blockedr
 
bool blockedz
 
bool blockedt
 
bool blocked
 
vpHomogeneousMatrix camMf2
 
vpHomogeneousMatrix f2Mf
 
double px_int
 
double py_int
 
double px_ext
 
double py_ext
 
bool displayObject
 
bool displayDesiredObject
 
bool displayCamera
 
bool displayImageSimulator
 
float cameraFactor
 
vpCameraTrajectoryDisplayType camTrajType
 
bool extCamChanged
 
vpHomogeneousMatrix rotz
 
unsigned int thickness_
 
double delta_t_
 
double maxTranslationVelocity
 
double maxRotationVelocity
 
int nDof
 
vpMatrix eJe
 
int eJeAvailable
 
vpMatrix fJe
 
int fJeAvailable
 
int areJointLimitsAvailable
 
double * qmin
 
double * qmax
 
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
 

Static Protected Attributes

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

Detailed Description

Simulator of Irisa's Viper S850 robot named Viper850.

Implementation of the vpRobotWireFrameSimulator class in order to simulate Irisa's Viper850 robot. This robot is an ADEPT six degrees of freedom arm.

Warning
This class uses threading capabilities. Thus on Unix-like platforms, the libpthread third-party library need to be installed. On Windows, we use the native threading capabilities.

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.

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

#include <visp/vpConfig.h>
#include <visp/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
// 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
return 0;
}

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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
// 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
return 0;
}

To control the robot in velocity, you may set the controller to velocity control and then 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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
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
return 0;
}

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.

To know how this class can be used to achieve a visual servoing simulation, you can follow the Tutorial: Image-based visual servo.

Examples:
servoSimuViper850FourPoints2DCamVelocity.cpp, and tutorial-ibvs-4pts-wireframe-robot-viper.cpp.

Definition at line 206 of file vpSimulatorViper850.h.

Member Enumeration Documentation

Enumerator
CT_LINE 
CT_POINT 

Definition at line 220 of file vpWireFrameSimulator.h.

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.

Enumerator
MODEL_3D 
MODEL_DH 

Definition at line 94 of file vpRobotWireFrameSimulator.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.

Type of scene used to display the object at the desired pose (in the internal view).

  • D_STANDARD will use the vpSceneObject used to be the object at the current position.
  • D_OUTIL will display a tool which is attached to the camera.
Enumerator
D_STANDARD 

The object displayed at the desired position is the same than the scene object defined in vpSceneObject.

D_CIRCLE 

The object displayed at the desired position is a circle.

D_TOOL 

A cylindrical tool is attached to the camera.

Definition at line 213 of file vpWireFrameSimulator.h.

Type of scene used to display the object at the current position.

Enumerator
THREE_PTS 

A 40cm by 40cm plate with 3 points at coordinates (0,0,0), (0.1,0,0), (0,0.1,0). Each point is represented by a circle with 2cm radius.

CUBE 

A 12.5cm size cube.

PLATE 

A 40cm by 40cm plate with 4 points at coordinates (-0.1,-0.1,0), (0.1,-0.1,0), (0.1,0.1,0), (0.1,0.1,0). Each point is represented by a circle with 2cm radius.

SMALL_PLATE 

4 points at coordinates (-0.03,-0.03,0), (0.03,-0.03,0), (0.03,0.03,0), (0.03,0.03,0). Each point is represented by a circle with 1cm radius.

RECTANGLE 

A 40cm by 40cm plate with 4 points at coordinates (-0.07,-0.05,0), (0.07,0.05,0), (0.07,-0.05,0), (-0.07,-0.05,0). Each point is represented by a circle with 2cm radius.

SQUARE_10CM 

A 40cm by 40cm plate with 4 points at coordinates (-0.05,0.05,0), (0.05,0.05,0), (0.05,-0.05,0), (-0.05,-0.05,0). Each point is represented by a circle with 2cm radius.

DIAMOND 

A 40cm by 40cm plate with 4 points at coordinates (0,-0.1,0), (0.1,0,0), (0,0.1,0), (-0.1,0,0). Each point is represented by a circle with 2cm radius.

TRAPEZOID 

A 40cm by 40cm plate with 4 points at coordinates (-0.025,-0.05,0), (-0.075,0.05,0), (0.075,0.05,0), (0.025,-0.05,0). Each point is represented by a circle with 2cm radius.

THREE_LINES 

Three parallel lines with equation y=-5, y=0, y=5.

ROAD 

Three parallel lines representing a road.

TIRE 

A tire represented by 2 circles with radius 10cm and 15cm.

PIPE 

A pipe represented by a cylinder of 25 cm length and 15cm radius.

CIRCLE 

A 10cm radius circle.

SPHERE 

A 15cm radius sphere.

CYLINDER 

A cylinder of 80cm length and 10cm radius.

PLAN 

A plane represented by a 56cm by 56cm plate with a grid of 49 squares inside.

POINT_CLOUD 

A plate with 8 points at coordinates (0.05,0,0), (0.15,0.05,0), (0.2,0.2,0), (-0.05,0.2,0), (-0.15,-0.1,0), (-0.1,-0.1,0), (-0.05,0.05,0) and (0.5,0,0). ach point is represented by a circle with 2cm radius.

Definition at line 186 of file vpWireFrameSimulator.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

vpSimulatorViper850::vpSimulatorViper850 ( bool  do_display)

Member Function Documentation

void vpSimulatorViper850::compute_fMi ( )
protected

Compute the pose between the robot reference frame and the frames used to compute the Denavit-Hartenberg representation. The last element of the table corresponds to the pose between the reference frame and the camera frame.

To compute the different homogeneous matrices, this function needs the articular coordinates as input.

Finally the output is a table of 8 elements : $ fM1 $, $ fM2 $, $ fM3 $, $ fM4 $, $ fM5 $, $ fM6 = fMw $, $ fM7 = fMe $ and $ fMc $ - where w is for wrist and e for effector-.

Definition at line 568 of file vpSimulatorViper850.cpp.

References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, vpViper::d6, vpRobotWireFrameSimulator::fMi, vpRobotWireFrameSimulator::get_artCoord(), get_cMe(), vpViper::get_fMc(), vpHomogeneousMatrix::inverse(), and vpRobotWireFrameSimulator::mutex_fMi.

Referenced by initialiseCameraRelativeToObject(), updateArticularPosition(), and vpSimulatorViper850().

void vpWireFrameSimulator::deleteCameraPositionHistory ( )
inlineinherited

Delete the history of the main camera position which are displayed in the external views.

Definition at line 296 of file vpWireFrameSimulator.h.

void vpWireFrameSimulator::display_scene ( Matrix  mat,
Bound_scene &  sc,
const vpImage< unsigned char > &  I,
const vpColor color 
)
protectedinherited
void vpWireFrameSimulator::displayTrajectory ( const vpImage< unsigned char > &  I,
const std::list< vpHomogeneousMatrix > &  list_cMo,
const std::list< vpHomogeneousMatrix > &  list_fMo,
const vpHomogeneousMatrix cMf 
)
inherited

Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.

The two lists must have the same size of homogeneous matrices must have the same size.

Parameters
I: The image where the trajectory is displayed.
list_cMo: The homogeneous matrices list containing the position of the camera relative to the object.
list_fMo: The homogeneous matrices list containing the position of the object relative to the world reference frame.
cMf: A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame.

Definition at line 1721 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, and vpWireFrameSimulator::thickness_.

void vpWireFrameSimulator::displayTrajectory ( const vpImage< vpRGBa > &  I,
const std::list< vpHomogeneousMatrix > &  list_cMo,
const std::list< vpHomogeneousMatrix > &  list_fMo,
const vpHomogeneousMatrix cMf 
)
inherited

Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.

The two lists must have the same size of homogeneous matrices must have the same size.

Parameters
I: The image where the trajectory is displayed.
list_cMo: The homogeneous matrices list containing the position of the camera relative to the object.
list_fMo: The homogeneous matrices list containing the position of the object relative to the world reference frame.
cMf: A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame.

Definition at line 1761 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, and vpWireFrameSimulator::thickness_.

void vpWireFrameSimulator::displayTrajectory ( const vpImage< unsigned char > &  I,
vpList< vpHomogeneousMatrix > &  list_cMo,
vpList< vpHomogeneousMatrix > &  list_fMo,
vpHomogeneousMatrix  cMf 
)
inherited
Deprecated:
This method is deprecated. You should use displayTrajectory(vpImage<unsigned char> &, const std::list<vpHomogeneousMatrix> &, const std::list<vpHomogeneousMatrix> &, const vpHomogeneousMatrix &); instead.

Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.

The two lists must have the same size of homogeneous matrices must have the same size.

Parameters
I: The image where the trajectory is displayed.
list_cMo: The homogeneous matrices list containing the position of the camera relative to the object.
list_fMo: The homogeneous matrices list containing the position of the object relative to the world reference frame.
cMf: A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame.

Definition at line 1639 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpList< type >::front(), vpList< type >::nbElements(), vpList< type >::next(), vpList< type >::outside(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, vpWireFrameSimulator::thickness_, and vpList< type >::value().

void vpWireFrameSimulator::displayTrajectory ( const vpImage< vpRGBa > &  I,
vpList< vpHomogeneousMatrix > &  list_cMo,
vpList< vpHomogeneousMatrix > &  list_fMo,
vpHomogeneousMatrix  cMf 
)
inherited
Deprecated:
This method is deprecated. You should use displayTrajectory (vpImage<vpRGBa> &, const std::list<vpHomogeneousMatrix> &, const std::list<vpHomogeneousMatrix> &, const vpHomogeneousMatrix &); instead.

Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.

The two lists must have the same size of homogeneous matrices must have the same size.

Parameters
I: The image where the trajectory is displayed.
list_cMo: The homogeneous matrices list containing the position of the camera relative to the object.
list_fMo: The homogeneous matrices list containing the position of the object relative to the world reference frame.
cMf: A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame.

Definition at line 1681 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpList< type >::front(), vpList< type >::nbElements(), vpList< type >::next(), vpList< type >::outside(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, vpWireFrameSimulator::thickness_, and vpList< type >::value().

void vpSimulatorViper850::findHighestPositioningSpeed ( vpColVector q)
protected
vpColVector vpRobotWireFrameSimulator::get_artVel ( )
inlineprotectedinherited
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 931 of file vpViper.cpp.

References vpViper::eMc, and vpHomogeneousMatrix::inverse().

Referenced by get_cMe(), vpRobotViper850::get_cMe(), vpRobotViper650::get_cMe(), vpViper::get_cVe(), get_cVe(), vpRobotViper850::get_cVe(), and vpRobotViper650::get_cVe().

void vpSimulatorViper850::get_cMe ( vpHomogeneousMatrix cMe)

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 2189 of file vpSimulatorViper850.cpp.

References vpViper::get_cMe().

Referenced by compute_fMi(), and getExternalImage().

vpHomogeneousMatrix vpRobotWireFrameSimulator::get_cMo ( )
inherited

Get the pose between the object and the robot's camera.

Returns
The pose between the object and the fixed world frame.

Definition at line 365 of file vpRobotWireFrameSimulator.cpp.

References vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_fMi(), vpHomogeneousMatrix::inverse(), and vpRobotWireFrameSimulator::size_fMi.

Referenced by vpSimulatorAfma6::setPosition().

vpHomogeneousMatrix vpWireFrameSimulator::get_cMo ( ) const
inlineinherited

Get the pose between the object and the camera.

Returns
The pose between between the object and the camera.

Definition at line 401 of file vpWireFrameSimulator.h.

void vpWireFrameSimulator::get_cMo_History ( std::list< vpHomogeneousMatrix > &  cMo_history)
inlineinherited

Get the homogeneous matrices cMo stored to display the camera trajectory.

Parameters
cMo_history: The list of the homogeneous matrices cMo.

Definition at line 408 of file vpWireFrameSimulator.h.

vp_deprecated vpList<vpHomogeneousMatrix> vpWireFrameSimulator::get_cMo_History ( )
inlineinherited
Deprecated:
This method is deprecated. You should use get_cMo_History(std::list<vpHomogeneousMatrix> &) instead.

Get the homogeneous matrices cMo stored to display the camera trajectory.
Returns
Returns the list of the homogeneous matrices cMo.

Definition at line 590 of file vpWireFrameSimulator.h.

References vpList< type >::addRight().

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

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

void vpSimulatorViper850::get_cVe ( vpVelocityTwistMatrix cVe)

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.

Definition at line 2202 of file vpSimulatorViper850.cpp.

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

bool vpRobotWireFrameSimulator::get_displayBusy ( )
inlineprotectedinherited
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 computeArticularVelocity(), get_eJe(), vpRobotViper850::get_eJe(), vpRobotViper650::get_eJe(), and getVelocity().

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

Definition at line 2220 of file vpSimulatorViper850.cpp.

References vpRobotWireFrameSimulator::get_artCoord(), vpViper::get_eJe(), 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 computeArticularVelocity(), get_fJe(), vpRobotViper850::get_fJe(), vpRobotViper650::get_fJe(), and getVelocity().

void vpSimulatorViper850::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 2244 of file vpSimulatorViper850.cpp.

References vpRobotWireFrameSimulator::get_artCoord(), vpViper::get_fJe(), 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 compute_fMi(), vpViper::getForwardKinematics(), getPosition(), vpRobotViper850::getVelocity(), vpRobotViper650::getVelocity(), 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 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 vpSimulatorViper850::get_fMi ( vpHomogeneousMatrix fMit)
inlineprotectedvirtual

Get a table of poses between the reference frame and the frames you used to compute the Denavit-Hartenberg representation

Implements vpRobotWireFrameSimulator.

Definition at line 287 of file vpSimulatorViper850.h.

Referenced by getExternalImage(), initialiseObjectRelativeToCamera(), and updateArticularPosition().

vpHomogeneousMatrix vpRobotWireFrameSimulator::get_fMo ( ) const
inlineinherited

Get the pose between the object and the fixed world frame.

Returns
The pose between the object and the fixed world frame.

Definition at line 219 of file vpRobotWireFrameSimulator.h.

References vpWireFrameSimulator::fMo.

void vpWireFrameSimulator::get_fMo_History ( std::list< vpHomogeneousMatrix > &  fMo_history)
inlineinherited

Get the homogeneous matrices fMo stored to display the camera trajectory.

Parameters
fMo_history: The list of the homogeneous matrices fMo.

Definition at line 427 of file vpWireFrameSimulator.h.

vp_deprecated vpList<vpHomogeneousMatrix> vpWireFrameSimulator::get_fMo_History ( )
inlineinherited
Deprecated:
This method is deprecated. You should use get_fMo_History(std::list<vpHomogeneousMatrix> &) instead.

Get the homogeneous matrices fMo stored to display the camera trajectory.
Returns
Returns the list of the homogeneous matrices fMo.

Definition at line 605 of file vpWireFrameSimulator.h.

References vpList< type >::addRight().

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

vpColVector vpRobotWireFrameSimulator::get_velocity ( )
inlineprotectedinherited
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().

void vpSimulatorViper850::getCameraParameters ( vpCameraParameters cam,
const unsigned int &  image_width,
const unsigned int &  image_height 
)

Get the current intrinsic camera parameters obtained by calibration.

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.
Warning
The image size must be : 640x480 !

Definition at line 344 of file vpSimulatorViper850.cpp.

References vpViper850::CONST_MARLIN_F033C_CAMERA_NAME, vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME, vpViper850::getToolType(), vpCameraParameters::initPersProjWithoutDistortion(), vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpViper850::TOOL_GENERIC_CAMERA, vpViper850::TOOL_MARLIN_F033C_CAMERA, vpViper850::TOOL_PTGREY_FLEA2_CAMERA, vpViper850::TOOL_SCHUNK_GRIPPER_CAMERA, and vpTRACE.

Referenced by getCameraParameters(), and initDisplay().

void vpSimulatorViper850::getCameraParameters ( vpCameraParameters cam,
const vpImage< unsigned char > &  I_ 
)

Get the current intrinsic camera parameters obtained by calibration.

Parameters
cam: In output, camera parameters to fill.
I_: A B&W image send by the current camera in use.
Warning
The image size must be : 640x480 !

Definition at line 397 of file vpSimulatorViper850.cpp.

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

void vpSimulatorViper850::getCameraParameters ( vpCameraParameters cam,
const vpImage< vpRGBa > &  I_ 
)

Get the current intrinsic camera parameters obtained by calibration.

Parameters
cam: In output, camera parameters to fill.
I_: A B&W image send by the current camera in use.
Warning
The image size must be : 640x480 !

Definition at line 412 of file vpSimulatorViper850.cpp.

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

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 vpSimulatorViper850::getDisplacement ( const 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 1944 of file vpSimulatorViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpColVector::resize().

vpCameraParameters vpRobotWireFrameSimulator::getExternalCameraParameters ( ) const
inlineinherited

Get the parameters of the virtual external camera.

Returns
It returns the camera parameters.

Definition at line 188 of file vpRobotWireFrameSimulator.h.

References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().

vpCameraParameters vpWireFrameSimulator::getExternalCameraParameters ( const vpImage< unsigned char > &  I) const
inlineinherited

Get the parameters of the virtual external camera.

Parameters
I: The image used to display the view of the camera.
Returns
It returns the camera parameters.

Definition at line 311 of file vpWireFrameSimulator.h.

References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().

Referenced by vpWireFrameSimulator::projectCameraTrajectory().

vpCameraParameters vpWireFrameSimulator::getExternalCameraParameters ( const vpImage< vpRGBa > &  I) const
inlineinherited

Get the parameters of the virtual external camera.

Parameters
I: The image used to display the view of the camera.
Returns
It returns the camera parameters.

Definition at line 330 of file vpWireFrameSimulator.h.

References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().

vpHomogeneousMatrix vpRobotWireFrameSimulator::getExternalCameraPosition ( ) const
inlineinherited

Get the external camera's position relative to the the world reference frame.

Returns
the main external camera position relative to the the world reference frame.

Definition at line 205 of file vpRobotWireFrameSimulator.h.

References vpWireFrameSimulator::getExternalCameraPosition().

Referenced by vpSimulatorAfma6::updateArticularPosition(), and updateArticularPosition().

void vpWireFrameSimulator::getExternalImage ( vpImage< unsigned char > &  I)
inherited

Get the external view. It corresponds to the view of the scene from a reference frame you have to set.

Parameters
I: The image where the external view is displayed.
Warning
: The objects are displayed thanks to overlays. The image I is not modified.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 1429 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::camColor, vpWireFrameSimulator::camera, vpWireFrameSimulator::cameraTrajectory, vpWireFrameSimulator::camMf, vpWireFrameSimulator::camMf2, vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::cMo, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpWireFrameSimulator::CUBE, vpWireFrameSimulator::curColor, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayCamera, vpWireFrameSimulator::displayCameraTrajectory, vpWireFrameSimulator::displayImageSimulator, vpDisplay::displayLine(), vpWireFrameSimulator::displayObject, vpDisplay::displayPoint(), vpWireFrameSimulator::extCamChanged, vpWireFrameSimulator::f2Mf, vpWireFrameSimulator::fMc, vpWireFrameSimulator::fMo, vpWireFrameSimulator::fMoList, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::navigation(), vpWireFrameSimulator::nbrPtLimit, vpWireFrameSimulator::objectImage, vpWireFrameSimulator::poseList, vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::px_ext, vpWireFrameSimulator::py_ext, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpImageSimulator::setCameraPosition(), vpWireFrameSimulator::SPHERE, and vpWireFrameSimulator::thickness_.

void vpWireFrameSimulator::getExternalImage ( vpImage< unsigned char > &  I,
const vpHomogeneousMatrix cam_Mf 
)
inherited
void vpWireFrameSimulator::getExternalImage ( vpImage< vpRGBa > &  I,
const vpHomogeneousMatrix cam_Mf 
)
inherited
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().

vpCameraParameters vpWireFrameSimulator::getInternalCameraParameters ( const vpImage< unsigned char > &  I) const
inlineinherited

Get the parameters of the virtual internal camera.

Parameters
I: The image used to display the view of the camera.
Returns
It returns the camera parameters.

Definition at line 361 of file vpWireFrameSimulator.h.

References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().

Referenced by vpWireFrameSimulator::getExternalImage(), and vpWireFrameSimulator::getInternalImage().

vpCameraParameters vpWireFrameSimulator::getInternalCameraParameters ( const vpImage< vpRGBa > &  I) const
inlineinherited

Get the parameters of the virtual internal camera.

Parameters
I: The image used to display the view of the camera.
Returns
It returns the camera parameters.

Definition at line 380 of file vpWireFrameSimulator.h.

References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().

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 initialiseCameraRelativeToObject(), 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 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 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 vpSimulatorViper850::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
virtual

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)
q: 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:
#include <visp/vpConfig.h>
#include <visp/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpTranslationVector.h>
#include <visp/vpRxyzVector.h>
#include <visp/vpRotationMatrix.h>
#include <visp/vpHomogeneousMatrix.h>
int main()
{
vpColVector position;
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 (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
}
See also
getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q, double &timestamp)
setPosition(const vpRobot::vpControlFrameType frame, const vpColVector & r)

Implements vpRobot.

Definition at line 1631 of file vpSimulatorViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpHomogeneousMatrix::extract(), vpRobotWireFrameSimulator::get_artCoord(), vpViper::get_fMc(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.

Referenced by getPosition().

void vpSimulatorViper850::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector q,
double &  timestamp 
)

Get the current time stamped 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)
q: 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: Unix time in second since January 1st 1970.
See also
getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)

Definition at line 1707 of file vpSimulatorViper850.cpp.

References getPosition(), and vpTime::measureTimeSecond().

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

Get the current position of the robot.

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

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

See also
getPosition(const vpRobot::vpControlFrameType frame, vpColVector &)

Definition at line 1725 of file vpSimulatorViper850.cpp.

References getPosition().

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

Get the current time stamped 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 1754 of file vpSimulatorViper850.cpp.

References getPosition(), and vpTime::measureTimeSecond().

double vpSimulatorViper850::getPositioningVelocity ( void  )
inline

Definition at line 242 of file vpSimulatorViper850.h.

Referenced by findHighestPositioningSpeed().

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited
vpToolType vpViper850::getToolType ( ) const
inlineinherited

Get the current tool type.

Definition at line 126 of file vpViper850.h.

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

void vpSimulatorViper850::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector vel 
)

Get the robot velocities.

Parameters
frame: Frame in wich velocities are mesured.
vel: Measured velocities. Translations are expressed in m/s and rotations in rad/s.
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]$.
#include <visp/vpConfig.h>
#include <visp/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
int main()
{
// 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
for ( ; ; ) {
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]
}
}

Definition at line 1060 of file vpSimulatorViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpViper::eMc, vpRobotWireFrameSimulator::get_artCoord(), vpRobotWireFrameSimulator::get_artVel(), vpViper::get_eJe(), vpViper::get_fJe(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.

Referenced by getVelocity().

void vpSimulatorViper850::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector vel,
double &  timestamp 
)

Get the robot time stamped velocities.

Parameters
frame: Frame in wich velocities are mesured.
vel: Measured velocities. Translations are expressed in m/s and rotations in rad/s.
timestamp: Unix time in second since January 1st 1970.
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]$.
See also
getVelocity(const vpRobot::vpControlFrameType frame, vpColVector & vel)

Definition at line 1119 of file vpSimulatorViper850.cpp.

References getVelocity(), and vpTime::measureTimeSecond().

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

Get the robot velocities.

Parameters
frame: Frame in wich velocities are mesured.
Returns
Measured velocities. Translations are expressed in m/s and rotations in rad/s.
#include <visp/vpConfig.h>
#include <visp/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
int main()
{
// 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
for ( ; ; ) {
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]
}
}

Definition at line 1168 of file vpSimulatorViper850.cpp.

References getVelocity().

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

Get the time stamped robot velocities.

Parameters
frame: Frame in wich velocities are mesured.
timestamp: Unix time in second since January 1st 1970.
Returns
Measured velocities. Translations are expressed in m/s and rotations in rad/s.
See also
getVelocity(vpRobot::vpControlFrameType frame)

Definition at line 1189 of file vpSimulatorViper850.cpp.

References getVelocity(), and vpTime::measureTimeSecond().

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

Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera.

The eMc parameters depend on the camera.

Warning
Only perspective projection without distortion is available!
Parameters
tool: Tool to use.
proj_model: Projection model associated to the camera.
See also
vpCameraParameters, init()

Definition at line 290 of file vpSimulatorViper850.cpp.

References vpHomogeneousMatrix::buildFrom(), vpViper::eMc, vpViper::erc, vpViper::etc, vpViper850::projModel, vpMath::rad(), setCameraParameters(), vpViper850::setToolType(), vpViper850::TOOL_GENERIC_CAMERA, vpViper850::TOOL_MARLIN_F033C_CAMERA, vpViper850::TOOL_PTGREY_FLEA2_CAMERA, and vpViper850::TOOL_SCHUNK_GRIPPER_CAMERA.

void vpSimulatorViper850::init ( void  )
protectedvirtual

Method which initialises the parameters linked to the robot caracteristics.

Set the path to the arm files (*.bnd and *.sln) used by the simulator. If the path set in vpConfig.h in VISP_ROBOT_ARMS_DIR macro is not valid, the path is set from the VISP_ROBOT_ARMS_DIR environment variable that the user has to set.

Reimplemented from vpRobotWireFrameSimulator.

Definition at line 195 of file vpSimulatorViper850.cpp.

References vpRobotWireFrameSimulator::artCoord, vpRobot::ARTICULAR_FRAME, vpRobotWireFrameSimulator::artVel, vpIoTools::checkDirectory(), defaultPositioningVelocity, vpViper850::defaultTool, vpRobotWireFrameSimulator::fMi, vpIoTools::getenv(), vpViper::joint_max, vpViper::joint_min, vpViper::njoint, vpMath::rad(), vpColVector::resize(), vpRobot::setRobotFrame(), setRobotState(), vpRobotWireFrameSimulator::size_fMi, and vpRobot::STATE_STOP.

Referenced by vpSimulatorViper850().

void vpSimulatorViper850::initArms ( )
protectedvirtual

Initialise the display of the robot's arms.

Set the path to the scene files (*.bnd and *.sln) used by the simulator. If the path set in vpConfig.h in VISP_SCENES_DIR macro is not valid, the path is set from the VISP_SCENES_DIR environment variable that the user has to set.

Implements vpRobotWireFrameSimulator.

Definition at line 2290 of file vpSimulatorViper850.cpp.

References vpWireFrameSimulator::camera, vpWireFrameSimulator::cameraFactor, vpIoTools::checkDirectory(), vpException::dimensionError, vpWireFrameSimulator::displayCamera, vpIoTools::getenv(), and vpRobotWireFrameSimulator::robotArms.

Referenced by initDisplay().

bool vpSimulatorViper850::initialiseCameraRelativeToObject ( const vpHomogeneousMatrix cMo_)

This method enables to initialise the joint coordinates of the robot in order to position the camera relative to the object.

Before using this method it is advised to set the position of the object thanks to the set_fMo() method.

In other terms, set the world to camera transformation ${^f}{\bf M}_c = {^f}{\bf M}_o \; ({^c}{\bf M}{_o})^{-1}$, and from the inverse kinematics set the joint positions ${\bf q}$ that corresponds to the ${^f}{\bf M}_c$ transformation.

Parameters
cMo_: the desired pose of the camera.
Returns
false if the robot kinematics is not able to reach the cMo position.

Definition at line 2464 of file vpSimulatorViper850.cpp.

References compute_fMi(), vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_artCoord(), vpViper::getInverseKinematics(), vpHomogeneousMatrix::inverse(), vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpColVector::t(), vpRobotWireFrameSimulator::verbose_, and vpERROR_TRACE.

void vpSimulatorViper850::initialiseObjectRelativeToCamera ( const vpHomogeneousMatrix cMo_)

This method enables to initialise the pose between the object and the reference frame, in order to position the object relative to the camera.

Before using this method it is advised to set the articular coordinates of the robot.

In other terms, set the world to object transformation ${^f}{\bf M}_o = {^f}{\bf M}_c \; {^c}{\bf M}_o$ where $ {^f}{\bf M}_c = f({\bf q})$ with ${\bf q}$ the robot joint position

Parameters
cMo_: the desired pose of the camera.

Definition at line 2505 of file vpSimulatorViper850.cpp.

References vpWireFrameSimulator::fMo, get_fMi(), vpRobotWireFrameSimulator::set_artVel(), and vpRobotWireFrameSimulator::set_velocity().

void vpRobotWireFrameSimulator::initScene ( const vpSceneObject obj,
const vpSceneDesiredObject desired_object 
)
inherited

Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

It exists several default scenes you can use. Use the vpSceneObject and the vpSceneDesiredObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

Parameters
obj: Type of scene used to display the object at the current position.
desired_object: Type of scene used to display the object at the desired pose (in the internal view).

Definition at line 134 of file vpRobotWireFrameSimulator.cpp.

References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().

void vpRobotWireFrameSimulator::initScene ( const char *  obj,
const char *  desired_object 
)
inherited

Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file. It is also possible to use a vrml (.wrl) file.

Parameters
obj: Path to the scene file you want to use.
desired_object: Path to the scene file you want to use.

Definition at line 157 of file vpRobotWireFrameSimulator.cpp.

References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().

void vpRobotWireFrameSimulator::initScene ( const vpSceneObject obj)
inherited

Initialize the display. It enables to choose the type of object which will be used to display the object at the current position. The object at the desired position is not displayed.

It exists several default scenes you can use. Use the vpSceneObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

Parameters
obj: Type of scene used to display the object at the current position.

Definition at line 178 of file vpRobotWireFrameSimulator.cpp.

References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().

void vpRobotWireFrameSimulator::initScene ( const char *  obj)
inherited

Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.

Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file, or the vrml file.

Parameters
obj: Path to the scene file you want to use.

Definition at line 199 of file vpRobotWireFrameSimulator.cpp.

References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().

void vpWireFrameSimulator::initScene ( const vpSceneObject obj,
const vpSceneDesiredObject desired_object,
const std::list< vpImageSimulator > &  imObj 
)
inherited

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

It exists several default scenes you can use. Use the vpSceneObject and the vpSceneDesiredObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Type of scene used to display the object at the current position.
desired_object: Type of scene used to display the object at the desired pose (in the internal view).
imObj: A list of vpImageSimulator instances.

Definition at line 719 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.

void vpWireFrameSimulator::initScene ( const char *  obj,
const char *  desired_object,
const std::list< vpImageSimulator > &  imObj 
)
inherited

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Path to the scene file you want to use.
desired_object: Path to the scene file you want to use.
imObj: A list of vpImageSimulator instances.

Definition at line 841 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.

void vpWireFrameSimulator::initScene ( const vpSceneObject obj,
const std::list< vpImageSimulator > &  imObj 
)
inherited

Initialize the simulator. It enables to choose the type of object which will be used to display the object at the current position. The object at the desired position is not displayed.

It exists several default scenes you can use. Use the vpSceneObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Type of scene used to display the object at the current position.
imObj: A list of vpImageSimulator instances.

Definition at line 951 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.

void vpWireFrameSimulator::initScene ( const char *  obj,
const std::list< vpImageSimulator > &  imObj 
)
inherited

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.

Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Path to the scene file you want to use.
imObj: A list of vpImageSimulator instances.

Definition at line 1051 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.

void vpWireFrameSimulator::initScene ( vpSceneObject  obj,
vpSceneDesiredObject  desired_object,
vpList< vpImageSimulator > &  imObj 
)
inherited
Deprecated:
This method is deprecated. You should use initScene(vpSceneObject, vpSceneDesiredObject, const std::list<vpImageSimulator> &) instead.

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

It exists several default scenes you can use. Use the vpSceneObject and the vpSceneDesiredObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Type of scene used to display the object at the current position.
desired_object: Type of scene used to display the object at the desired pose (in the internal view).
imObj: A list of vpImageSimulator instances.

Definition at line 695 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpList< type >::front(), vpWireFrameSimulator::initScene(), vpList< type >::next(), vpWireFrameSimulator::objectImage, vpList< type >::outside(), and vpList< type >::value().

void vpWireFrameSimulator::initScene ( const char *  obj,
const char *  desired_object,
vpList< vpImageSimulator > &  imObj 
)
inherited
Deprecated:
This method is deprecated. You should use initScene(const char*, const char*, const std::list<vpImageSimulator> &) instead.

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Path to the scene file you want to use.
desired_object: Path to the scene file you want to use.
imObj: A list of vpImageSimulator instances.

Definition at line 817 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpList< type >::front(), vpWireFrameSimulator::initScene(), vpList< type >::next(), vpWireFrameSimulator::objectImage, vpList< type >::outside(), and vpList< type >::value().

void vpWireFrameSimulator::initScene ( vpSceneObject  obj,
vpList< vpImageSimulator > &  imObj 
)
inherited
Deprecated:
This method is deprecated. You should use initScene(vpSceneObject, const std::list<vpImageSimulator> &) instead.

Initialize the simulator. It enables to choose the type of object which will be used to display the object at the current position. The object at the desired position is not displayed.

It exists several default scenes you can use. Use the vpSceneObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Type of scene used to display the object at the current position.
imObj: A list of vpImageSimulator instances.

Definition at line 928 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpList< type >::front(), vpWireFrameSimulator::initScene(), vpList< type >::next(), vpWireFrameSimulator::objectImage, vpList< type >::outside(), and vpList< type >::value().

void vpWireFrameSimulator::initScene ( const char *  obj,
vpList< vpImageSimulator > &  imObj 
)
inherited
Deprecated:
This method is deprecated. You should use initScene(const char*, const std::list<vpImageSimulator> &) instead.

Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.

Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.

It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.

Parameters
obj: Path to the scene file you want to use.
imObj: A list of vpImageSimulator instances.

Definition at line 1028 of file vpWireFrameSimulator.cpp.

References vpWireFrameSimulator::displayImageSimulator, vpList< type >::front(), vpWireFrameSimulator::initScene(), vpList< type >::next(), vpWireFrameSimulator::objectImage, vpList< type >::outside(), and vpList< type >::value().

int vpSimulatorViper850::isInJointLimit ( void  )
protectedvirtual

Method used to check if the robot reached a joint limit.

Implements vpRobotWireFrameSimulator.

Definition at line 1853 of file vpSimulatorViper850.cpp.

References vpRobotWireFrameSimulator::get_artCoord(), vpViper::joint_max, and vpViper::joint_min.

Referenced by updateArticularPosition().

static void* vpRobotWireFrameSimulator::launcher ( void *  arg)
inlinestaticprotectedinherited

Function used to launch the thread which moves the robot.

Definition at line 339 of file vpRobotWireFrameSimulator.h.

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

void vpSimulatorViper850::move ( const char *  filename)

Moves the robot to the joint position specified in the filename.

Parameters
filenameFile containing a joint position.
See also
readPosFile

Definition at line 2163 of file vpSimulatorViper850.cpp.

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

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

vpImagePoint vpWireFrameSimulator::projectCameraTrajectory ( const vpImage< unsigned char > &  I,
const vpHomogeneousMatrix cMo_,
const vpHomogeneousMatrix fMo_ 
)
protectedinherited
vpImagePoint vpWireFrameSimulator::projectCameraTrajectory ( const vpImage< vpRGBa > &  I,
const vpHomogeneousMatrix cMo_,
const vpHomogeneousMatrix fMo_,
const vpHomogeneousMatrix cMf 
)
protectedinherited
vpImagePoint vpWireFrameSimulator::projectCameraTrajectory ( const vpImage< unsigned char > &  I,
const vpHomogeneousMatrix cMo_,
const vpHomogeneousMatrix fMo_,
const vpHomogeneousMatrix cMf 
)
protectedinherited
bool vpSimulatorViper850::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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
int main()
{
// 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
}
See also
savePosFile()

Definition at line 2056 of file vpSimulatorViper850.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 vpRobotViper850::setVelocity().

bool vpSimulatorViper850::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 2126 of file vpSimulatorViper850.cpp.

References vpMath::deg().

void vpRobotWireFrameSimulator::set_displayBusy ( const bool &  status)
inlineprotectedinherited
void vpRobotWireFrameSimulator::set_fMo ( const vpHomogeneousMatrix fMo_)
inlineinherited

Set the pose between the object and the fixed world frame.

Parameters
fMo_: The pose between the object and the fixed world frame.

Definition at line 326 of file vpRobotWireFrameSimulator.h.

void vpRobotWireFrameSimulator::setCameraColor ( const vpColor  col)
inlineinherited

Set the color used to display the camera in the external view.

Parameters
col: The desired color.

Definition at line 232 of file vpRobotWireFrameSimulator.h.

void vpWireFrameSimulator::setCameraColor ( const vpColor col)
inlineinherited

Set the color used to display the camera in the external view.

Parameters
col: The desired color.
Examples:
wireframeSimulator.cpp.

Definition at line 444 of file vpWireFrameSimulator.h.

void vpSimulatorViper850::setCameraParameters ( const vpCameraParameters cam)

Set the intrinsic camera parameters.

Parameters
cam: The desired camera parameters.

Definition at line 425 of file vpSimulatorViper850.cpp.

References vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpWireFrameSimulator::px_int, and vpWireFrameSimulator::py_int.

Referenced by init().

void vpWireFrameSimulator::setCameraPositionRelObj ( const vpHomogeneousMatrix cMo_)
inlineinherited

Set the position of the camera relative to the object.

Parameters
cMo_: The pose of the camera.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 450 of file vpWireFrameSimulator.h.

References vpHomogeneousMatrix::inverse().

void vpWireFrameSimulator::setCameraPositionRelWorld ( const vpHomogeneousMatrix fMc_)
inlineinherited

Set the position of the the world reference frame relative to the camera.

Parameters
fMc_: The pose of the camera.

Definition at line 457 of file vpWireFrameSimulator.h.

References vpHomogeneousMatrix::inverse().

void vpWireFrameSimulator::setCameraSizeFactor ( const float  factor)
inlineinherited

Set the parameter which enables to choose the size of the main camera in the external camera views. By default this parameter is set to 1.

Parameters
factor: The ration for the camera size.

Definition at line 464 of file vpWireFrameSimulator.h.

void vpWireFrameSimulator::setCameraTrajectoryColor ( const vpColor col)
inlineinherited

Set the color used to display the camera trajectory in the external view.

Parameters
col: The desired color.

Definition at line 471 of file vpWireFrameSimulator.h.

void vpWireFrameSimulator::setCameraTrajectoryDisplayType ( const vpCameraTrajectoryDisplayType camTraj_type)
inlineinherited

Set the way to display the history of the main camera trajectory in the main external view. The choice is given between displaying lines and points.

Parameters
camTraj_type: The chosen way to display the camera trajectory.

Definition at line 478 of file vpWireFrameSimulator.h.

void vpRobotWireFrameSimulator::setConstantSamplingTimeMode ( const bool  _constantSamplingTimeMode)
inlineinherited

Set the flag used to force the sampling time in the thread computing the robot's displacement to a constant value; see setSamplingTime(). It may be useful if the main thread (computing the features) is very time consuming. False by default.

Parameters
_constantSamplingTimeMode: The new value of the constantSamplingTimeMode flag.

Definition at line 242 of file vpRobotWireFrameSimulator.h.

void vpRobotWireFrameSimulator::setCurrentViewColor ( const vpColor  col)
inlineinherited

Set the color used to display the object at the current position in the robot's camera view.

Parameters
col: The desired color.

Definition at line 251 of file vpRobotWireFrameSimulator.h.

void vpWireFrameSimulator::setCurrentViewColor ( const vpColor col)
inlineinherited

Set the color used to display the object at the current position.

Parameters
col: The desired color.
Examples:
wireframeSimulator.cpp.

Definition at line 485 of file vpWireFrameSimulator.h.

void vpRobotWireFrameSimulator::setDesiredCameraPosition ( const vpHomogeneousMatrix  cdMo_)
inlineinherited

Set the desired position of the robot's camera relative to the object.

Parameters
cdMo_: The desired pose of the camera.

Definition at line 265 of file vpRobotWireFrameSimulator.h.

References vpWireFrameSimulator::setDesiredCameraPosition().

void vpWireFrameSimulator::setDesiredCameraPosition ( const vpHomogeneousMatrix cdMo_)
inlineinherited

Set the desired position of the camera relative to the object.

Parameters
cdMo_: The desired pose of the camera.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 491 of file vpWireFrameSimulator.h.

Referenced by vpRobotWireFrameSimulator::setDesiredCameraPosition().

void vpRobotWireFrameSimulator::setDesiredViewColor ( const vpColor  col)
inlineinherited

Set the color used to display the object at the desired position in the robot's camera view.

Parameters
col: The desired color.

Definition at line 258 of file vpRobotWireFrameSimulator.h.

void vpWireFrameSimulator::setDesiredViewColor ( const vpColor col)
inlineinherited

Set the color used to display the object at the desired position.

Parameters
col: The desired color.
Examples:
wireframeSimulator.cpp.

Definition at line 497 of file vpWireFrameSimulator.h.

void vpWireFrameSimulator::setDisplayCameraTrajectory ( const bool &  do_display)
inlineinherited

Enable or disable the displaying of the camera trajectory in the main external camera view.

By default the trajectory is displayed.

Parameters
do_display: Set to true to display the camera trajectory.

Definition at line 505 of file vpWireFrameSimulator.h.

void vpRobotWireFrameSimulator::setDisplayRobotType ( const vpDisplayRobotType  dispType)
inlineinherited

Set the way to draw the robot. Depending on what you choose you can display a 3D wireframe model or a set of lines linking the frames used to compute the geometrical model.

Parameters
dispType: Type of display. Can be MODEL_3D or MODEL_DH.

Definition at line 275 of file vpRobotWireFrameSimulator.h.

void vpWireFrameSimulator::setExternalCameraParameters ( const vpCameraParameters cam)
inlineinherited

Set the internal camera parameters.

Parameters
cam: The desired camera parameters.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 512 of file vpWireFrameSimulator.h.

References vpCameraParameters::get_px(), and vpCameraParameters::get_py().

Referenced by vpSimulatorAfma6::initDisplay(), and initDisplay().

void vpRobotWireFrameSimulator::setExternalCameraPosition ( const vpHomogeneousMatrix  camMf_)
inlineinherited

Set the external camera point of view.

Parameters
camMf_: The pose of the external camera relative to the world reference frame.

Definition at line 281 of file vpRobotWireFrameSimulator.h.

References vpWireFrameSimulator::setExternalCameraPosition().

Referenced by vpSimulatorAfma6::initDisplay(), and initDisplay().

void vpWireFrameSimulator::setExternalCameraPosition ( const vpHomogeneousMatrix cam_Mf)
inlineinherited

Set the external camera point of view.

Parameters
cam_Mf: The pose of the external camera relative to the world reference frame.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 521 of file vpWireFrameSimulator.h.

References vpHomogeneousMatrix::buildFrom(), vpHomogeneousMatrix::extract(), and vpHomogeneousMatrix::inverse().

Referenced by vpRobotWireFrameSimulator::setExternalCameraPosition().

void vpRobotWireFrameSimulator::setGraphicsThickness ( unsigned int  thickness)
inlineinherited

Specify the thickness of the graphics drawings.

Definition at line 288 of file vpRobotWireFrameSimulator.h.

void vpWireFrameSimulator::setInternalCameraParameters ( const vpCameraParameters cam)
inlineinherited

Set the internal camera parameters.

Parameters
cam: The desired camera parameters.
Examples:
servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuSphere.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, and wireframeSimulator.cpp.

Definition at line 544 of file vpWireFrameSimulator.h.

References vpCameraParameters::get_px(), and vpCameraParameters::get_py().

void vpSimulatorViper850::setJointLimit ( const vpColVector limitMin,
const vpColVector limitMax 
)

This method enables to set the minimum and maximum joint limits for all the six axis of the robot. All the values have to be given in radian.

Parameters
limitMin: The minimum joint limits are given in a vector of size 6. All the value must be in radian.
limitMax: The maximum joint limits are given in a vector of size 6. All the value must be in radian.

Definition at line 1768 of file vpSimulatorViper850.cpp.

References vpMatrix::getRows(), vpViper::joint_max, vpViper::joint_min, and vpTRACE.

void vpRobot::setMaxRotationVelocity ( const double  w_max)
inherited

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.
Examples:
servoMomentPoints.cpp, servoSimu4Points.cpp, and servoSimuSphere.cpp.

Definition at line 266 of file vpRobot.cpp.

Referenced by vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().

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 vpWireFrameSimulator::setNbPtTrajectory ( const unsigned int  nbPt)
inlineinherited

Set the maximum number of main camera's positions which are stored. Those position can be displayed in the external camera field of view. By default this parameter is set to 1000.

Parameters
nbPt: The desired number of position which are saved.

Definition at line 554 of file vpWireFrameSimulator.h.

void vpSimulatorViper850::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector q 
)
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
q: 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 respectively X, Y, Z, A, B, C, with X,Y,Z the translations, and A,B,C the rotations of the end-effector.
  • In the camera and the reference frame, 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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
int main()
{
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
}

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 1288 of file vpSimulatorViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpViper::get_fMc(), vpViper::getInverseKinematics(), vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobotException::positionOutOfRangeError, vpRobot::REFERENCE_FRAME, vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpRobotWireFrameSimulator::setVelocityCalled, vpRobot::STATE_POSITION_CONTROL, vpMatrix::sumSquare(), vpRobotWireFrameSimulator::verbose_, and vpERROR_TRACE.

Referenced by move(), and setPosition().

void vpSimulatorViper850::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 overloads 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/vpSimulatorViper850.h>
int main()
{
// 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);
}
See also
setPosition()

Definition at line 1494 of file vpSimulatorViper850.cpp.

References setPosition(), and vpERROR_TRACE.

void vpSimulatorViper850::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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
int main()
{
robot.readPosFile("MyPositionFilename.pos", q);
}
Exceptions
vpRobotException::lowLevelError: vpRobot::MIXT_FRAME not implemented.
vpRobotException::positionOutOfRangeError: The requested position is out of range.
See also
setPositioningVelocity()

Definition at line 1555 of file vpSimulatorViper850.cpp.

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

void vpSimulatorViper850::setPositioningVelocity ( const double  vel)
inline

Definition at line 274 of file vpSimulatorViper850.h.

vpRobot::vpRobotStateType vpSimulatorViper850::setRobotState ( const vpRobot::vpRobotStateType  newState)
virtual

Change the robot state.

Parameters
newState: New requested robot state.

Reimplemented from vpRobot.

Definition at line 718 of file vpSimulatorViper850.cpp.

References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and stopMotion().

Referenced by init(), move(), and setPosition().

void vpRobotWireFrameSimulator::setSamplingTime ( const double &  delta_t)
inlinevirtualinherited

Set the sampling time.

Parameters
delta_t: Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

Since the wireframe simulator is threaded, the sampling time is set to vpTime::minTimeForUsleepCall / 1000 seconds.

Reimplemented from vpRobotSimulator.

Definition at line 302 of file vpRobotWireFrameSimulator.h.

References vpTime::minTimeForUsleepCall.

Referenced by vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().

void vpRobotWireFrameSimulator::setSingularityManagement ( const bool  sm)
inlineinherited

Set the parameter which enable or disable the singularity mangement

Definition at line 311 of file vpRobotWireFrameSimulator.h.

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

Set the current tool type.

Definition at line 136 of file vpViper850.h.

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

void vpSimulatorViper850::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/vpSimulatorViper850.h>
#include <visp/vpColVector.h>
#include <visp/vpMath.h>
int main()
{
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
}

Implements vpRobot.

Definition at line 822 of file vpSimulatorViper850.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpMatrix::getRows(), vpRobotWireFrameSimulator::jointLimit, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobotWireFrameSimulator::set_velocity(), vpRobot::setRobotFrame(), vpRobotWireFrameSimulator::setVelocityCalled, vpRobot::STATE_VELOCITY_CONTROL, vpERROR_TRACE, and vpRobotException::wrongStateError.

void vpRobotWireFrameSimulator::setVerbose ( bool  verbose)
inlineinherited

Activates extra printings when the robot reaches joint limits...

Definition at line 316 of file vpRobotWireFrameSimulator.h.

bool vpSimulatorViper850::singularityTest ( const vpColVector  q,
vpMatrix J 
)
protected

Test to detect if the robot is near one of its singularities.

The goal is to avoid the problems du to such configurations.

Definition at line 1798 of file vpSimulatorViper850.cpp.

References vpViper::a1, vpViper::a2, vpViper::a3, and vpViper::d4.

Referenced by computeArticularVelocity().

void vpSimulatorViper850::updateArticularPosition ( )
protectedvirtual

Method lauched by the thread to compute the position of the robot in the articular frame.

Implements vpRobotWireFrameSimulator.

Definition at line 437 of file vpSimulatorViper850.cpp.

References vpRobotWireFrameSimulator::cameraParam, compute_fMi(), computeArticularVelocity(), vpRobotWireFrameSimulator::constantSamplingTimeMode, vpMeterPixelConversion::convertPoint(), vpMath::deg(), vpDisplay::display(), vpRobotWireFrameSimulator::displayAllowed, vpDisplay::displayCamera(), vpDisplay::displayFrame(), vpDisplay::displayLine(), vpRobotWireFrameSimulator::displayType, vpDisplay::flush(), vpRobotWireFrameSimulator::fMi, vpRobotWireFrameSimulator::get_artCoord(), vpRobotWireFrameSimulator::get_artVel(), vpRobotWireFrameSimulator::get_displayBusy(), get_fMi(), vpPoint::get_x(), vpPoint::get_y(), vpRobotWireFrameSimulator::getExternalCameraPosition(), getExternalImage(), vpRobotSimulator::getSamplingTime(), vpColor::green, vpRobotWireFrameSimulator::I, isInJointLimit(), vpViper::joint_max, vpViper::joint_min, vpRobotWireFrameSimulator::jointLimit, vpRobotWireFrameSimulator::jointLimitArt, vpTime::measureTimeMs(), vpTime::minTimeForUsleepCall, vpRobotWireFrameSimulator::MODEL_3D, vpRobotWireFrameSimulator::MODEL_DH, vpColor::none, vpRobotWireFrameSimulator::robotStop, vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_displayBusy(), vpRobotWireFrameSimulator::setVelocityCalled, vpPoint::setWorldCoordinates(), vpRobotWireFrameSimulator::tcur, vpWireFrameSimulator::thickness_, vpRobotWireFrameSimulator::tprev, vpForwardProjection::track(), vpRobotWireFrameSimulator::verbose_, and vpTime::wait().

Member Data Documentation

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 111 of file vpRobot.h.

Referenced by vpRobot::operator=().

vpColVector vpRobotWireFrameSimulator::artCoord
protectedinherited

The articular coordinates

Definition at line 118 of file vpRobotWireFrameSimulator.h.

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

vpColVector vpRobotWireFrameSimulator::artVel
protectedinherited

The articular velocity

Definition at line 120 of file vpRobotWireFrameSimulator.h.

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

pthread_attr_t vpRobotWireFrameSimulator::attr
protectedinherited
bool vpWireFrameSimulator::blocked
protectedinherited

Definition at line 261 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::navigation().

bool vpWireFrameSimulator::blockedr
protectedinherited

Definition at line 258 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::navigation().

bool vpWireFrameSimulator::blockedt
protectedinherited

Definition at line 260 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::navigation().

bool vpWireFrameSimulator::blockedz
protectedinherited

Definition at line 259 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::navigation().

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

vpColor vpWireFrameSimulator::camColor
protectedinherited
float vpWireFrameSimulator::cameraFactor
protectedinherited
vpCameraParameters vpRobotWireFrameSimulator::cameraParam
protectedinherited
std::list<vpImagePoint> vpWireFrameSimulator::cameraTrajectory
protectedinherited
vpHomogeneousMatrix vpWireFrameSimulator::camMf2
protectedinherited
vpColor vpWireFrameSimulator::camTrajColor
protectedinherited
vpCameraTrajectoryDisplayType vpWireFrameSimulator::camTrajType
protectedinherited
vpHomogeneousMatrix vpWireFrameSimulator::cdMo
protectedinherited
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 getCameraParameters().

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

Definition at line 86 of file vpViper850.h.

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

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

bool vpRobotWireFrameSimulator::constantSamplingTimeMode
protectedinherited

Flag used to force the sampling time in the thread computing the robot's displacement to a constant value (samplingTime). It may be useful if the main thread (computing the features) is very time consumming. False by default.

Definition at line 171 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::updateArticularPosition(), and updateArticularPosition().

double vpViper::d1
protectedinherited
double vpViper::d6
protectedinherited
const double vpSimulatorViper850::defaultPositioningVelocity = 25.0
static

Definition at line 209 of file vpSimulatorViper850.h.

Referenced by init().

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(), init(), and vpRobotViper850::init().

double vpRobotSimulator::delta_t_
protectedinherited
vpColor vpWireFrameSimulator::desColor
protectedinherited
vpSceneDesiredObject vpWireFrameSimulator::desiredObject
protectedinherited
vpDisplayX vpRobotWireFrameSimulator::display
protectedinherited
bool vpRobotWireFrameSimulator::displayAllowed
protectedinherited
bool vpRobotWireFrameSimulator::displayBusy
protectedinherited

Definition at line 141 of file vpRobotWireFrameSimulator.h.

bool vpWireFrameSimulator::displayCameraTrajectory
protectedinherited

Definition at line 249 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::getExternalImage().

bool vpWireFrameSimulator::displayImageSimulator
protectedinherited
vpDisplayRobotType vpRobotWireFrameSimulator::displayType
protectedinherited
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=().

bool vpWireFrameSimulator::extCamChanged
protectedinherited

Definition at line 280 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::getExternalImage().

vpHomogeneousMatrix vpWireFrameSimulator::f2Mf
protectedinherited
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=().

vpHomogeneousMatrix vpWireFrameSimulator::fMc
protectedinherited

Definition at line 233 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::getExternalImage().

vpHomogeneousMatrix* vpRobotWireFrameSimulator::fMi
protectedinherited

Table containing all the homogeneous matrices between the reference frame of the robot and the frames you used to compute the Denavit-Hartenberg representation

If you use a camera at the end of the effector, the last homogeneous matrix has to be the one between the reference frame and the camera frame (fMc)

Definition at line 115 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::compute_fMi(), compute_fMi(), vpSimulatorAfma6::init(), init(), vpSimulatorAfma6::updateArticularPosition(), updateArticularPosition(), vpSimulatorAfma6::~vpSimulatorAfma6(), and ~vpSimulatorViper850().

std::list<vpHomogeneousMatrix> vpWireFrameSimulator::fMoList
protectedinherited
bool vpRobotWireFrameSimulator::jointLimit
protectedinherited
unsigned int vpRobotWireFrameSimulator::jointLimitArt
protectedinherited

Index of the joint which is in limit

Definition at line 148 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::updateArticularPosition(), and updateArticularPosition().

double vpRobot::maxRotationVelocity
protectedinherited
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.

pthread_mutex_t vpRobotWireFrameSimulator::mutex_artCoord
protectedinherited
pthread_mutex_t vpRobotWireFrameSimulator::mutex_artVel
protectedinherited
pthread_mutex_t vpRobotWireFrameSimulator::mutex_display
protectedinherited
pthread_mutex_t vpRobotWireFrameSimulator::mutex_fMi
protectedinherited
pthread_mutex_t vpRobotWireFrameSimulator::mutex_velocity
protectedinherited
unsigned int vpWireFrameSimulator::nbrPtLimit
protectedinherited

Definition at line 253 of file vpWireFrameSimulator.h.

Referenced by vpWireFrameSimulator::getExternalImage().

int vpRobot::nDof
protectedinherited

number of degrees of freedom

Definition at line 101 of file vpRobot.h.

Referenced by vpRobot::operator=().

vpSceneObject vpWireFrameSimulator::object
protectedinherited

Definition at line 239 of file vpWireFrameSimulator.h.

std::list<vpImageSimulator> vpWireFrameSimulator::objectImage
protectedinherited
vpImagePoint vpWireFrameSimulator::old_iPr
protectedinherited
vpImagePoint vpWireFrameSimulator::old_iPt
protectedinherited
vpImagePoint vpWireFrameSimulator::old_iPz
protectedinherited
std::list<vpHomogeneousMatrix> vpWireFrameSimulator::poseList
protectedinherited
vpCameraParameters::vpCameraParametersProjType vpViper850::projModel
protectedinherited

Definition at line 144 of file vpViper850.h.

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

double vpWireFrameSimulator::px_ext
protectedinherited
double vpWireFrameSimulator::py_ext
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().

vpHomogeneousMatrix vpWireFrameSimulator::refMo
protectedinherited

Definition at line 235 of file vpWireFrameSimulator.h.

Bound_scene* vpRobotWireFrameSimulator::robotArms
protectedinherited
bool vpRobotWireFrameSimulator::robotStop
protectedinherited
bool vpRobotWireFrameSimulator::setVelocityCalled
protectedinherited

Flag used to specify to the thread managing the robot displacements that the setVelocity() method has been called.

Definition at line 174 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::setPosition(), setPosition(), vpSimulatorAfma6::setVelocity(), setVelocity(), vpSimulatorAfma6::updateArticularPosition(), and updateArticularPosition().

bool vpRobotWireFrameSimulator::singularityManagement
protectedinherited

True if the singularity are automatically managed

Definition at line 150 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::computeArticularVelocity(), and computeArticularVelocity().

unsigned int vpRobotWireFrameSimulator::size_fMi
protectedinherited
double vpRobotWireFrameSimulator::tcur
protectedinherited

cpu time at the begining of the robot's movement

Definition at line 103 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::updateArticularPosition(), updateArticularPosition(), vpSimulatorAfma6::vpSimulatorAfma6(), and vpSimulatorViper850().

pthread_t vpRobotWireFrameSimulator::thread
protectedinherited
vpToolType vpViper850::tool_current
protectedinherited

Current tool in use.

Definition at line 138 of file vpViper850.h.

double vpRobotWireFrameSimulator::tprev
protectedinherited

cpu time at the end of the last robot's movement

Definition at line 105 of file vpRobotWireFrameSimulator.h.

Referenced by vpSimulatorAfma6::updateArticularPosition(), and updateArticularPosition().

vpColVector vpRobotWireFrameSimulator::velocity
protectedinherited

The velocity in the current frame (articular, camera or reference)

Definition at line 122 of file vpRobotWireFrameSimulator.h.

Referenced by vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().