Visual Servoing Platform  version 3.6.1 under development (2024-04-18)
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 ()
 

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 m_dh_model
 
vpHomogeneousMatrix m_cMe
 

Inherited functionalities from vpBiclops

void init (void)
 
void computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
vpHomogeneousMatrix computeMGD (const vpColVector &q) const
 
void computeMGD (const vpColVector &q, vpPoseVector &fPc) 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 &fPc) 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 dh_model=vpBiclops::DH1)
 
VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpBiclops &dummy)
 

Detailed Description

Jacobian, geometric model functionalities... for Biclops, pan, tilt head.

Two different Denavit-Hartenberg representations of the robot are implemented. As mentioned 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 61 of file vpBiclops.h.

Member Enumeration Documentation

◆ DenavitHartenbergModel

Two different Denavit-Hartenberg representations of the robot are implemented. As you can see in the next image, they differ in the orientation of the tilt axis.

Biclops PT models

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

Joint $a_i$ $d_i$ $\alpha_i$ $\theta_i$
1 0 0 $-\pi/2$ $q_1$
2 0 0 $ \pi/2$ $q_2 + \pi/2$

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

Joint $a_i$ $d_i$ $\alpha_i$ $\theta_i$
1 0 0 $ \pi/2$ $q_1$
2 0 0 $-\pi/2$ $q_2 - \pi/2$

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

Constructor & Destructor Documentation

◆ vpBiclops()

vpBiclops::vpBiclops ( void  )

Default constructor. Call init() that sets vpBiclops::DH1 Denavit-Hartenberg model.

Definition at line 166 of file vpBiclops.cpp.

References init().

◆ ~vpBiclops()

virtual vpBiclops::~vpBiclops ( )
inlinevirtual

Destructor that does nothing.

Definition at line 120 of file vpBiclops.h.

Member Function Documentation

◆ computeMGD() [1/3]

vpHomogeneousMatrix vpBiclops::computeMGD ( const vpColVector q) const

Return the direct geometric model of the camera: fMc

Warning
Provided for compatibility with previous versions. Use rather get_fMc(const vpColVector &).
Parameters
q: Joint 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 66 of file vpBiclops.cpp.

References computeMGD().

◆ computeMGD() [2/3]

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

Compute the direct geometric model of the camera: fMc

Warning
Provided for compatibility with previous versions. Use rather get_fMc(const vpColVector &, vpHomogeneousMatrix &).
Parameters
q: Joint 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 46 of file vpBiclops.cpp.

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

Referenced by computeMGD().

◆ computeMGD() [3/3]

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

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

Warning
Provided for compatibility with previous versions. Use rather get_fMc(const vpColVector &, vpPoseVector &).
Parameters
q: Joint position for pan and tilt axis.
fPc: 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 146 of file vpBiclops.cpp.

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

◆ get_cMe()

vpHomogeneousMatrix vpBiclops::get_cMe ( ) const
inline

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

Definition at line 193 of file vpBiclops.h.

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

◆ 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
[out]cVe: Twist transformation between camera and end effector frame to express a velocity skew from end effector frame in camera frame.

Definition at line 184 of file vpBiclops.cpp.

References vpVelocityTwistMatrix::buildFrom(), and m_cMe.

◆ get_eJe()

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
[in]q: Joint position for pan and tilt axis.
[out]eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Definition at line 211 of file vpBiclops.cpp.

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

Referenced by vpRobotBiclops::get_eJe().

◆ get_fJe()

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

Get the robot jacobian expressed in the robot reference frame

Parameters
[in]q: Joint position for pan and tilt axis.
[out]fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Definition at line 236 of file vpBiclops.cpp.

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

Referenced by vpRobotBiclops::get_fJe().

◆ get_fMc() [1/3]

vpHomogeneousMatrix vpBiclops::get_fMc ( const vpColVector q) const

Return the direct geometric model of the camera: fMc

Parameters
[in]q: Joint 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.

Definition at line 75 of file vpBiclops.cpp.

References get_fMc().

◆ get_fMc() [2/3]

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

Compute the direct geometric model of the camera: fMc

Parameters
[in]q: Joint position for pan and tilt axis.
[out]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 56 of file vpBiclops.cpp.

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

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

◆ get_fMc() [3/3]

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

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

Parameters
[in]q: Joint position for pan and tilt axis.
[out]fPc: Pose vector 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 156 of file vpBiclops.cpp.

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

◆ get_fMe()

vpHomogeneousMatrix vpBiclops::get_fMe ( const vpColVector q) const

Return the direct geometric model of the end effector: fMe

Parameters
[in]q: Joint 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 84 of file vpBiclops.cpp.

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

Referenced by computeMGD(), and get_fMc().

◆ getDenavitHartenbergModel()

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

Return the Denavit-Hartenberg representation used to model the head.

See also
vpBiclops::DenavitHartenbergModel

Definition at line 276 of file vpBiclops.h.

◆ init()

void vpBiclops::init ( void  )

Initialization.

  • By default vpBiclops::DH1 Denavit-Hartenberg model is selected.
  • Initialize also the default ${^c}{\bf M}_e$ transformation calling set_cMe().

    \[ {^c}{\bf M}_e = \left( \begin{matrix} 0 & 1 & 0 & 0 \\ -1 & 0 & 0 & h \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{matrix} \right) \]

Definition at line 168 of file vpBiclops.cpp.

References DH1, m_dh_model, and set_cMe().

Referenced by vpBiclops().

◆ set_cMe() [1/2]

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.

\[ {^c}{\bf M}_e = \left( \begin{matrix} 0 & 1 & 0 & 0 \\ -1 & 0 & 0 & h \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{matrix} \right) \]

Definition at line 186 of file vpBiclops.cpp.

References h, and m_cMe.

Referenced by init().

◆ set_cMe() [2/2]

void vpBiclops::set_cMe ( const vpHomogeneousMatrix cMe)
inline

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

Definition at line 300 of file vpBiclops.h.

◆ setDenavitHartenbergModel()

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

Set the Denavit-Hartenberg representation used to model the head.

Parameters
[in]dh_model: Denavit-Hartenberg model.
See also
vpBiclops::DenavitHartenbergModel
Examples
servoPioneerPanSegment3D.cpp.

Definition at line 307 of file vpBiclops.h.

Friends And Related Function Documentation

◆ operator<<

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

Set output stream with Biclops parameters.

Parameters
os: Output stream.
dummy: Not used.
Returns
Output stream with the Biclops parameters.

Definition at line 175 of file vpBiclops.cpp.

Member Data Documentation

◆ h

const float vpBiclops::h = 0.048f
static

Definition at line 102 of file vpBiclops.h.

Referenced by set_cMe().

◆ m_cMe

vpHomogeneousMatrix vpBiclops::m_cMe
protected

Camera frame to PT end-effector frame transformation.

Definition at line 109 of file vpBiclops.h.

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

◆ m_dh_model

DenavitHartenbergModel vpBiclops::m_dh_model
protected

Denavit-Hartenberg model.

Definition at line 108 of file vpBiclops.h.

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

◆ ndof

◆ panJointLimit

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

Pan axis +/- joint limit in rad.

Definition at line 103 of file vpBiclops.h.

Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().

◆ speedLimit

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

Pan and tilt axis max velocity in rad/s to perform a displacement.

Definition at line 105 of file vpBiclops.h.

Referenced by vpRobotBiclops::setVelocity().

◆ tiltJointLimit

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

Tilt axis +/- joint limit in rad.

Definition at line 104 of file vpBiclops.h.

Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().