Visual Servoing Platform
version 3.6.1 under development (2024-11-15)
|
#include <visp3/robot/vpPtu46.h>
Public Member Functions | |
vpPtu46 (void) | |
virtual | ~vpPtu46 () |
Static Public Attributes | |
static const unsigned int | ndof = 2 |
static const float | L = 0.0765f |
static const float | h = 0.068f |
Inherited functionalities from vpPtu46 | |
void | init (void) |
void | computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc) const |
vpHomogeneousMatrix | computeMGD (const vpColVector &q) const |
void | computeMGD (const vpColVector &q, vpPoseVector &r) const |
void | get_cMe (vpHomogeneousMatrix &_cMe) const |
void | get_cVe (vpVelocityTwistMatrix &_cVe) const |
void | get_eJe (const vpColVector &q, vpMatrix &eJe) const |
void | get_fJe (const vpColVector &q, vpMatrix &fJe) const |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpPtu46 &constant) |
Jacobian, geometric model functionalities... for ptu46, pan, tilt head from Directed Perception.
See http://www.DPerception.com for more details.
vpPtu46::vpPtu46 | ( | void | ) |
|
inlinevirtual |
vpHomogeneousMatrix vpPtu46::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 118 of file vpPtu46.cpp.
References computeMGD().
void vpPtu46::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 68 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), h, and L.
Referenced by computeMGD().
void vpPtu46::computeMGD | ( | const vpColVector & | q, |
vpPoseVector & | r | ||
) | const |
Compute the direct geometric model of the camera in terms of pose vector.
q | : Articular position for pan and tilt axis. |
r | : Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 136 of file vpPtu46.cpp.
References vpPoseVector::buildFrom(), computeMGD(), and vpHomogeneousMatrix::inverse().
void vpPtu46::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the 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.
cMe | : Homogeneous matrix between camera and end effector frame. |
Definition at line 208 of file vpPtu46.cpp.
References h, vpHomogeneousMatrix::inverse(), and L.
Referenced by vpRobotPtu46::get_cMe(), get_cVe(), and vpRobotPtu46::get_cVe().
void vpPtu46::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 express a velocity skew from end effector frame in camera frame. |
Definition at line 191 of file vpPtu46.cpp.
References vpVelocityTwistMatrix::buildFrom(), and get_cMe().
void vpPtu46::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 247 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), and vpArray2D< Type >::resize().
Referenced by vpRobotPtu46::get_eJe().
void vpPtu46::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 276 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), and vpArray2D< Type >::resize().
Referenced by vpRobotPtu46::get_fJe().
void vpPtu46::init | ( | void | ) |
Initialization. Here nothing to do.
Definition at line 164 of file vpPtu46.cpp.
Referenced by vpPtu46().
|
friend |
Definition at line 170 of file vpPtu46.cpp.
|
static |
Horizontal offset along the last joint, from last joint to camera frame.
Definition at line 80 of file vpPtu46.h.
Referenced by computeMGD(), and get_cMe().
|
static |
|
static |
Nombre d'articulations du robot. Number of dof
Definition at line 76 of file vpPtu46.h.
Referenced by vpRobotPtu46::getDisplacement(), vpRobotPtu46::getPosition(), vpRobotPtu46::getVelocity(), and vpRobotPtu46::readPositionFile().