Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
ROBOOP::Impedance Class Reference#include <controller.h>
Detailed DescriptionImpedance controller class.The implemantation of the impedance controller is made of two section: the first one is the generation of a compliance trajectory and the second one used a position controller to ensure the end effector follow the compliance trajectory (We recommended to used the resolve acceleration controller scheme, implemented in the class Resolved_acc). This class generate a compliance path given by the translational and the rotational impedance.
where
The impedance parameters Definition at line 80 of file controller.h.
Constructor & Destructor Documentation
Member Function Documentation
Assign the translational impedance inertia matrix
Definition at line 136 of file controller.cpp. Referenced by Impedance().
Assign the translational impedance inertia term
Definition at line 153 of file controller.cpp.
Assign the translational impedance damping matrix
Definition at line 169 of file controller.cpp. Referenced by Impedance().
Assign the translational impedance damping term
Definition at line 186 of file controller.cpp.
Assign the translational impedance stifness matrix
Definition at line 202 of file controller.cpp. Referenced by Impedance().
Assign the translational impedance stifness term
Definition at line 219 of file controller.cpp.
Assign the rotational impedance inertia matrix
Definition at line 235 of file controller.cpp. Referenced by Impedance().
Assign the rotational impedance inertia term
Definition at line 252 of file controller.cpp.
Assign the rotational impedance damping matrix
Definition at line 268 of file controller.cpp. Referenced by Impedance().
Assign the rotational impedance damping term
Definition at line 285 of file controller.cpp.
Assign the rotational impedance stifness matrix
Definition at line 301 of file controller.cpp. Referenced by Impedance().
Assign the rotational impedance stifness term
Definition at line 318 of file controller.cpp.
Generation of a compliance trajectory.
![]() ![]() ![]() ![]() ![]() ![]() ![]() ![]() ![]() The quaternion -q represents exactly the same rotation as the quaternion q. The temporay quaternion, quat, is quatd plus a sign correction. It is customary to choose the sign G on q1 so that q0.Gq1 >=0 (the angle between q0 ang Gq1 is acute). This choice avoids extra spinning caused by the interpolated rotations. Definition at line 334 of file controller.cpp.
Member Data DocumentationCompliant frame quaternion.
Definition at line 107 of file controller.h. Referenced by control(), Impedance(), and operator=(). Compliant frame quaternion derivative.
Definition at line 107 of file controller.h. Referenced by control(), Impedance(), and operator=(). Previous value of qcp.
Definition at line 107 of file controller.h. Referenced by control(), Impedance(), and operator=(). Orientation error (betweem compliant and desired frame) quaternion.
Definition at line 107 of file controller.h. Referenced by control(). Temporary quaternion.
Definition at line 107 of file controller.h. Referenced by control(), Impedance(), and operator=(). Compliant position.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Compliant velocity.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Compliant acceleration.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Previous value of pcp.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Previous value of pcpp.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Difference between pc and desired position.
Definition at line 112 of file controller.h. Referenced by control(). Difference between pcp and desired velocity.
Definition at line 112 of file controller.h. Referenced by control(). Compliant angular velocity.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Compliant angular acceleration.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Previous value of wcp.
Definition at line 112 of file controller.h. Referenced by control(), Impedance(), and operator=(). Difference between wc and desired angular velocity.
Definition at line 112 of file controller.h. Referenced by control().
Translational impedance inertia matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Mp().
Translational impedance damping matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Dp().
Translational impedance stifness matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Kp().
Rotational impedance inertia matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Mo().
Rotational impedance damping matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Do().
Rotational impedance stifness matrix.
Definition at line 124 of file controller.h. Referenced by control(), Impedance(), operator=(), and set_Ko().
Modified rotational impedance stifness matrix.
Definition at line 130 of file controller.h. Referenced by control(), Impedance(), and operator=().
The documentation for this class was generated from the following files: |
ROBOOP v1.21a |
Generated Thu Nov 22 00:51:35 2007 by Doxygen 1.5.4 |