ViSP  2.8.0

#include <vpBiclops.h>

+ Inheritance diagram for vpBiclops:

Public Types

enum  DenavitHartenbergModel { DH1, DH2 }
 

Public Member Functions

 vpBiclops (void)
 
void init (void)
 
void computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc)
 
vpHomogeneousMatrix computeMGD (const vpColVector &q)
 
void computeMGD (const vpColVector &q, vpPoseVector &fvc)
 
vpHomogeneousMatrix get_cMe () const
 
void get_cVe (vpVelocityTwistMatrix &_cVe)
 
void get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc)
 
void get_fMc (const vpColVector &q, vpPoseVector &fvc)
 
vpHomogeneousMatrix get_fMc (const vpColVector &q)
 
vpHomogeneousMatrix get_fMe (const vpColVector &q)
 
void get_eJe (const vpColVector &q, vpMatrix &eJe)
 
void get_fJe (const vpColVector &q, vpMatrix &fJe)
 
vpBiclops::DenavitHartenbergModel getDenavitHartenbergModel ()
 
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

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 78 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 119 of file vpBiclops.h.

Constructor & Destructor Documentation

vpBiclops::vpBiclops ( void  )

Default construtor. Call init().

Definition at line 287 of file vpBiclops.cpp.

References init().

Member Function Documentation

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

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 80 of file vpBiclops.cpp.

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

Referenced by computeMGD().

vpHomogeneousMatrix vpBiclops::computeMGD ( const vpColVector q)

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 126 of file vpBiclops.cpp.

References computeMGD().

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

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 246 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 154 of file vpBiclops.h.

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

void vpBiclops::get_cVe ( vpVelocityTwistMatrix cVe)

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 336 of file vpBiclops.cpp.

References vpVelocityTwistMatrix::buildFrom(), and cMe_.

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

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 389 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpMatrix::getRows(), vpMatrix::resize(), and vpERROR_TRACE.

Referenced by vpRobotBiclops::get_eJe().

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

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 431 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpMatrix::getRows(), vpMatrix::resize(), and vpERROR_TRACE.

Referenced by vpRobotBiclops::get_fJe().

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

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

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 267 of file vpBiclops.cpp.

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

vpHomogeneousMatrix vpBiclops::get_fMc ( const vpColVector q)

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 146 of file vpBiclops.cpp.

References get_fMc().

vpHomogeneousMatrix vpBiclops::get_fMe ( const vpColVector q)

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 166 of file vpBiclops.cpp.

References DH1, dh_model_, vpException::dimensionError, vpMatrix::getRows(), and vpERROR_TRACE.

Referenced by computeMGD(), and get_fMc().

vpBiclops::DenavitHartenbergModel vpBiclops::getDenavitHartenbergModel ( )
inline

Return the Denavit Hartenberg representation used to model the head.

See also
vpBiclops::DenavitHartenbergModel

Definition at line 172 of file vpBiclops.h.

void vpBiclops::init ( void  )

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

Definition at line 301 of file vpBiclops.cpp.

References 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 349 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 181 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 190 of file vpBiclops.h.

Friends And Related Function Documentation

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

Definition at line 312 of file vpBiclops.cpp.

Member Data Documentation

vpHomogeneousMatrix vpBiclops::cMe_
protected

Definition at line 139 of file vpBiclops.h.

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

DenavitHartenbergModel vpBiclops::dh_model_
protected

Definition at line 138 of file vpBiclops.h.

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

const float vpBiclops::h = 0.048f
static

Definition at line 130 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 132 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 134 of file vpBiclops.h.

Referenced by vpRobotBiclopsController::setPosition(), and vpRobotBiclops::setVelocity().

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

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

Definition at line 133 of file vpBiclops.h.

Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().