Visual Servoing Platform  version 3.0.0
vpBiclops Class Reference

#include <visp3/robot/vpBiclops.h>

+ Inheritance diagram for vpBiclops:

Public Types

enum  DenavitHartenbergModel { DH1, DH2 }
 

Public Member Functions

 vpBiclops (void)
 
virtual ~vpBiclops ()
 
void init (void)
 
void computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
vpHomogeneousMatrix computeMGD (const vpColVector &q) const
 
void computeMGD (const vpColVector &q, vpPoseVector &fvc) const
 
vpHomogeneousMatrix get_cMe () const
 
void get_cVe (vpVelocityTwistMatrix &_cVe) const
 
void get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
void get_fMc (const vpColVector &q, vpPoseVector &fvc) const
 
vpHomogeneousMatrix get_fMc (const vpColVector &q) const
 
vpHomogeneousMatrix get_fMe (const vpColVector &q) const
 
void get_eJe (const vpColVector &q, vpMatrix &eJe) const
 
void get_fJe (const vpColVector &q, vpMatrix &fJe) const
 
vpBiclops::DenavitHartenbergModel getDenavitHartenbergModel () const
 
void set_cMe ()
 
void set_cMe (const vpHomogeneousMatrix &cMe)
 
void setDenavitHartenbergModel (vpBiclops::DenavitHartenbergModel m=vpBiclops::DH1)
 

Static Public Attributes

static const unsigned int ndof = 2
 
static const float h = 0.048f
 
static const float panJointLimit = (float)(M_PI)
 
static const float tiltJointLimit = (float)(M_PI/4.5)
 
static const float speedLimit = (float)(M_PI/3.0)
 

Protected Attributes

DenavitHartenbergModel dh_model_
 
vpHomogeneousMatrix cMe_
 

Friends

VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpBiclops &constant)
 

Detailed Description

Jacobian, geometric model functionnalities... for biclops, pan, tilt head.

Two different Denavit Hartenberg representations of the robot are implemented. As mentionned in vpBiclops::DenavitHartenbergModel they differ in the orientation of the tilt axis. Use setDenavitHartenbergModel() to select the representation.

See http://www.traclabs.com/tracbiclops.htm for more details concerning the hardware.

Definition at line 74 of file vpBiclops.h.

Member Enumeration Documentation

Two different Denavit Hartenberg representations of the robot are implemented. They differ in the orientation of the tilt axis.

The first representation, vpBiclops::DH1 is given by:

\[ \begin{tabular}{|c|c|c|c|c|} \hline Joint & $a_i$ & $d_i$ & $\alpha_i$ & $\theta_i$ \\ \hline 1 & 0 & 0 & $-\pi/2$ & $q_1^*$ \\ 2 & 0 & 0 & $ \pi/2$ & $q_2^* + \pi/2$ \\ \hline \end{tabular} \]

The second one, vpBiclops::DH2 is given by:

\[ \begin{tabular}{|c|c|c|c|c|} \hline Joint & $a_i$ & $d_i$ & $\alpha_i$ & $\theta_i$ \\ \hline 1 & 0 & 0 & $ \pi/2$ & $q_1^*$ \\ 2 & 0 & 0 & $ -\pi/2$ & $q_2^* - \pi/2$ \\ \hline \end{tabular} \]

where $q_1^*, q_2^*$ are respectively the pan and tilt joint positions.

In those representations, the pan is oriented from left to right, while the tilt is oriented

Enumerator
DH1 

First Denavit Hartenberg representation.

DH2 

Second Denavit Hartenberg representation.

Definition at line 115 of file vpBiclops.h.

Constructor & Destructor Documentation

vpBiclops::vpBiclops ( void  )

Default construtor. Call init().

Definition at line 283 of file vpBiclops.cpp.

References init().

virtual vpBiclops::~vpBiclops ( )
inlinevirtual

Destructor that does nothing.

Definition at line 140 of file vpBiclops.h.

Member Function Documentation

void vpBiclops::computeMGD ( const vpColVector q,
vpHomogeneousMatrix fMc 
) const

Compute the direct geometric model of the camera: fMc

Warning
Provided for compatibilty with previous versions. Use rather get_fMc(const vpColVector &, vpHomogeneousMatrix &).
Parameters
q: Articular position for pan and tilt axis.
fMc: Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame.
See also
get_fMc(const vpColVector &, vpHomogeneousMatrix &)

Definition at line 76 of file vpBiclops.cpp.

References cMe_, get_fMe(), vpHomogeneousMatrix::inverse(), and vpCDEBUG.

Referenced by computeMGD().

vpHomogeneousMatrix vpBiclops::computeMGD ( const vpColVector q) const

Return the direct geometric model of the camera: fMc

Warning
Provided for compatibilty with previous versions. Use rather get_fMc(const vpColVector &).
Parameters
q: Articular position for pan and tilt axis.
Returns
fMc, the homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame.
See also
get_fMc(const vpColVector &)

Definition at line 122 of file vpBiclops.cpp.

References computeMGD().

void vpBiclops::computeMGD ( const vpColVector q,
vpPoseVector fvc 
) const

Compute the direct geometric model of the camera in terms of pose vector.

Warning
Provided for compatibilty with previous versions. Use rather get_fMc(const vpColVector &, vpPoseVector &).
Parameters
q: Articular position for pan and tilt axis.
fvc: Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame.
See also
get_fMc(const vpColVector &, vpPoseVector &)

Definition at line 242 of file vpBiclops.cpp.

References vpPoseVector::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().

vpHomogeneousMatrix vpBiclops::get_cMe ( ) const
inline

Return the tranformation ${^c}{\bf M}_e$ between the camera frame and the end effector frame.

Definition at line 152 of file vpBiclops.h.

Referenced by vpRobotBiclops::get_cMe(), and vpRobotBiclops::get_cVe().

void vpBiclops::get_cVe ( vpVelocityTwistMatrix cVe) const

Get the twist matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.

Parameters
cVe: Twist transformation between camera and end effector frame to expess a velocity skew from end effector frame in camera frame.

Definition at line 332 of file vpBiclops.cpp.

References vpVelocityTwistMatrix::buildFrom(), and cMe_.

void vpBiclops::get_eJe ( const vpColVector q,
vpMatrix eJe 
) const

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

Warning
Re is not the embedded camera frame. It corresponds to the frame associated to the tilt axis (see also get_cMe).
Parameters
q: Articular position for pan and tilt axis.
eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Definition at line 385 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.

Referenced by vpRobotBiclops::get_eJe().

void vpBiclops::get_fJe ( const vpColVector q,
vpMatrix fJe 
) const

Get the robot jacobian expressed in the robot reference frame

Parameters
q: Articular position for pan and tilt axis.
fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Definition at line 425 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.

Referenced by vpRobotBiclops::get_fJe().

void vpBiclops::get_fMc ( const vpColVector q,
vpHomogeneousMatrix fMc 
) const

Compute the direct geometric model of the camera: fMc

Parameters
q: Articular position for pan and tilt axis.
fMc: Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame.

Definition at line 97 of file vpBiclops.cpp.

References cMe_, get_fMe(), vpHomogeneousMatrix::inverse(), and vpCDEBUG.

Referenced by computeMGD(), get_fMc(), and vpRobotBiclops::getDisplacement().

void vpBiclops::get_fMc ( const vpColVector q,
vpPoseVector fvc 
) const

Compute the direct geometric model of the camera in terms of pose vector.

Parameters
q: Articular position for pan and tilt axis.
fvc: Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame.

Definition at line 263 of file vpBiclops.cpp.

References vpPoseVector::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().

vpHomogeneousMatrix vpBiclops::get_fMc ( const vpColVector q) const

Return the direct geometric model of the camera: fMc

Parameters
q: Articular position for pan and tilt axis.
Returns
fMc, the homogeneous matrix corresponding to the direct geometric model of the camera. Discribes the transformation between the robot reference frame (called fixed) and the camera frame.

Definition at line 142 of file vpBiclops.cpp.

References get_fMc().

vpHomogeneousMatrix vpBiclops::get_fMe ( const vpColVector q) const

Return the direct geometric model of the end effector: fMe

Parameters
q: Articular position for pan and tilt axis.
Returns
fMe, the homogeneous matrix corresponding to the direct geometric model of the end effector. Describes the transformation between the robot reference frame (called fixed) and the end effector frame.

Definition at line 162 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpArray2D< Type >::getRows(), and vpERROR_TRACE.

Referenced by computeMGD(), and get_fMc().

vpBiclops::DenavitHartenbergModel vpBiclops::getDenavitHartenbergModel ( ) const
inline

Return the Denavit Hartenberg representation used to model the head.

See also
vpBiclops::DenavitHartenbergModel

Definition at line 170 of file vpBiclops.h.

void vpBiclops::init ( void  )

Initialization. Set the default ${^c}{\bf M}_e$ transformation.

Definition at line 298 of file vpBiclops.cpp.

References DH1, dh_model_, and set_cMe().

Referenced by vpBiclops().

void vpBiclops::set_cMe ( )

Set the default homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.

Definition at line 345 of file vpBiclops.cpp.

References cMe_, h, and vpHomogeneousMatrix::inverse().

Referenced by init().

void vpBiclops::set_cMe ( const vpHomogeneousMatrix cMe)
inline

Set the transformation between the camera frame and the end effector frame.

Definition at line 179 of file vpBiclops.h.

void vpBiclops::setDenavitHartenbergModel ( vpBiclops::DenavitHartenbergModel  m = vpBiclops::DH1)
inline

Set the Denavit Hartenberg representation used to model the head.

See also
vpBiclops::DenavitHartenbergModel
Examples:
servoPioneerPanSegment3D.cpp.

Definition at line 188 of file vpBiclops.h.

Friends And Related Function Documentation

VISP_EXPORT std::ostream& operator<< ( std::ostream &  os,
const vpBiclops constant 
)
friend

Definition at line 310 of file vpBiclops.cpp.

Member Data Documentation

vpHomogeneousMatrix vpBiclops::cMe_
protected

Definition at line 135 of file vpBiclops.h.

Referenced by computeMGD(), get_cVe(), get_fMc(), and set_cMe().

DenavitHartenbergModel vpBiclops::dh_model_
protected

Definition at line 134 of file vpBiclops.h.

Referenced by get_eJe(), get_fJe(), get_fMe(), and init().

const float vpBiclops::h = 0.048f
static

Definition at line 126 of file vpBiclops.h.

Referenced by set_cMe().

const float vpBiclops::panJointLimit = (float)(M_PI)
static

Pan range (in rad): from -panJointLimit to + panJointLimit

Definition at line 128 of file vpBiclops.h.

Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().

const float vpBiclops::speedLimit = (float)(M_PI/3.0)
static

Maximum speed (in rad/s) to perform a displacement

Definition at line 130 of file vpBiclops.h.

Referenced by vpRobotBiclops::setVelocity().

const float vpBiclops::tiltJointLimit = (float)(M_PI/4.5)
static

Tilt range (in rad): from -tiltJointLimit to + tiltJointLimit

Definition at line 129 of file vpBiclops.h.

Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().