Visual Servoing Platform
version 3.6.1 under development (2024-11-14)
|
#include <visp3/robot/vpBiclops.h>
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) |
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 63 of file vpBiclops.h.
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.
The first representation, vpBiclops::DH1 is given by:
Joint | ||||
---|---|---|---|---|
1 | 0 | 0 | ||
2 | 0 | 0 |
The second one, vpBiclops::DH2 is given by:
Joint | ||||
---|---|---|---|---|
1 | 0 | 0 | ||
2 | 0 | 0 |
where 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 94 of file vpBiclops.h.
vpBiclops::vpBiclops | ( | void | ) |
Default constructor. Call init() that sets vpBiclops::DH1 Denavit-Hartenberg model.
Definition at line 167 of file vpBiclops.cpp.
References init().
|
inlinevirtual |
Destructor that does nothing.
Definition at line 122 of file vpBiclops.h.
vpHomogeneousMatrix vpBiclops::computeMGD | ( | const vpColVector & | q | ) | const |
Return the direct geometric model of the camera: fMc
q | : Joint position for pan and tilt axis. |
Definition at line 67 of file vpBiclops.cpp.
References computeMGD().
void vpBiclops::computeMGD | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
Compute the direct geometric model of the camera: fMc
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. |
Definition at line 47 of file vpBiclops.cpp.
References get_fMe(), vpHomogeneousMatrix::inverse(), and m_cMe.
Referenced by computeMGD().
void vpBiclops::computeMGD | ( | const vpColVector & | q, |
vpPoseVector & | fPc | ||
) | const |
Compute the direct geometric model of the camera in terms of pose vector.
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. |
Definition at line 147 of file vpBiclops.cpp.
References vpPoseVector::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().
|
inline |
Return the transformation between the camera frame and the end effector frame.
Definition at line 195 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.
[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 185 of file vpBiclops.cpp.
References vpVelocityTwistMatrix::buildFrom(), and m_cMe.
void vpBiclops::get_eJe | ( | const vpColVector & | q, |
vpMatrix & | eJe | ||
) | const |
Get the robot jacobian expressed in the end-effector frame.
[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 212 of file vpBiclops.cpp.
References DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), m_dh_model, and vpArray2D< Type >::resize().
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
[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 237 of file vpBiclops.cpp.
References DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), m_dh_model, and vpArray2D< Type >::resize().
Referenced by vpRobotBiclops::get_fJe().
vpHomogeneousMatrix vpBiclops::get_fMc | ( | const vpColVector & | q | ) | const |
Return the direct geometric model of the camera: fMc
[in] | q | : Joint position for pan and tilt axis. |
Definition at line 76 of file vpBiclops.cpp.
References get_fMc().
void vpBiclops::get_fMc | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
Compute the direct geometric model of the camera: fMc
[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 57 of file vpBiclops.cpp.
References get_fMe(), vpHomogeneousMatrix::inverse(), and m_cMe.
Referenced by computeMGD(), get_fMc(), and vpRobotBiclops::getDisplacement().
void vpBiclops::get_fMc | ( | const vpColVector & | q, |
vpPoseVector & | fPc | ||
) | const |
Compute the direct geometric model of the camera in terms of pose vector.
[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 157 of file vpBiclops.cpp.
References vpPoseVector::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().
vpHomogeneousMatrix vpBiclops::get_fMe | ( | const vpColVector & | q | ) | const |
Return the direct geometric model of the end effector: fMe
[in] | q | : Joint position for pan and tilt axis. |
Definition at line 85 of file vpBiclops.cpp.
References DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), and m_dh_model.
Referenced by computeMGD(), and get_fMc().
|
inline |
Return the Denavit-Hartenberg representation used to model the head.
Definition at line 278 of file vpBiclops.h.
void vpBiclops::init | ( | void | ) |
Initialization.
Definition at line 169 of file vpBiclops.cpp.
References DH1, m_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 187 of file vpBiclops.cpp.
Referenced by init().
|
inline |
Set the transformation between the camera frame and the end effector frame.
Definition at line 302 of file vpBiclops.h.
|
inline |
Set the Denavit-Hartenberg representation used to model the head.
[in] | dh_model | : Denavit-Hartenberg model. |
Definition at line 309 of file vpBiclops.h.
|
friend |
Set output stream with Biclops parameters.
os | : Output stream. |
dummy | : Not used. |
Definition at line 176 of file vpBiclops.cpp.
|
static |
Definition at line 104 of file vpBiclops.h.
Referenced by set_cMe().
|
protected |
Camera frame to PT end-effector frame transformation.
Definition at line 111 of file vpBiclops.h.
Referenced by computeMGD(), get_cVe(), get_fMc(), and set_cMe().
|
protected |
|
static |
Number of dof.
Definition at line 101 of file vpBiclops.h.
Referenced by vpRobotBiclops::getDisplacement(), vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotBiclops::init(), vpRobotBiclops::readPositionFile(), vpRobotBiclops::setVelocity(), vpRobotBiclops::stopMotion(), and vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().
|
static |
Pan axis +/- joint limit in rad.
Definition at line 105 of file vpBiclops.h.
Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().
|
static |
Pan and tilt axis max velocity in rad/s to perform a displacement.
Definition at line 107 of file vpBiclops.h.
Referenced by vpRobotBiclops::setVelocity().
|
static |
Tilt axis +/- joint limit in rad.
Definition at line 106 of file vpBiclops.h.
Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().