Afma4¶
- class Afma4(self)¶
Bases:
pybind11_object
Modelization 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 \(q_1^*, q_2^*,q_4^*, q_5^*\) are the variable joint positions.
\[\begin{split}\begin{tabular}{|c|c|c|c|c|} \hline Joint & $a_i$ & $d_i$ & $\alpha_i$ & $\theta_i$ \\\hline 1 & 0 & 0 & 0 & $q_1^*$ \\2 & $a_1$ & $q_2^*$ & $-\pi/2$ & 0 \\3 & 0 & $d_3$ & $\pi/2$ & 0 \\4 & 0 & $d_4$ & $-\pi/2$ & $q_4^*-\pi/2$ \\5 & 0 & 0 & 0 & $q_5^*$ \\\hline \end{tabular} \end{split}\]The forward kinematics of the robot is given by the homogeneous matrix \({^f}M_e\) which is implemented in get_fMe() .
\[\begin{split}{^f}M_e = \left[\begin{array}{cccc} c_1s_4c_5+s_1c_4c_5 & -c_1s_4s_5-s_1c_4s_5 & c_1c_4-s_1s_4 &a_1c_1-d_3s_1 \\s_1s_4c_5-c_1c_4c_5 & -s_1s_4s_5+c_1c_4s_5 & s_1c_4+c_1s_4 &a_1s_1+d_3c_1 \\-s_5 & -c_5 & d_4+q_2 \\0 & 0 & 0 & 1 \\\end{array} \right] \end{split}\]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() .
Default constructor.
Methods
Default constructor.
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
Get max joint values.
Get min joint values.
Get the geometric transformation between the camera frame and the end-effector frame.
Get the twist transformation from camera frame to end-effector frame.
Get the twist transformation from camera frame to the reference frame.
Get the robot jacobian expressed in the end-effector frame:
Get the robot jacobian expressed in the robot reference frame also called fix frame:
Get the inverse jacobian.
Overloaded function.
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
Does nothing for the moment.
Inherited Methods
Operators
__doc__
Default constructor.
__module__
__repr__
Attributes
__annotations__
njoint
- __init__(self)¶
Default constructor.
- getForwardKinematics(self, q: visp._visp.core.ColVector) visp._visp.core.HomogeneousMatrix ¶
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).
Note
See get_fMc(const vpColVector & q)
Note
See getInverseKinematics()
- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- Returns:
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame ( \({^f}M_c\) ) with:
\[{^f}M_c = {^f}M_e * {^e}M_c \]
- getJointMax(self) visp._visp.core.ColVector ¶
Get max joint values.
- Returns:
Maximal joint values for the 4 dof X, Y, A, B. Translation Y is expressed in meters. Rotations X, A and B in radians.
- getJointMin(self) visp._visp.core.ColVector ¶
Get min joint values.
- Returns:
Minimal joint values for the 4 dof X, Y, A, B. Translation Y is expressed in meters. Rotations X,A and B in radians.
- get_cMe(self, cMe: visp._visp.core.HomogeneousMatrix) None ¶
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.
- Parameters:
- cMe: visp._visp.core.HomogeneousMatrix¶
Transformation between the camera frame and the end-effector frame.
- get_cVe(self, cVe: visp._visp.core.VelocityTwistMatrix) None ¶
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.
- Parameters:
- cVe: visp._visp.core.VelocityTwistMatrix¶
Twist transformation.
- get_cVf(self, q: visp._visp.core.ColVector, cVf: visp._visp.core.VelocityTwistMatrix) None ¶
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.
- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- cVf: visp._visp.core.VelocityTwistMatrix¶
Twist transformation.
- get_eJe(self, q: visp._visp.core.ColVector, eJe: visp._visp.core.Matrix) None ¶
Get the robot jacobian expressed in the end-effector frame:
\[\begin{split}{^e}J_e = \left[\begin{array}{cccc} -c_5(a_1c_4+d_3s_4) & -s_5 & 0 & 0 \\s_5(a_1c_4+d_3s_4) & -c_5 & 0 & 0 \\a_1s_4-d_3c_4 & 0 & 0 & 0 \\-s_5 & 0 & -s_5 & 0 \\-c_5 & 0 & -c_5 & 0 \\0 & 0 & 0 & 1 \\\end{array} \right] \end{split}\]Note
See get_fJe()
- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- eJe: visp._visp.core.Matrix¶
Robot jacobian expressed in the end-effector frame, with:
\[\begin{split}{^e}J_e = \left[\begin{array}{cc} {^f}R_e^T & 0_{3 \times 3} \\0_{3 \times 3} & {^f}R_e^T \\\end{array} \right] {^f}J_e\end{split}\]
- get_fJe(self, q: visp._visp.core.ColVector, fJe: visp._visp.core.Matrix) None ¶
Get the robot jacobian expressed in the robot reference frame also called fix frame:
\[\begin{split}{^f}J_e = \left[\begin{array}{cccc} -a_1s_1-d_3c_1 & 0 & 0 & 0 \\a_1c_1-d_3s_1 & 0 & 0 & 0 \\0 & 1 & 0 & 0 \\0 & 0 & 0 & c_{14} \\0 & 0 & 0 & s_{14} \\1 & 0 & 1 & 0 \\\end{array} \right] \end{split}\]Note
See get_eJe() and get_fJe_inverse()
- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- fJe: visp._visp.core.Matrix¶
Robot jacobian expressed in the robot reference frame.
- get_fJe_inverse(self, q: visp._visp.core.ColVector, fJe_inverse: visp._visp.core.Matrix) None ¶
Get the inverse jacobian.
\[\begin{split}{^f}J_e^+ = \left[\begin{array}{cccccc} -(a_1s_1+d_3c_1)/(a_1^2+d_3^2) & (a_1c_1-d_3s_1)/(a_1^2+d_3^2) & 0&0&0&0 \\0 & 0 & 1 & 0 & 0 & 0 \\(a_1s_1+d_3c_1)/(a_1^2+d_3^2) & -(a_1c_1-d_3s_1)/(a_1^2+d_3^2) & 0&0&0&1 \\0 & 0 & 0 & c_{14} & s_{14} & 0 \\\end{array} \right] \end{split}\]Note
See get_eJe() and get_fJe()
- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- fJe_inverse: visp._visp.core.Matrix¶
Inverse robot jacobian expressed in the robot reference frame.
- get_fMc(*args, **kwargs)¶
Overloaded function.
get_fMc(self: visp._visp.robot.Afma4, q: visp._visp.core.ColVector) -> visp._visp.core.HomogeneousMatrix
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).
Note
See getForwardKinematics(const vpColVector & q)
- Parameters:
- q
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- Returns:
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame ( \({^f}M_c\) ) with:
\[{^f}M_c = {^f}M_e * {^e}M_c \]get_fMc(self: visp._visp.robot.Afma4, q: visp._visp.core.ColVector, fMc: visp._visp.core.HomogeneousMatrix) -> None
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.
- Parameters:
- q
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). 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 ( \({^f}M_c\) ) with:
\[{^f}M_c = {^f}M_e * {^e}M_c\]
- get_fMe(self, q: visp._visp.core.ColVector, fMe: visp._visp.core.HomogeneousMatrix) None ¶
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.
\[\begin{split}{^f}M_e = \left[\begin{array}{cccc} c_1s_4c_5+s_1c_4c_5 & -c_1s_4s_5-s_1c_4s_5 & c_1c_4-s_1s_4 &a_1c_1-d_3s_1 \\s_1s_4c_5-c_1c_4c_5 & -s_1s_4s_5+c_1c_4s_5 & s_1c_4+c_1s_4 &a_1s_1+d_3c_1 \\-s_5 & -c_5 & d_4+q_2 \\0 & 0 & 0 & 1 \\\end{array} \right] \end{split}\]- Parameters:
- q: visp._visp.core.ColVector¶
Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value \(q_1\) ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value \(q_2\) ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values \(q_4\) and \(q_5\) ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters.
- fMe: visp._visp.core.HomogeneousMatrix¶
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame ( \({^f}M_e\) ) with