ViSP
2.10.0
|
#include <vpBiclops.h>
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) |
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.
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:
The second one, vpBiclops::DH2 is given by:
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 119 of file vpBiclops.h.
vpBiclops::vpBiclops | ( | void | ) |
|
inlinevirtual |
Destructor that does nothing.
Definition at line 144 of file vpBiclops.h.
void vpBiclops::computeMGD | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
Compute the direct geometric model of the camera: fMc
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 80 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
q | : Articular position for pan and tilt axis. |
Definition at line 126 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.
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 246 of file vpBiclops.cpp.
References vpPoseVector::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().
|
inline |
Return the tranformation between the camera frame and the end effector frame.
Definition at line 156 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.
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 | ||
) | const |
Get the robot jacobian expressed in the end-effector frame.
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 | ||
) | const |
Get the robot jacobian expressed in the robot reference frame
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 429 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 | ||
) | const |
Compute the direct geometric model of the camera: fMc
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 | ||
) | const |
Compute the direct geometric model of the camera in terms of pose vector.
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 | ) | const |
Return the direct geometric model of the camera: fMc
q | : Articular position for pan and tilt axis. |
Definition at line 146 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
q | : Articular position for pan and tilt axis. |
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().
|
inline |
Return the Denavit Hartenberg representation used to model the head.
Definition at line 174 of file vpBiclops.h.
void vpBiclops::init | ( | void | ) |
Initialization. Set the default transformation.
Definition at line 302 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 349 of file vpBiclops.cpp.
References cMe_, h, and vpHomogeneousMatrix::inverse().
Referenced by init().
|
inline |
Set the transformation between the camera frame and the end effector frame.
Definition at line 183 of file vpBiclops.h.
|
inline |
Set the Denavit Hartenberg representation used to model the head.
Definition at line 192 of file vpBiclops.h.
|
friend |
Definition at line 314 of file vpBiclops.cpp.
|
protected |
Definition at line 139 of file vpBiclops.h.
Referenced by computeMGD(), get_cVe(), get_fMc(), and set_cMe().
|
protected |
|
static |
Definition at line 130 of file vpBiclops.h.
Referenced by set_cMe().
|
static |
Number of dof
Definition at line 127 of file vpBiclops.h.
Referenced by vpRobotBiclopsController::getActualPosition(), vpRobotBiclopsController::getActualVelocity(), vpRobotBiclops::getDisplacement(), vpRobotBiclopsController::getPosition(), vpRobotBiclops::getPosition(), vpRobotBiclopsController::getVelocity(), vpRobotBiclops::getVelocity(), vpRobotBiclops::init(), vpRobotBiclops::readPositionFile(), vpRobotBiclopsController::readShm(), vpRobotBiclopsController::setPosition(), vpRobotBiclopsController::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotBiclops::stopMotion(), vpRobotBiclopsController::vpRobotBiclopsController(), vpRobotBiclops::vpRobotBiclopsSpeedControlLoop(), and vpRobotBiclopsController::writeShm().
|
static |
Pan range (in rad): from -panJointLimit to + panJointLimit
Definition at line 132 of file vpBiclops.h.
Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().
|
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().
|
static |
Tilt range (in rad): from -tiltJointLimit to + tiltJointLimit
Definition at line 133 of file vpBiclops.h.
Referenced by vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().