diff --git a/doc/pinocchio_cheat_sheet.pdf b/doc/pinocchio_cheat_sheet.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..6a05add6fb4e91533f06915677404d5304799ca1
Binary files /dev/null and b/doc/pinocchio_cheat_sheet.pdf differ
diff --git a/doc/pinocchio_cheat_sheet.tex b/doc/pinocchio_cheat_sheet.tex
index c2e12827896caedaf20601db85181130b60f0e6a..ef2832994a3b47e921a9fed9a35838f00767bfc5 100644
--- a/doc/pinocchio_cheat_sheet.tex
+++ b/doc/pinocchio_cheat_sheet.tex
@@ -1,23 +1,10 @@
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 % Pinocchio Cheat Sheet
-%
-% Edited by Aurélie Bonnefoy
-% Available at https://www.overleaf.com/project/5e66106889524e000114b5df
-%
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-%%%%%%%%%%%%% TODOs %%%%%%%%%%%%%
-% - purpose of the cheat sheet ? overview for beginners vs. completeness and adv. algos
-% - add derivatives
-% - add missing algorithms
-% - restructure main algorithm section
-% - think about common abbreviations to avoid too many 2liners
-% - add links to overview / pinocchio doc / more detailed explanations, featherstone book
-% - adapt design, maybe not all cols need to be the same lengths, algos need much more space
-%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
 \documentclass[10.5pt]{article}
 \usepackage[landscape,a3paper]{geometry}
+\usepackage[table]{xcolor}
 \usepackage{url}
 \usepackage{multicol}
 \usepackage{amsmath}
@@ -27,10 +14,11 @@
 \usepackage{amsmath,amssymb}
 
 \usepackage{colortbl}
-\usepackage{xcolor}
 \usepackage{mathtools}
 \usepackage{amsmath,amssymb}
 \usepackage{enumitem}
+\usepackage{arydshln}
+\usepackage{wrapfig}
 
 \title{Pinocchio Cheat Sheet}
 \usepackage[english]{babel}
@@ -38,7 +26,6 @@
 
 \usepackage{minted}
 \usemintedstyle{vs}
-\usepackage{xcolor}
 
 
 \advance\topmargin-3cm
@@ -65,11 +52,14 @@
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        \begin{tabular}{p{3cm} | p{8cm}}
+    \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            easy install & \texttt{conda install -c conda-forge pinocchio}\\
             import & \texttt{import pinocchio as pin}\\
             & \texttt{from pinocchio.utils import *} \\
-            get documentation & \texttt{pin.Model?} \\
+            \textbf{documentation} & \texttt{pin.Model?} \\
         \end{tabular}
+    
     \end{minipage}
 };
 
@@ -78,24 +68,28 @@
 %------------ End Get started ---------------------
 
 %------------ Begin Spatial quantities ---------------------
+
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-
+        \rowcolors{1}{white}{gray!20}
         \centerline{\textbf{Transforms}}\vspace{0.1cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
             SE3 & \texttt{aMb = pin.SE3(aRb,apb)} \\ \hline
-            \quad unit transformation & \texttt{M = pin.SE3(1)} \\ 
+            \quad unit transformation & \texttt{M = pin.SE3(1)} or \texttt{pin.SE3.Identity()} \\ 
+            \quad random transformation & \texttt{pin.SE3.Random()} \\ 
             \quad rotation matrix & \texttt{M.rotation} \\
             \quad translation vector & \texttt{M.translation} \\ \hline
             SE3 inverse & \texttt{bMa = aMb.inverse()} \\
             SE3 action & \texttt{aMc = aMb * bMc} \\
             action matrix & \texttt{aXb = aMb.action} \\
             homegeneous matrix & \texttt{aHb = aMb.homogeneous} \\
+            log operation SE3 $\rightarrow$ 6D & \texttt{pin.log(M)} \\
+            exp operation & \texttt{pin.exp(M)} \\
         \end{tabular} \newline
 
         \centerline{\textbf{Spatial Velocity}}\vspace{0.1cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
             Motion & \texttt{m = pin.Motion(v,w)} \\ \hline
             \quad linear acceleration & \texttt{m.linear} \\
             \quad angular acceleration & \texttt{m.angular} \\ \hline
@@ -103,14 +97,14 @@
         \end{tabular} \newline
         
         \centerline{\textbf{Spatial Acceleration}}\vspace{0.1cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
-            is used in algorithms  & \texttt{a = ($\dot{\omega}$,$\dot{v}_O$)} \\ 
-            Get classical acceleration & \texttt{a' = a + $(0, \omega \times v_O)$} \\
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            used in algorithms  & \texttt{a = ($\dot{\omega}$,$\dot{v}_O$)} \\ 
+            get classical acceleration & \texttt{a' = a + $(0, \omega \times v_O)$} \\
                           & \texttt{pin.classicAcceleration(v,a, [aMb])} \\
         \end{tabular} \newline
 
         \centerline{\textbf{Spatial Force}}\vspace{0.1cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
             Force & \texttt{f = pin.Force(l,n)} \\ \hline
             \quad linear force & \texttt{f.linear} \\
             \quad torque & \texttt{f.angular} \\ \hline
@@ -118,7 +112,7 @@
         \end{tabular} \newline
 
         \centerline{\textbf{Spatial Inertia}}\vspace{0.1cm}
-       \begin{tabular}{p{4cm} | p{7cm}}	
+       \begin{tabular}{p{4cm} | p{7.5cm}}	
             Inertia & \texttt{Y = pin.Inertia(mass,com,I)} \\ \hline
             \quad mass & \texttt{Y.mass} \\
             \quad center of mass pos. & \texttt{Y.lever} \\
@@ -126,14 +120,14 @@
         \end{tabular} \newline
         
         \centerline{\textbf{Geometry}}\vspace{0.1cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
             Quaternion & \texttt{quat = pin.Quaternion(R)} \\
             Angle Axis & \texttt{aa = pin.AngleAxis(angle,axis)} \\ 
         \end{tabular} \newline
         
         \centerline{\textbf{Useful converters}} 
         \vspace{0.2cm}
-        \begin{tabular}{p{4cm} | p{7cm}}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
         	  SE3 $\rightarrow$ (x,y,z,quat) & \texttt{pin.se3ToXYZQUAT(M)} \\
         	  (x,y,z,quat) $\rightarrow$ SE3 & \texttt{pin.XYZQUATToSE3(vec)} \\
         \end{tabular}
@@ -145,20 +139,50 @@
 \end{tikzpicture}
 %------------ End Spatial quantities ---------------------
 
+%------------ Begin Data ---------------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            Data {\small related to the model} & \texttt{data = pin.Data(model)} \\ 
+             & \texttt{data = model.createData()} \\ \hline
+            \hspace{0.5em} joint data & \texttt{data.joints} \\
+            \hspace{0.5em} joint placements & \texttt{data.oMi} \\
+            \hspace{0.5em} joint velocities & \texttt{data.v} \\
+            \hspace{0.5em} joint accelerations & \texttt{data.a} \\
+            \hspace{0.5em} joint forces & \texttt{data.f} \\
+            \hspace{0.5em} mass matrix & \texttt{data.M} \\
+            \hspace{0.5em} non linear effects & \texttt{data.nle} \\
+            \hspace{0.5em} centroidal momentum & \texttt{data.hg} \\
+            \hspace{0.5em} centroidal matrix & \texttt{data.Ag} \\
+            \hspace{0.5em} centroidal inertia & \texttt{data.Ig} \\
+        \end{tabular} 
+        
+    \end{minipage}
+};
+
+\node[fancytitle] at (box.north) {Data};
+\end{tikzpicture}
+%------------ End Data ---------------------------------
+
 %------------ Begin Model --------------------------------
 % Some items in this box here seems kind of self-explanatory, good idea to make award of the different attributes and methods but maybe not to best representation (model name - model.name) , others are quite useful.
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        \begin{tabular}{p{4cm} | p{7cm}}
-            Model & \texttt{model = pin.Model()} \\ \hline
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            Model {\small of the kinematic tree} & \texttt{model = pin.Model()} \\ \hline
             \quad model name & \texttt{model.name} \\
             \quad joint names & \texttt{model.names} \\
             \quad joint models & \texttt{model.joints} \\
             \quad joint placements & \texttt{model.placements} \\
             \quad link inertias & \texttt{model.inertias} \\
             \quad frames & \texttt{model.frames} \\ 
-            Methods &  \\ \hline
+            \quad \# position variables & \texttt{model.nq} \\ 
+            \quad \# velocity variables & \texttt{model.nv} \\ 
+            Methods & use ? to get doc and input arguments  \\ \hline
             % Inputs missing, but there are a lot. maybe enough like this and doc should be ask. maybe another hint to the doc ?
             \quad add joint & \texttt{model.addJoint} \\
             \quad append body & \texttt{model.appendBodyToJoint} \\
@@ -179,11 +203,10 @@
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        
-         \begin{tabular}{p{3cm} | p{8cm}}
+        \rowcolors{1}{white}{gray!20}
+         \begin{tabular}{p{3cm} | p{8.5cm}}
             load an URDF file & \texttt{pin.buildModelFromUrdf(filename,[root\_joint])} \\
-            load a SDF file & \texttt{pin.buildModelFromSdf(filename,[root\_joint]} \\
-             & \texttt{root\_link\_name,parent\_guidance)} \\
+            load a SDF file & \texttt{pin.buildModelFromSdf(filename,[root\_joint], root\_link\_name,parent\_guidance)} \\
         \end{tabular} 
         
     \end{minipage}
@@ -193,252 +216,413 @@
 \end{tikzpicture}
 %------------ End Parsers --------------------------------
 
-%------------ Begin Data ---------------------------------
+%------------ Begin Reference Frames ---------------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.25\linewidth}
+    \includegraphics[]{local_world_aligned.pdf}
+    \end{minipage}%
+    \begin{minipage}{0.65\linewidth}
+        \small{Coordinate system (CS)}\newline
+        \\
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4.0cm} | p{4.0cm}}
+            WORLD & world CS \\
+            LOCAL & local CS of the joint \\
+            LOCAL\_WORLD\_ALIGNED & local CS aligned with WORLD axis \\
+            
+        \end{tabular} 
+
+    \end{minipage}
+};
+
+\node[fancytitle] at (box.north) {Reference Frames};
+\end{tikzpicture}
+%------------ End Reference Frames ---------------------------------
+
+%------------ Begin Frames ----------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        \begin{tabular}{p{4cm} | p{7cm}}
-            Data & \texttt{data = pin.Data(model)} \\ 
-             & \texttt{data = model.createData()} \\ \hline
-            \hspace{0.5em} joint data & \texttt{data.joints} \\
-            \hspace{0.5em} joint placements & \texttt{data.oMi} \\
-            \hspace{0.5em} joint velocities & \texttt{data.v} \\
-            \hspace{0.5em} joint accelerations & \texttt{data.a} \\
-            \hspace{0.5em} joint forces & \texttt{data.f} \\
-            \hspace{0.5em} mass matrix & \texttt{data.M} \\
-            \hspace{0.5em} non linear effects & \texttt{data.nle} \\
-            \hspace{0.5em} centroidal momentum & \texttt{data.hg} \\
-            \hspace{0.5em} centroidal matrix & \texttt{data.Ag} \\
-            \hspace{0.5em} centroidal inertia & \texttt{data.Ig} \\ \hline
-            Reference frames &  \\
-            LOCAL & local coordinate system of the joint \\
-            LOCAL\_WORLD\_ALIGNED & local coordinate system aligned with WORLD axis \\
-            WORLD & world coordinate system \\
+    \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            placement of all operational frames & \texttt{pin.updateFramePlacements(model, data)} \\ 
+            frame veloctiy & \texttt{pin.getFrameVelocity(model, data, frame\_id, ref\_frame)} \\ 
+            frame acceleration & \texttt{pin.getFrameAcceleration(model, data, frame\_id, ref\_frame)} \\
+            frame acceleration & \texttt{pin.getFrameClassicalAcceleration(\newline model, data, frame\_id, ref\_frame)} \\
+            frames placement & \texttt{pin.framesForwardKinematics(model, data, q)} \\
+            frame jacobian & \texttt{pin.computeFrameJacobian(model, data, q, frame\_id, ref\_frame)} \\ \hline
+            frame jacobian time variation & \texttt{pin.frameJacobianTimeVariation(model, data, q, v, frame\_id, ref\_frame)} \\ 
+            % maybe better to use symbols ? 
+            partial derivatives of the spatial velocity & \texttt{pin.getFrameVelocityDerivatives(model, data, frame\_id, ref\_frame)} \\ 
+            partial derivatives of the spatial velocity & \texttt{pin.getFrameVelocityDerivatives(model, data, joint\_id, placement ref\_frame)} \\ 
+            partial derivatives of the spatial acceleration & \texttt{pin.getFrameVelocityDerivatives(model, data, frame\_id, ref\_frame)} \\ 
+            partial derivatives of the spatial acceleration & \texttt{pin.getFrameAccelerationDerivatives\newline (model, data, joint\_id, placement ref\_frame)} \\ 
         \end{tabular} 
         
     \end{minipage}
 };
 
-\node[fancytitle] at (box.north) {Data};
+\node[fancytitle] at (box.north) {Frames};
 \end{tikzpicture}
-%------------ End Data ---------------------------------
+%------------ End Frames ------------------------
 
 
-%------------ Begin Main Algorithms---------------------
+%------------ Begin Configuration -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            random configuration & \texttt{pin.randomConfiguration(model, [lower\_bound, upper\_bound])} \\
+            neutral configuration & \texttt{pin.neutral(model)} \\
+            normalized configuration & \texttt{pin.normalize(model, q)} \\
+            difference configurations & \texttt{pin.difference(model, q1, q2)} \\
+            distance configurations & \texttt{pin.distance(model, q1, q2)} \\
+            squared distance configurations & \texttt{pin.squareDistance(model, q1, q2)} \\
+            interpolate configuration & \texttt{pin.interpolate(model, q1, q2, alpha)} \\
+            integrate configuration & \texttt{pin.integrate(model, q, v)} \\ \hline
+            partial derivatives of difference & \texttt{pin.dDifference(model, q1, q2, [arg\_pos])} \\
+            partial derivatives of integration & \texttt{pin.dIntegrate(model, q, v, [arg\_pos])}
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Configuration};
+\end{tikzpicture}
+%------------ End Configuration  ---------------------------
 
-% List the missing algorithms and decide which to include
-% - joint : dIntegrate, interpolate, difference
-% - contact-jacobian: getConstraintJacobian
-% - contact-dynamics: forwardDynamics, impulseDynamics, computeKKTContactDynamicMatrixInverse
-% - constrained-dynamics: initConstraintDynamics, constraintDynamics
-% - constrained-dynamics-derivatives: computeConstraintDynamicsDerivatives
-% - collision / broadphase: computeCollisions
-% - kinematic regressor
-% - regressor: computeStaticRegressor, bodyRegressor, jointBodyRegressor, computeJointTorqueRegressor
-% - cholesky: decompose, solve, computeMinv
-% - impulse dynamics
+%------------ Begin Collision -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            placement collision obj & \texttt{pin.updateGeometryPlacements(model, data, geometry\_model, geometry\_data, [q])} \\ 
+            collisions detection for all pairs & \texttt{pin.computeCollisions(model, data, geometry\_model, geometry\_data, q)} \\
+            collisions detection for a pair &
+            \texttt{pin.computeCollisions(geometry\_model, geometry\_data, pair\_index)} \\
+            distance from collision & \texttt{pin.computeDistance(geometry\_model, geometry\_data, [pair\_index])} \\
+            distance from collision each pair &
+            \texttt{pin.computeDistances([model, data], geometry\_model, geometry\_data, [q])} \\
+            geometry volume radius & \texttt{pin.computeBodyRadius(model, geometry\_model, geometry\_data} \\ \hline
+            BroadPhase &
+            \texttt{pin.computeCollisions(broadphase\_manager, callback)} \\
+             & \texttt{pin.computeCollisions(broadphase\_manager, stop\_at\_first\_collision)} \\
+            + forward kinmetatics to update geometry placements & \texttt{pin.computeCollisions(model, data, broadphase\_manager, q, stop\_at\_first\_collision)} \\
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Collision};
+\end{tikzpicture}
+%------------ End Collision  ---------------------------
 
+%------------ Begin COM ---------------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{4cm} | p{7.5cm}}
+            total mass of model & \texttt{pin.computeTotalMass(model, [data])} \\ 
+            mass of each subtree & \texttt{pin.computeSubtreeMasses(model, data)} \\ 
+            center of mass (COM) & \texttt{pin.centerOfMass(model, data, q, [v, a],[compute\_subtree\_com])} \\ 
+            Jacobian COM & \texttt{pin.jacobianCenterOfMass(model, data, [q],[compute\_subtree\_com])} \\ 
+        \end{tabular} 
+        
+    \end{minipage}
+};
 
-        \centerline{\textbf{Configuration}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            placement collision obj & \texttt{pin.updateGeometryPlacements(model, data, robot.collision\_model, robot.collision\_data, q)} \\ 
-            collisions detection & \texttt{pin.computeCollisions(robot.collision\_model, robot.collision\_data, False)} \\
-            distance from collision & \texttt{pin.computeDistances(robot.collision\_model, robot.collision\_data)} \\
-            integrate configuration & \texttt{pin.integrate(model, q, v)} \\ 
-        \end{tabular} \newline
+\node[fancytitle] at (box.north) {Center of Mass};
+\end{tikzpicture}
+%------------ End COM ---------------------------------
 
-        \centerline{\textbf{Kinematics}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            forward kinematics & \texttt{pin.forwardKinematics(model, data, q, [v, [ a] ])} \\
-            forward kinematics derivatives & \texttt{pin.computeForwardKinematicsDerivatives( \newline model,data,q,v,a)} \\
-            dv\_dq,dv\_dv = & \texttt{pin.getJointVelocityDerivatives(model,data, \newline joint\_id,pin.ReferenceFrame.WORLD)}   \\
-            dv\_dq\_local,da\_dq\_\newline local,da\_dv\_local,\newline da\_da\_local = & \texttt{ pin.getJointAccelerationDerivatives(model,data,\newline joint\_id,pin.ReferenceFrame.LOCAL)} \\ 
-            frames placement & \texttt{pin.framesForwardKinematics(model, data, q)} \\
-            frame jacobian & \texttt{pin.computeFrameJacobian(model, data, q, frame\_id, ref\_frame)} \\ 
+%------------ Begin Energy -------------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            FK and kinetic Energy & \texttt{pin.computeKineticEnergy(model, data, [q, v]) } \\
+            FK and potential Energy & \texttt{pin.computePotentialEnergy(model, data, [q, v]) } \\
+            FK and mechanical Energy & \texttt{pin.computeMechanicalEnergy(model, data, [q, v]) } \\
+        \end{tabular} 
+        
+    \end{minipage}
+};
+
+\node[fancytitle] at (box.north) {Energy};
+\end{tikzpicture}
+%------------ End Energy ---------------------------------
+
+%------------ Begin Kinematics -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            forward kinematics (FK) & \texttt{pin.forwardKinematics(model, data, q, [v,[a]])} \\ \hline
+            FK derivatives & \texttt{pin.computeForwardKinematicsDerivatives( \newline model, data, q, v, a)} \\
+            $\left[ \frac{\partial{v}}{\partial{q}},\frac{\partial{v}}{\partial{\dot{q}}} \right]^{WORLD}$ & \texttt{pin.getJointVelocityDerivatives(model, data, joint\_id,pin.ReferenceFrame.WORLD)}   \\
+            $\left[ \frac{\partial{v}}{\partial{q}},\frac{\partial{a}}{\partial{q}}, \frac{\partial{a}}{\partial{\dot{q}}}\right]^{LOCAL}$ & \texttt{pin.getJointAccelerationDerivatives(model, data, joint\_id,pin.ReferenceFrame.LOCAL)} \\ 
             % getVelocity, getAcceleration, getClassicalAcceleration
-        \end{tabular} \newline
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Kinematics};
+\end{tikzpicture}
+%------------ End Kinematics  ---------------------------
 
-        \centerline{\textbf{Jacobian}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            full model Jacobian data.J & \texttt{pin.computeJointJacobians(model, data, [q])} \\
-            joint Jacobian & \texttt{pin.getJointJacobian(model, data, joint\_id, ref\_frame)} \\
+%------------ Begin Jacobian ----------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            full model Jacobian $\rightarrow$ data.J & \texttt{pin.computeJointJacobians(model, data, [q])} \\
+            joint Jacobian & \texttt{pin.getJointJacobian(model, data, joint\_id, ref\_frame)} \\ \hline
             full model dJ/dt & \texttt{pin.computeJointJacobiansTimeVariation(model, data, q, v)} \\
             joint dJ/dt & \texttt{pin.getJointJacobianTimeVariation(model, data, joint\_id, ref\_frame)} \\
-        \end{tabular} \newline
+        \end{tabular} 
+        
+    \end{minipage}
+};
 
-        \centerline{\textbf{Forward Dynamics}}
-        \begin{tabular}{p{3cm} | p{8cm}}mmmm
+\node[fancytitle] at (box.north) {Jacobian};
+\end{tikzpicture}
+%------------ End Jacobian  ------------------------------
+
+%------------ Begin Forward Dynamics ---------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
             Articulated-Body Algorithm $\ddot{q}$ & \texttt{pin.aba(model, data, q, v, tau, [f\_ext]) } \\
             Joint Space Inertia Matrix Inv & \texttt{pin.computeMinverse(model, data, [q]) } \\ \hline
             Composite Rigid-Body Algorithm & \texttt{pin.crba(model, data, q)}
-        \end{tabular} \newline
+        \end{tabular} 
         
-        \centerline{\textbf{Inverse Dynamics}}
-        \begin{tabular}{p{3cm} | p{8cm}}
+    \end{minipage}
+};
+
+\node[fancytitle] at (box.north) {Forward Dynamics};
+\end{tikzpicture}
+%------------ End Forward Dynamics -----------------------
+
+%------------ Begin Inverse Dynamics ---------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
             Recursive Newton-Euler Algorithm & \texttt{pin.rnea(model, data, q, v, a, [f\_ext]) } \\
+            generalized gravity & \texttt{pin.computeGeneralizedGravity(model, data, q) } \\
+            \hline
             dtau\_dq, dtau\_dv, dtau\_da & \texttt{pin.computeRNEADerivatives(model, data, q, v, a, [f\_ext]) } \\
         % nonLinearEffects, computeGeneralizedGravity, computeStaticTorque, computeCoriolisMatrix
-        \end{tabular} \newline
-        
-        \centerline{\textbf{Centroidal}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            Centroidal momentum & \texttt{pin.computeCentroidalMomentum(model, data, [q, v]) } \\
-            Centroidal momentum + time derivatives & \texttt{pin.computeCentroidalMomentumTimeVariation(model, data, [q, v, a]) } \\
-        % also mention ccrba, dccrba, computeCentroidalMap, computeCentroidalMapTimeVariation?
-        \end{tabular} \newline
-        
-        \centerline{\textbf{Energy}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            forward kinematics and kin. E & \texttt{pin.computeKineticEnergy(model, data, [q, v]) } \\
-            forward kinematics and pot. E & \texttt{pin.computePotentialEnergy(model, data, [q, v]) } \\
-            forward kinematics and mech. E & \texttt{pin.computeMechanicalEnergy(model, data, [q, v]) } \\
-        % also mention ccrba, dccrba, computeCentroidalMap, computeCentroidalMapTimeVariation?
-        \end{tabular} \newline
+        \end{tabular} 
         
-        \centerline{\textbf{General}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            all terms, check doc & \texttt{pin.computeAllTerms(model, data, q, v) } \\
-        \end{tabular} \newline
+    \end{minipage}
+};
 
+\node[fancytitle] at (box.north) {Inverse Dynamics};
+\end{tikzpicture}
+%------------ End Inverse Dynamics -----------------------
 
+%------------ Begin Centroidal ---------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            Centroidal momentum & \texttt{pin.computeCentroidalMomentum(model, data, [q, v]) } \\ \hline
+            Centroidal momentum + time derivatives & \texttt{pin.computeCentroidalMomentumTimeVariation(\newline model, data, [q, v, a]) } \\
+        % also mention ccrba, dccrba, computeCentroidalMap, computeCentroidalMapTimeVariation?
+        \end{tabular} 
+        
     \end{minipage}
 };
 
-\node[fancytitle, right=10pt] at (box.north west) {Main algorithms};
+\node[fancytitle] at (box.north) {Centroidal};
 \end{tikzpicture}
-%------------ End Main Algorithms------------------
+%------------ End Centroidal -----------------------------
 
-%------------ Begin COM ---------------------------------
+
+%------------ Begin General ------------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        \begin{tabular}{p{4cm} | p{7cm}}
-            Total mass of model & \texttt{pin.computeTotalMass(model, [data])} \\ 
-            Mass of each subtree & \texttt{pin.computeSubtreeMasses(model, data)} \\ 
-            Center of mass & \texttt{pin.centerOfMass(model, data, q, [v, a],[compute\_subtree\_com])} \\ 
-            Jacobian center of mass & \texttt{pin.jacobianCenterOfMass(model, data, [q],[compute\_subtree\_com])} \\ 
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            all terms (check doc) & \texttt{pin.computeAllTerms(model, data, q, v) } \\
         \end{tabular} 
         
     \end{minipage}
 };
 
-\node[fancytitle] at (box.north) {COM};
+\node[fancytitle] at (box.north) {General};
 \end{tikzpicture}
-%------------ End COM ---------------------------------
+%------------ End General -------------------------------
 
-%------------ Begin Frames ---------------------------------
+%------------ Begin Kinematic Regressor -------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
-        \begin{tabular}{p{4cm} | p{7cm}}
-            placement of all operational frames & \texttt{pin.updateFramePlacements(model, data)} \\ 
-            frame veloctiy & \texttt{pin.getFrameVelocity(model, data, frame\_id, reference\_frame)} \\ 
-            frame acceleration & \texttt{pin.getFrameAcceleration(model, data, frame\_id, reference\_frame)} \\
-            frame acceleration & \texttt{pin.getFrameClassicalAcceleration(model, data, frame\_id, reference\_frame)} \\
-            frames placement & \texttt{pin.framesForwardKinematics(model, data, q)} \\
-            frame jacobian & \texttt{pin.computeFrameJacobian(model, data, q, frame\_id, ref\_frame)} \\ 
-            frame jacobian time variation & \texttt{pin.frameJacobianTimeVariation(model, data, q, v, frame\_id, ref\_frame)} \\ 
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            kinematic regressor & \texttt{pin.computeJointKinematicRegressor(model, data, joint\_id, ref\_frame, [placement])} \\ 
+            kinematic regressor & \texttt{pin.computeFrameKinematicRegressor(model, data, frame\_id, ref\_frame)} \\ 
         \end{tabular} 
         
     \end{minipage}
 };
+\node[fancytitle] at (box.north) {Kinematic Regressor};
+\end{tikzpicture}
+%------------ End Kinematic Regressor  ---------------------------
 
-\node[fancytitle] at (box.north) {Frames};
+%------------ Begin Regressor -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            static regressor & \texttt{pin.computeStaticRegressor(model, data, q)} \\ 
+            body regressor & \texttt{pin.bodyRegressor(velocity, acceleration)} \\ 
+            body attached to joint regressor & \texttt{pin.jointBodyRegressor(model, data, joint\_id)} \\ 
+            body attached to frame regressor & \texttt{pin.frameBodyRegressor(model, data, frame\_id)} \\ 
+            joint torque regressor & \texttt{pin.computeJointTorqueRegressor(model, data, q, v, a)} \\ 
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Regressor};
 \end{tikzpicture}
-%------------ End Frames ---------------------------------
-
-
-%%------------ Optimization ---------------------
-%\begin{tikzpicture}
-%\node [mybox] (box){%
-%    \begin{minipage}{0.9\linewidth}
-%
-%
-%        \begin{tabular}{p{3cm} | p{8cm}}
-%            initialization & \texttt{from scipy.optimize import fmin\_bfgs} \\
-%            & \texttt{from scipy.optimize import fmin\_slsqp} \\ \hline
-%            BFGS optimization & \texttt{fmin\_bfgs(cost, x0, callback)} \\ \hline
-%            SLSQP optimization & \texttt{fmin\_slsqp(cost, x0, callback, f\_eqcons) }
-%        \end{tabular}
-%
-%
-%    \end{minipage}
-%};
-%%------------ Title ---------------------
-%\node[fancytitle, right=10pt] at (box.north west) {Optimization};
-%\end{tikzpicture}
-
-
-%------------ Begin Robot Wrapper ---------------
-% TODO explain usage / utility of robot wrapper in a sentence
+%------------ End Regressor  ---------------------------
+
+
+
+%------------ Begin Contact Jacobian -------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            kinematic Jacobian of constraint model & \texttt{pin.getConstraintJacobian(model, data, contact\_model, contact\_data)} \\ 
+            kinematic Jacobian of set of constraint models& \texttt{pin.getConstraintJacobian(model, data, contact\_models, contact\_datas)} \\ 
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Contact Jacobian};
+\end{tikzpicture}
+%------------ End Contact Jacobian  ---------------------------
 
-        \begin{tabular}{p{3cm} | p{8cm}}
-            import & \texttt{from pinocchio.robot\_wrapper import RobotWrapper} \\ \hline
-            reference initial position & \texttt{robot.q0} \\ \hline
-            display & \texttt{robot.display(q)} \\ \hline
-            return joint index & \texttt{robot.index('joint name')} \\ \hline
-            model constants & \texttt{model = robot.model} \\
-            \quad names & \texttt{model.names} \\
-            \quad frames & \texttt{model.frames} \\ \hline
-            model data & \texttt{data = robot.data} \\ \hline
-            joint placement & \texttt{robot.placement(idx)} \\
-            \quad translation & \texttt{robot.placement(idx).translation} \\
-            \quad rotation & \texttt{robot.placement(idx).rotation} \\ \hline
-            frame placement & \texttt{robot.framePlacement(idx)} \\
-        \end{tabular} \newline
+%------------ Begin Contact Dynamics -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            constrained dynamics with contacts & \texttt{pin.forwardDynamics(model, data, [q, v,] tau, constraint\_jacobian, constraint\_drift, damping)} \\ 
+            impact dynamics with contacts & \texttt{pin.impulseDynamics(model, data, [q,] v\_before, constraint\_jacobian, restitution\_coefficient, damping)} \\ 
+            inverse of the constraint matrix & \texttt{pin.computeKKTContactDynamicMatrixInverse(\newline model, data, q, constraint\_jac, damping)} \\ 
+            % getKKTContactDynamicMatrixInverse
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Contact Dynamics};
+\end{tikzpicture}
+%------------ End Contact Dynamics  ---------------------------
 
+%------------ Begin Constraint Dynamics -------------------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            allocate memory & \texttt{pin.initConstraintDynamics(model, data, contact\_models)} \\ 
+            forward dynamics with contact constraints & \texttt{pin.constraintDynamics(model, data, q, v, tau, contact\_models, contact\_datas, [prox\_settings])} \\ \hline
+            derivatives of the forward dynamics with kinematic constraints & \texttt{pin.computeConstraintDynamicsDerivatives(\newline model, data, contact\_models, contact\_datas, prox\_settings)} \\
+        \end{tabular} 
+        
     \end{minipage}
 };
+\node[fancytitle] at (box.north) {Constraint Dynamics};
+\end{tikzpicture}
+%------------ End Constraint Dynamics  ---------------------------
 
-\node[fancytitle, right=10pt] at (box.north west) {Robot Wrapper class };
+%------------ Begin Impulse Dynamics -------------------------
+% TODO dupliacte with contact dynamics ? not really, different args
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            impulse dynamics with contact constraints & \texttt{pin.impulseDynamics(model, data, q, v, contact\_models, contact\_datas, r\_coeff, mu)} \\ \hline
+            impulse dynamics derivatives & \texttt{pin.computeImpulseDynamicsDerivatives(model, data, contact\_models, contact\_datas, r\_coeff, prox\_settings)} \\
+            
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Impulse Dynamics};
 \end{tikzpicture}
-%------------ End Robot Wrapper ---------------
+%------------ End Impulse Dynamics  ---------------------------
 
 
-%------------ Begin Gepetto Viewer --------------
+%------------ Begin Cholesky -------------------------
 \begin{tikzpicture}
 \node [mybox] (box){%
     \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            Cholesky decomposition of the joint space inertia matrix & \texttt{pin.cholesky.decompose(model, data)} \\
+            $x$ of $ M x = y$ & \texttt{pin.cholesky.solve(model, data, v)} \\
+            inverse of the joint space inertia matrix & \texttt{pin.cholesky.computeMinv(model, data)} \\
+        \end{tabular} 
+        
+    \end{minipage}
+};
+\node[fancytitle] at (box.north) {Cholesky};
+\end{tikzpicture}
+%------------ End Cholesky  ---------------------------
+
 
+%------------ Begin Viewer --------------
+\begin{tikzpicture}
+\node [mybox] (box){%
+    \begin{minipage}{0.9\linewidth}
+        \rowcolors{1}{white}{gray!20}
         \centerline{\textbf{Get started}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            open from terminal & \texttt{gepetto-gui} \\ \hline
-            import & \texttt{import gviewserver}\\ \hline
-            initialization & \texttt{gv = gviewserver.GepettoViewerServer()} \\
-            \quad or & \texttt{gv=robot.viewer.gui}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            create viewer & \texttt{mv = pin.visualize.MeshcatVisualizer} \\
+            load model & \texttt{viz = mv(model, collision\_model, visual\_model)} \\
+            initialize & \texttt{viz.initViewer(loadModel=True)} \\
+            display & \texttt{viz.display(q)} \\ 
         \end{tabular} \newline
+        
 
         \centerline{\textbf{Add basic shapes}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            sphere & \texttt{gv.addSphere('world/Sphere', radius, color=[r,g,b,a])} \\ \hline
-            capsule & \texttt{gv.addCapsule('world/Capsule', radis, length, color)} \\ \hline
-            box & \texttt{gv.addBox('world/Box', depth(x), length(y), height(z), color)}\\ \hline
-            axis & \texttt{gv.addXYZaxis('world/Frame', color, radius, size)}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            sphere & \texttt{viz.viewer[name].set\_object(meshcat.geometry.\newline Sphere(size), material)} \\ \hline
+            box & \texttt{viz.viewer[name].set\_object(meshcat.geometry.\newline Box([sizex, sizey, sizez]), material)}\\ \hline
         \end{tabular} \newline
 
         \centerline{\textbf{Display}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            configuration & \texttt{gv.applyConfiguration('path/to/the/shape', [x,y,z,quaternion])} \\ \hline
-            refresh & \texttt{gv.refresh()}
+        \begin{tabular}{p{3cm} | p{8.5cm}}
+            change placement of geometry [name] & \texttt{viz.viewer[name].set\_transform(\newline meshcat\_transform(xyzquat\_placement))} \\ \hline
+            % refresh & \texttt{viz.refresh()}
         \end{tabular} \newline
 
-        \centerline{\textbf{Clean scene}}
-        \begin{tabular}{p{3cm} | p{8cm}}
-            erase world & \texttt{gv.deleteNode('world',True)}
-        \end{tabular}
-
     \end{minipage}
 };
 
-\node[fancytitle, right=10pt] at (box.north west) {Gepetto Viewer};
+\node[fancytitle, right=10pt] at (box.north west) {Viewer};
 \end{tikzpicture}
-%------------ End Gepetto Viewer --------------
+%------------ End Viewer --------------
 
 \end{multicols*}
 \end{document}