layout | title |
---|---|
page |
Advanced Robotics |
- Math/Physics
- FK/IK
- Dynamics
- Controls
- Motion Planning
Q: What's the properties of rotation matrix?
A:
- A rotation matrix will always be a square and orthogonal matrix.
- Column vectors are mutually orthogonal (orthonormal frame)
- Column vectors have unit norm
- the transpose will be equal to the inverse of the matrix
$R^T=R^{-1}$ . - The determinant of a rotation matrix will always be equal to 1.
$det(R)=1$ . - Right-handed coordinate system
- for clockwise rotation, a negative angle is used.
- Multiplication of rotation matrices will result in a rotation matrix.
Q: how to determine a matrix is a rotation matrix. given $ R^A_B = \begin{bmatrix} \cos \theta & 0& \sin \theta \ \sin \phi \sin\theta & \cos\phi & -\sin\phi\cos\theta\ -\cos\phi\sin\theta & \sin\phi & \cos\phi\cos\theta \ \end{bmatrix} $
A: calculate the
Q: List one advantage and one disadvantage for using the Jacobian transpose (
$J^T$ ) method, versus of the Jacobian Moore-Penrose pseudoinverse ($J^+$ ) when computing inverse kinematics solutions.
A:
pros | cons | principles | |
---|---|---|---|
most precise | not exist when J drops rank | ||
|
|
Project difference vector Dx on those dimensions q which can reduce it the most | |
|
|
Shortest path in q-space | |
Damped least squares | pros | cons | principles |
Q: Determine the relationship between angular velocities and time derivatives of the Euler angles.
A:
- For ZYZ: $$ T = \begin{bmatrix} 0& -s_\phi & c_\phi s_\theta \ 0& c_\phi & s_\phi s_\theta \ 1& 0& c_\theta\ \end{bmatrix} $$
- For ZYX (yaw pitch roll): $$ T=\begin{bmatrix} 0& -s_\phi & c_\phi c_\theta \ 0& c_\phi & s_\phi c_\theta \ 1& 0& -s_\theta\ \end{bmatrix} $$
Q: How to derive Lagrange equation for robot?
A:
- Compute position
$p_i$ , linear velocity$v_i=\frac{d p_i}{dt}$ and acceleration$a_i=\frac{d v_i}{dt}$ , angular velocity$\omega_i$ , acceleration$\alpha_i=\frac{d \omega_i}{dt}$ vector of CoM each joint. - Write / assume moment of Inertia
$Ii$ , mass$m_i$ of each link; Make assumptions that coordinate frame is aligned with principle axes so that Off diagonals (prodcts of inertia) are all ZEROs. Diagonal terms (moments of inertia) are inertia about each axis. (SEE Dynamics Q1.) - Calculate kinetic
$\frac{1}{2}m_iv_i^Tv_i \pink+ \frac{1}{2}w_i^TI_iw_i$ AND potential energy$m_igh_i$ for each link. - Derive the Lagrange equation
$L = KE-PE$ . -
Derive equation of motion with dynamics
$\frac{d}{dt} (\frac{\partial{L}}{\partial{\dot{\theta}}}) -\frac{\partial{L}}{\partial{\theta}} = F_{ext} = \sum\tau$ and get$M,B,C,G$ . (SEE Inverse Dynamics)
Q: Compare different control
Equation | When | |
---|---|---|
Feedforward | Ideal case. | |
Feedback | $\tau = \underbrace{k_p(\theta_d-\theta)}{\text{spring}}\underbrace{-k_v\dot{\theta}}\text{damper}$ | Inverse dynamics control. Minimise steady-state error. |
PID | $\tau = \underbrace{k_p(\theta_d-\theta)}{\text{P:Proportional }}\underbrace{-k_v\dot{\theta}}\text{ D:Derivative}+\underbrace{\red{k_i\int(\theta_d-\theta)dt}}_\text{I:Integral}$ | NOT safe for robot. Integral. |
Gravity compensation | $\tau = \underbrace{k_p(\theta_d-\theta)}{\text{P:Proportional }}\underbrace{-k_v\dot{\theta}}\text{ D:Derivative}+\underbrace{rmg\theta}_\text{gravity compensation}$ | Model based. Need to know G |
Linearlisation | tracking complete trajectory. Error guaranteed to 0 | |
Task space control | Desired motion in task space ( end effector ). Null space projection for secondary task. | |
Impedance control | $M(q_d)\ddot{q}_d + C(q_d,\dot{q}d)+G(q_d) = \tau \red\pm J^T_CF{ext}$ | External forces applied by(+)/to(-) robot. Can be at any joint. |
Force control | ||
Hybrid Force-motion control | seperate control of force and motion. Force in one direction and motion in another. e.g. open a door(door's moving). Task space controller with constraints. Projection matrix |
Q: Comparisions between different methods?
A:
pros | cons | others | |
---|---|---|---|
Potential Fields | Smooth, obstacle-free trajectory | in highly-cluttered environments, |
|
Voronoi Graphs | solve stuck | Paths are not smooth, requires post-processing | Focus on the free space |
Regular Cell Decomposition | wavefront propagation algorithm | ||
Sampling Based Roadmaps | |||
Rapidly-exploring Random Trees (RRTs) | configuration space is sampled randomly | ||
Lattice Based Methods |