ViSP
2.10.0
|
#include <vpAfma4.h>
Public Member Functions | |
vpAfma4 () | |
virtual | ~vpAfma4 () |
void | init (void) |
vpHomogeneousMatrix | getForwardKinematics (const vpColVector &q) const |
vpHomogeneousMatrix | get_fMc (const vpColVector &q) const |
void | get_fMe (const vpColVector &q, vpHomogeneousMatrix &fMe) const |
void | get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const |
void | get_cMe (vpHomogeneousMatrix &cMe) const |
void | get_cVe (vpVelocityTwistMatrix &cVe) const |
void | get_cVf (const vpColVector &q, vpVelocityTwistMatrix &cVf) const |
void | get_eJe (const vpColVector &q, vpMatrix &eJe) const |
void | get_fJe (const vpColVector &q, vpMatrix &fJe) const |
void | get_fJe_inverse (const vpColVector &q, vpMatrix &fJe_inverse) const |
vpColVector | getJointMin () const |
vpColVector | getJointMax () const |
Static Public Attributes | |
static const unsigned int | njoint = 4 |
Protected Attributes | |
double | _a1 |
double | _d3 |
double | _d4 |
double | _joint_max [4] |
double | _joint_min [4] |
vpTranslationVector | _etc |
vpRxyzVector | _erc |
vpHomogeneousMatrix | _eMc |
Friends | |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpAfma4 &afma4) |
Modelisation of Irisa's cylindrical robot named Afma4.
This robot has five degrees of freedom, but only four motorized joints (joint 3 is not motorized). Joint 2 and 3 are prismatic. The other ones are revolute joints.
The non modified Denavit-Hartenberg representation of the robot is given in the table below, where are the variable joint positions.
The forward kinematics of the robot is given by the homogeneous matrix which is implemented in get_fMe().
The robot forward jacobian used to compute the cartesian velocities from joint ones is given and implemented in get_fJe() and get_eJe().
The robot inverse jacobian used to compute the joint velocities from cartesian ones are given and implemented in get_fJe_inverse().
vpAfma4::vpAfma4 | ( | ) |
Default constructor.
Definition at line 71 of file vpAfma4.cpp.
References _a1, _d3, _d4, _eMc, _erc, _etc, _joint_max, _joint_min, vpHomogeneousMatrix::buildFrom(), and init().
|
inlinevirtual |
void vpAfma4::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the geometric transformation between the camera frame and the end-effector frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by hand or by calibration.
cMe | : Transformation between the camera frame and the end-effector frame. |
Definition at line 324 of file vpAfma4.cpp.
References _eMc, and vpHomogeneousMatrix::inverse().
Referenced by vpRobotAfma4::get_cMe(), get_cVe(), and vpRobotAfma4::get_cVe().
void vpAfma4::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) | const |
Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.
cVe | : Twist transformation. |
Definition at line 339 of file vpAfma4.cpp.
References vpVelocityTwistMatrix::buildFrom(), and get_cMe().
void vpAfma4::get_cVf | ( | const vpColVector & | q, |
vpVelocityTwistMatrix & | cVf | ||
) | const |
Get the twist transformation from camera frame to the reference frame. This transformation allows to compute a velocity expressed in the reference frame into the camera frame.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
cVf | : Twist transformation. |
Definition at line 368 of file vpAfma4.cpp.
References vpVelocityTwistMatrix::buildFrom(), get_fMc(), and vpHomogeneousMatrix::inverse().
Referenced by vpRobotAfma4::get_cVf().
void vpAfma4::get_eJe | ( | const vpColVector & | q, |
vpMatrix & | eJe | ||
) | const |
Get the robot jacobian expressed in the end-effector frame:
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
eJe | : Robot jacobian expressed in the end-effector frame, with:
|
Definition at line 416 of file vpAfma4.cpp.
References _a1, _d3, and vpMatrix::resize().
Referenced by vpRobotAfma4::get_eJe().
void vpAfma4::get_fJe | ( | const vpColVector & | q, |
vpMatrix & | fJe | ||
) | const |
Get the robot jacobian expressed in the robot reference frame also called fix frame:
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 470 of file vpAfma4.cpp.
References _a1, _d3, and vpMatrix::resize().
Referenced by vpRobotAfma4::get_fJe().
void vpAfma4::get_fJe_inverse | ( | const vpColVector & | q, |
vpMatrix & | fJe_inverse | ||
) | const |
Get the inverse jacobian.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fJe_inverse | : Inverse robot jacobian expressed in the robot reference frame. |
Definition at line 526 of file vpAfma4.cpp.
References _a1, _d3, and vpMatrix::resize().
Referenced by vpRobotAfma4::setVelocity().
vpHomogeneousMatrix vpAfma4::get_fMc | ( | const vpColVector & | q | ) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
Definition at line 190 of file vpAfma4.cpp.
Referenced by get_cVf(), getForwardKinematics(), vpRobotAfma4::getPosition(), and vpRobotAfma4::getVelocity().
void vpAfma4::get_fMc | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fMc | : The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame ( ) with:
|
Definition at line 225 of file vpAfma4.cpp.
void vpAfma4::get_fMe | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMe | ||
) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the end effector with respect to the base frame given the articular positions of all the four variable joints.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fMe | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame ( ) with |
Definition at line 273 of file vpAfma4.cpp.
Referenced by get_fMc(), and vpRobotAfma4::setVelocity().
vpHomogeneousMatrix vpAfma4::getForwardKinematics | ( | const vpColVector & | q | ) | const |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
This method is the same than get_fMc(const vpColVector & q).
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
Definition at line 152 of file vpAfma4.cpp.
References get_fMc().
vpColVector vpAfma4::getJointMax | ( | ) | const |
Get max joint values.
Definition at line 579 of file vpAfma4.cpp.
References _joint_max.
vpColVector vpAfma4::getJointMin | ( | ) | const |
Get min joint values.
Definition at line 562 of file vpAfma4.cpp.
References _joint_min.
void vpAfma4::init | ( | void | ) |
|
friend |
Print on the output stream os the robot parameters (joint min/max, distance between axis 5 and 6, coupling factor between axis 5 and 6, hand-to-eye homogeneous matrix.
os | : Output stream. |
afma4 | : Robot parameters. |
Definition at line 598 of file vpAfma4.cpp.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Definition at line 149 of file vpAfma4.h.
Referenced by getJointMax(), vpRobotAfma4::init(), and vpAfma4().
|
protected |
Definition at line 150 of file vpAfma4.h.
Referenced by getJointMin(), vpRobotAfma4::init(), and vpAfma4().
|
static |
Number of joint.
Definition at line 142 of file vpAfma4.h.
Referenced by vpRobotAfma4::get_cVf(), vpRobotAfma4::get_eJe(), vpRobotAfma4::get_fJe(), vpRobotAfma4::getDisplacement(), vpRobotAfma4::getPosition(), vpRobotAfma4::getVelocity(), vpRobotAfma4::setPosition(), and vpRobotAfma4::setVelocity().