Viper¶
- class Viper(self)¶
Bases:
pybind11_object
Modelization of the ADEPT Viper robot.
<unparsed image <doxmlparser.compound.docImageType object at 0x7fd019ea7d90>>
The non modified Denavit-Hartenberg representation of the robot is given in the table below, where \(q_1^*, \ldots, q_6^*\) 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 & $a_1$ & $d_1$ & $-\pi/2$ & $q_1^*$ \\2 & $a_2$ & 0 & 0 & $q_2^*$ \\3 & $a_3$ & 0 & $-\pi/2$ & $q_3^* - \pi$ \\4 & 0 & $d_4$ & $\pi/2$ & $q_4^*$ \\5 & 0 & 0 & $-\pi/2$ & $q_5^*$ \\6 & 0 & 0 & 0 & $q_6^*-\pi$ \\7 & 0 & $d_6$ & 0 & 0 \\\hline \end{tabular} \end{split}\]In this modelization, different frames have to be considered.
\({\cal F}_f\) : the reference frame, also called world frame
\({\cal F}_w\) : the wrist frame located at the intersection of the last three rotations, with \(^f{\bf M}_w = ^0{\bf M}_6\)
\({\cal F}_e\) : the end-effector frame located at the interface of the two tool changers, with \(^f{\bf M}_e = 0{\bf M}_7\)
\({\cal F}_c\) : the camera or tool frame, with \(^f{\bf M}_c = ^f{\bf M}_e \; ^e{\bf M}_c\) where \(^e{\bf M}_c\) is the result of a calibration stage. We can also consider a custom tool TOOL_CUSTOM and set this during robot initialisation or using set_eMc() .
\({\cal F}_s\) : the force/torque sensor frame, with \(d7=0.0666\) .
The forward kinematics of the robot is implemented in get_fMw() , get_fMe() and get_fMc() .
The robot forward jacobian used to compute the cartesian velocities from joint ones is given and implemented in get_fJw() , get_fJe() and get_eJe() .
Default constructor.
Methods
Default constructor.
Return the coupling factor between join 5 and joint 6.
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
Compute the inverse kinematics (inverse geometric model).
Compute the inverse kinematics (inverse geometric model).
Get maximal joint values.
Get minimal joint values.
Get the geometric transformation between the camera frame and the end-effector frame.
Get the twist transformation \(^c{\bf V}_e\) from camera frame to end-effector frame.
Get the robot jacobian \({^e}{\bf J}_e\) which gives the velocity of the origin of the end-effector frame expressed in end-effector frame.
Get the geometric transformation between the end-effector frame and the camera frame.
Get the geometric transformation between the end-effector frame and the force/torque sensor frame.
Get the robot jacobian \({^f}{\bf J}_e\) which gives the velocity of the origin of the end-effector frame expressed in the robot reference frame also called fix frame.
Get the robot jacobian \({^f}{\bf J}_w\) which express the velocity of the origin of the wrist frame in the robot reference frame also called fix frame.
Overloaded function.
Compute the forward kinematics (direct geometric model) as an homogeneous matrix \({^f}{\bf M}_e\) .
Compute the transformation between the fix frame and the wrist frame.
Return the transformation between the wrist frame and the end-effector.
Overloaded function.
Inherited Methods
Operators
__annotations__
__doc__
Default constructor.
__module__
__repr__
Attributes
__annotations__
njoint
- __init__(self)¶
Default constructor.
- getCoupl56(self) float ¶
Return the coupling factor between join 5 and joint 6.
This factor should be only useful when motor positions are considered. Since the positions returned by the robot are joint positions which takes into account the coupling factor, it has not to be considered in the modelization of the robot.
- 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 six joint positions.
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¶
A six dimension vector corresponding to the robot joint positions expressed in radians.
- Returns:
The homogeneous matrix \(^f{\bf M}_c\) corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame.
- getInverseKinematics(self, fMc: visp._visp.core.HomogeneousMatrix, q: visp._visp.core.ColVector, verbose: bool = false) int ¶
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
The code below shows how to compute the inverse geometric model:
vpColVector q1(6), q2(6); vpHomogeneousMatrix fMc; vpViper robot; // Get the current joint position of the robot robot.getPosition(vpRobot::ARTICULAR_FRAME, q1); // Compute the pose of the camera in the reference frame using the // direct geometric model fMc = robot.getForwardKinematics(q1); // this is similar to fMc = robot.get_fMc(q1); // or robot.get_fMc(q1, fMc); // Compute the inverse geometric model int nbsol; // number of solutions (0, 1 to 8) of the inverse geometric model // get the nearest solution to the current joint position nbsol = robot.getInverseKinematics(fMc, q1); if (nbsol == 0) std::cout << "No solution of the inverse geometric model " << std::endl; else if (nbsol >= 1) std::cout << "Nearest solution: " << q1 << std::endl;
Note
See getForwardKinematics() , getInverseKinematicsWrist
- Parameters:
- fMc: visp._visp.core.HomogeneousMatrix¶
Homogeneous matrix \(^f{\bf M}_c\) describing the transformation from base frame to the camera frame.
- q: visp._visp.core.ColVector¶
In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to \(^f{\bf M}_c\) .
- verbose: bool = false¶
Add extra printings.
- Returns:
Add printings if no solution was found.The number of solutions (1 to 8) of the inverse geometric model. O, if no solution can be found.
- getInverseKinematicsWrist(self, fMw: visp._visp.core.HomogeneousMatrix, q: visp._visp.core.ColVector, verbose: bool = false) int ¶
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
The code below shows how to compute the inverse geometric model:
vpColVector q1(6), q2(6); vpHomogeneousMatrix fMw; vpViper robot; // Get the current joint position of the robot robot.getPosition(vpRobot::ARTICULAR_FRAME, q1); // Compute the pose of the wrist in the reference frame using the // direct geometric model robot.get_fMw(q1, fMw); // Compute the inverse geometric model int nbsol; // number of solutions (0, 1 to 8) of the inverse geometric model // get the nearest solution to the current joint position nbsol = robot.getInverseKinematicsWrist(fMw, q1); if (nbsol == 0) std::cout << "No solution of the inverse geometric model " << std::endl; else if (nbsol >= 1) std::cout << "Nearest solution: " << q1 << std::endl;
Note
See getForwardKinematics() , getInverseKinematics()
- Parameters:
- fMw: visp._visp.core.HomogeneousMatrix¶
Homogeneous matrix \(^f{\bf M}_w\) describing the transformation from base frame to the wrist frame.
- q: visp._visp.core.ColVector¶
In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to \(^f{\bf M}_w\) .
- verbose: bool = false¶
Add extra printings.
- Returns:
Add printings if no solution was found.The number of solutions (1 to 8) of the inverse geometric model. O, if no solution can be found.
- getJointMax(self) visp._visp.core.ColVector ¶
Get maximal joint values.
- Returns:
A 6-dimension vector that contains the maximal joint values for the 6 dof. All the values are expressed in radians.
- getJointMin(self) visp._visp.core.ColVector ¶
Get minimal joint values.
- Returns:
A 6-dimension vector that contains the minimal joint values for the 6 dof. All the values are expressed 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 calibration.
Note
See get_eMc()
- 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 \(^c{\bf V}_e\) from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.
\[\begin{split}^c{\bf V}_e = \left(\begin{array}{cc} ^c{\bf R}_e & [^c{\bf t}_e]_\times ^c{\bf R}_e\\{\bf 0}_{3\times 3} & ^c{\bf R}_e \end{array} \right) \end{split}\]- Parameters:
- cVe: visp._visp.core.VelocityTwistMatrix¶
Twist transformation \(^c{\bf V}_e\) .
- get_eJe(self, q: visp._visp.core.ColVector, eJe: visp._visp.core.Matrix) None ¶
Get the robot jacobian \({^e}{\bf J}_e\) which gives the velocity of the origin of the end-effector frame expressed in end-effector frame.
\[\begin{split}{^e}{\bf J}_e = \left[\begin{array}{cc} {^w}{\bf R}_f & {[{^e}{\bf t}_w}]_\times \; {^w}{\bf R}_f \\0_{3\times3} & {^w}{\bf R}_f \end{array} \right] \; {^f}{\bf J}_w \end{split}\]Note
See get_fJw()
- Parameters:
- q: visp._visp.core.ColVector¶
A six-dimension vector that contains the joint positions of the robot expressed in radians.
- eJe: visp._visp.core.Matrix¶
Robot jacobian \({^e}{\bf J}_e\) that express the velocity of the end-effector in the robot end-effector frame.
- get_eMc(self, eMc: visp._visp.core.HomogeneousMatrix) None ¶
Get the geometric transformation between the end-effector frame and the camera frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
Note
See get_cMe()
- get_eMs(self, eMs: visp._visp.core.HomogeneousMatrix) None ¶
Get the geometric transformation between the end-effector frame and the force/torque sensor frame. This transformation is constant.
- Parameters:
- eMs: visp._visp.core.HomogeneousMatrix¶
Transformation between the the end-effector frame and the force/torque sensor frame.
- get_fJe(self, q: visp._visp.core.ColVector, fJe: visp._visp.core.Matrix) None ¶
Get the robot jacobian \({^f}{\bf J}_e\) which gives the velocity of the origin of the end-effector frame expressed in the robot reference frame also called fix frame.
\[\begin{split}{^f}{\bf J}_e = \left[\begin{array}{cc} I_{3\times3} & [{^f}{\bf R}_w \; {^e}{\bf t}_w]_\times \\0_{3\times3} & I_{3\times3} \end{array} \right] {^f}{\bf J}_w \end{split}\]Note
See get_fJw
- Parameters:
- q: visp._visp.core.ColVector¶
A six-dimension vector that contains the joint positions of the robot expressed in radians.
- fJe: visp._visp.core.Matrix¶
Robot jacobian \({^f}{\bf J}_e\) that express the velocity of the end-effector in the robot reference frame.
- get_fJw(self, q: visp._visp.core.ColVector, fJw: visp._visp.core.Matrix) None ¶
Get the robot jacobian \({^f}{\bf J}_w\) which express the velocity of the origin of the wrist frame in the robot reference frame also called fix frame.
\[\begin{split}{^f}J_w = \left(\begin{array}{cccccc} J_{11} & J_{12} & J_{13} & 0 & 0 & 0 \\J_{21} & J_{22} & J_{23} & 0 & 0 & 0 \\0 & J_{32} & J_{33} & 0 & 0 & 0 \\0 & -s1 & -s1 & c1s23 & J_{45} & J_{46} \\0 & c1 & c1 & s1s23 & J_{55} & J_{56} \\1 & 0 & 0 & c23 & s23s4 & J_{56} \\\end{array} \right) \end{split}\]with
\[\begin{split}\begin{array}{l} J_{11} = -s1(-c23a3+s23d4+a1+a2c2) \\J_{21} = c1(-c23a3+s23d4+a1+a2c2) \\J_{12} = c1(s23a3+c23d4-a2s2) \\J_{22} = s1(s23a3+c23d4-a2s2) \\J_{32} = c23a3-s23d4-a2c2 \\J_{13} = c1(a3(s2c3+c2s3)+(-s2s3+c2c3)d4)\\J_{23} = s1(a3(s2c3+c2s3)+(-s2s3+c2c3)d4)\\J_{33} = -a3(s2s3-c2c3)-d4(s2c3+c2s3)\\J_{45} = -c23c1s4-s1c4\\J_{55} = c1c4-c23s1s4\\J_{46} = (c1c23c4-s1s4)s5+c1s23c5\\J_{56} = (s1c23c4+c1s4)s5+s1s23c5\\J_{66} = -s23c4s5+c23c5\\\end{array} \end{split}\]Note
See get_fJe() , get_eJe()
- Parameters:
- q: visp._visp.core.ColVector¶
A six-dimension vector that contains the joint positions of the robot expressed in radians.
- fJw: visp._visp.core.Matrix¶
Robot jacobian \({^f}{\bf J}_w\) that express the velocity of the point w (origin of the wrist frame) in the robot reference frame.
- get_fMc(*args, **kwargs)¶
Overloaded function.
get_fMc(self: visp._visp.robot.Viper, 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 joint positions of all the six joints.
\[^f{\bf M}_c = ^f{\bf M}_e \; ^e{\bf M}_c \]This method is the same than getForwardKinematics(const vpColVector & q).
Note
See getForwardKinematics(const vpColVector & q), get_fMe() , get_eMc()
- Parameters:
- q
Vector of six joint positions expressed in radians.
- Returns:
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame (fMc).
get_fMc(self: visp._visp.robot.Viper, 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 six joint positions.
\[^f{\bf M}_c = ^f{\bf M}_e \; {^e}{\bf M}_c \]Note
See get_fMe() , get_eMc()
- Parameters:
- q
Vector of six joint positions expressed in radians.
- fMc
The homogeneous matrix \(^f{\bf M}_c\) corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame.
- 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 \({^f}{\bf M}_e\) .
By forward kinematics we mean here the position and the orientation of the end effector with respect to the base frame given the motor positions of all the six joints.
\[\begin{split}{^f}M_e = \left(\begin{array}{cccc} r_{11} & r_{12} & r_{13} & t_x \\r_{21} & r_{22} & r_{23} & t_y \\r_{31} & r_{32} & r_{33} & t_z \\\end{array} \right) \end{split}\]with
\[\begin{split}\begin{array}{l} r_{11} = c1(c23(c4c5c6-s4s6)-s23s5c6)-s1(s4c5c6+c4s6) \\r_{21} = -s1(c23(-c4c5c6+s4s6)+s23s5c6)+c1(s4c5c6+c4s6) \\r_{31} = s23(s4s6-c4c5c6)-c23s5c6 \\\\r_{12} = -c1(c23(c4c5s6+s4c6)-s23s5s6)+s1(s4c5s6-c4c6)\\r_{22} = -s1(c23(c4c5s6+s4c6)-s23s5s6)-c1(s4c5s6-c4c6)\\r_{32} = s23(c4c5s6+s4c6)+c23s5s6\\\\r_{13} = c1(c23c4s5+s23c5)-s1s4s5\\r_{23} = s1(c23c4s5+s23c5)+c1s4s5\\r_{33} = -s23c4s5+c23c5\\\\t_x = c1(c23(c4s5d6-a3)+s23(c5d6+d4)+a1+a2c2)-s1s4s5d6\\t_y = s1(c23(c4s5d6-a3)+s23(c5d6+d4)+a1+a2c2)+c1s4s5d6\\t_z = s23(a3-c4s5d6)+c23(c5d6+d4)-a2s2+d1\\\end{array} \end{split}\]Note that this transformation can also be computed by considering the wrist frame \({^f}{\bf M}_e = {^f}{\bf M}_w *{^w}{\bf M}_e\) .
#include <visp3/robot/vpViper.h> #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif int main() { vpViper robot; vpColVector q(6); // The measured six joint positions vpHomogeneousMatrix fMe; // Transformation from fix frame to end-effector robot.get_fMe(q, fMe); // Get the forward kinematics // The forward kinematics can also be computed by considering the wrist frame vpHomogeneousMatrix fMw; // Transformation from fix frame to wrist frame robot.get_fMw(q, fMw); vpHomogeneousMatrix wMe; // Transformation from wrist frame to end-effector robot.get_wMe(wMe); // Constant transformation // Compute the forward kinematics fMe = fMw * wMe; }
- Parameters:
- q: visp._visp.core.ColVector¶
A 6-dimension vector that contains the 6 joint positions expressed in radians.
- fMe: visp._visp.core.HomogeneousMatrix¶
The homogeneous matrix \({^f}{\bf M}_e\) corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame.
- get_fMw(self, q: visp._visp.core.ColVector, fMw: visp._visp.core.HomogeneousMatrix) None ¶
Compute the transformation between the fix frame and the wrist frame. The wrist frame is located on the intersection of the 3 last rotations.
\[\begin{split}{^f}M_w = \left(\begin{array}{cccc} r_{11} & r_{12} & r_{13} & t_x \\r_{21} & r_{22} & r_{23} & t_y \\r_{31} & r_{32} & r_{33} & t_z \\\end{array} \right) \end{split}\]with
\[\begin{split}\begin{array}{l} r_{11} = c1(c23(c4c5c6-s4s6)-s23s5c6)-s1(s4c5c6+c4s6) \\r_{21} = -s1(c23(-c4c5c6+s4s6)+s23s5c6)+c1(s4c5c6+c4s6) \\r_{31} = s23(s4s6-c4c5c6)-c23s5c6 \\\\r_{12} = -c1(c23(c4c5s6+s4c6)-s23s5s6)+s1(s4c5s6-c4c6)\\r_{22} = -s1(c23(c4c5s6+s4c6)-s23s5s6)-c1(s4c5s6-c4c6)\\r_{32} = s23(c4c5s6+s4c6)+c23s5s6\\\\r_{13} = c1(c23c4s5+s23c5)-s1s4s5\\r_{23} = s1(c23c4s5+s23c5)+c1s4s5\\r_{33} = -s23c4s5+c23c5\\\\t_x = c1(-c23a3+s23d4+a1+a2c2)\\t_y = s1(-c23a3+s23d4+a1+a2c2)\\t_z = s23a3+c23d4-a2s2+d1\\\end{array} \end{split}\]- Parameters:
- q: visp._visp.core.ColVector¶
A 6-dimension vector that contains the 6 joint positions expressed in radians.
- fMw: visp._visp.core.HomogeneousMatrix¶
The homogeneous matrix corresponding to the transformation between the fix frame and the wrist frame (fMw).
- get_wMe(self, wMe: visp._visp.core.HomogeneousMatrix) None ¶
Return the transformation between the wrist frame and the end-effector. The wrist frame is located on the intersection of the 3 last rotations.
- Parameters:
- wMe: visp._visp.core.HomogeneousMatrix¶
The homogeneous matrix corresponding to the transformation between the wrist frame and the end-effector frame (wMe).
- set_eMc(*args, **kwargs)¶
Overloaded function.
set_eMc(self: visp._visp.robot.Viper, eMc_: visp._visp.core.HomogeneousMatrix) -> None
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).
- Parameters:
- eMc_
Transformation between the end-effector frame and the tool frame.
set_eMc(self: visp._visp.robot.Viper, etc_: visp._visp.core.TranslationVector, erc_: visp._visp.core.RxyzVector) -> None
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera frame).
- Parameters:
- etc_
Translation between the end-effector frame and the tool frame.
- erc_
Rotation between the end-effector frame and the tool frame using the Euler angles in radians with the XYZ convention.