diff --git a/bindings/python/algorithm/expose-jacobian.cpp b/bindings/python/algorithm/expose-jacobian.cpp
index 1913a09a9e4d85e9281a09077b62c761bc6a5a50..4601141e2cf05be61e92eae34e61ea1a1988cbef 100644
--- a/bindings/python/algorithm/expose-jacobian.cpp
+++ b/bindings/python/algorithm/expose-jacobian.cpp
@@ -14,16 +14,10 @@ namespace pinocchio
     jacobian_proxy(const Model & model,
                    Data & data,
                    const Eigen::VectorXd & q,
-                   Model::JointIndex jointId,
-                   ReferenceFrame rf,
-                   bool update_kinematics)
+                   Model::JointIndex jointId)
     {
       Data::Matrix6x J(6,model.nv); J.setZero();
-      
-      if (update_kinematics)
-        computeJointJacobians(model,data,q);
-      
-      getJointJacobian(model,data,jointId,rf,J);
+      jointJacobian(model,data,q,jointId,J);
       
       return J;
     }
@@ -75,11 +69,8 @@ namespace pinocchio
               bp::args("Model, the model of the kinematic tree",
                        "Data, the data associated to the model where the results are stored",
                        "Joint configuration q (size Model::nq)",
-                       "Joint ID, the index of the joint.",
-                       "Reference frame rf (either ReferenceFrame.LOCAL or ReferenceFrame.WORLD)",
-                       "update_kinematics (true = update the value of the total jacobian)"),
-              "Computes the jacobian of a given given joint according to the given input configuration."
-              "If rf is set to LOCAL, it returns the jacobian associated to the joint frame. Otherwise, it returns the jacobian of the frame coinciding with the world frame.");
+                       "Joint ID, the index of the joint"),
+              "Computes the Jacobian of a specific joint frame expressed in the local frame of the joint according to the given input configuration.");
 
       bp::def("getJointJacobian",get_jacobian_proxy,
               bp::args("Model, the model of the kinematic tree",
diff --git a/bindings/python/pinocchio/deprecated.py b/bindings/python/pinocchio/deprecated.py
index c83c8f632644151971ea1ecb8783feb6a610239f..dffff196a139aa82e1106c1d4192664849108fea 100644
--- a/bindings/python/pinocchio/deprecated.py
+++ b/bindings/python/pinocchio/deprecated.py
@@ -60,12 +60,32 @@ def computeJacobians(model,data,q=None):
   else:
     return pin.computeJointJacobians(model,data,q)
 
+# This function is only deprecated when using a specific signature. Therefore, it needs special care
+# Marked as deprecated on 19 Feb 2019
+def jointJacobian(model, data, q, jointId, *args):
+  if len(args)==2:
+    message = ("This function signature has been deprecated and will be removed in future releases of Pinocchio. "
+               "Please change for the new signature of jointJacobian or use computeJointJacobian + getJointJacobian.")
+    _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
+    rf = args[0]
+    update_kinematics = args[1]
+    if update_kinematics:
+        pin.computeJointJacobians(model,data,q)
+    return pin.getJointJacobian(model,data,jointId,rf)
+  else:
+    return pin.jointJacobian(model,data,q,jointId)
+jointJacobian.__doc__ =  (
+  pin.jointJacobian.__doc__
+  + '\n\njointJacobian( (Model)Model, (Data)Data, (object)Joint configuration q (size Model::nq), (Index)jointId, ReferenceFrame rf, (bool)updateKinematics) -> object :'
+  + '\n    This function signature has been deprecated and will be removed in future releases of Pinocchio.'
+)
+
 @deprecated("This function has been renamed jointJacobian and will be removed in future releases of Pinocchio. Please change for new jointJacobian function.")
 def jacobian(model,data,q,jointId,local,update_kinematics):
-  if local:
-    return pin.jointJacobian(model,data,q,jointId,pin.ReferenceFrame.LOCAL,update_kinematics)
-  else:
-    return pin.jointJacobian(model,data,q,jointId,pin.ReferenceFrame.WORLD,update_kinematics)
+  rf = pin.ReferenceFrame.LOCAL if local else pin.ReferenceFrame.WORLD
+  if update_kinematics:
+      computeJointJacobians(model,data,q)
+  return pin.getJointJacobian(model,data,jointId,rf)
 
 @deprecated("This function has been renamed getJointJacobian and will be removed in future releases of Pinocchio. Please change for new getJointJacobian function.")
 def getJacobian(model,data,jointId,local):
diff --git a/bindings/python/pinocchio/robot_wrapper.py b/bindings/python/pinocchio/robot_wrapper.py
index 3ec94b1f6a64ae986240893b1f607e40bbd5d767..7ea33aa6b4bfe094eb77e06053a95acdfb9acfbc 100644
--- a/bindings/python/pinocchio/robot_wrapper.py
+++ b/bindings/python/pinocchio/robot_wrapper.py
@@ -188,8 +188,13 @@ class RobotWrapper(object):
         else:
             return pin.jointJacobian(self.model, self.data, q, index, pin.ReferenceFrame.WORLD, update_kinematics)
 
-    def jointJacobian(self, q, index, rf_frame=pin.ReferenceFrame.LOCAL, update_kinematics=True):
-        return pin.jointJacobian(self.model, self.data, q, index, rf_frame, update_kinematics)
+    def jointJacobian(self, q, index, *args):
+        if len(args)==0:
+            return pin.jointJacobian(self.model, self.data, q, index)
+        else: # use deprecated signature (19 Feb 2019)
+            update_kinematics = True if len(args)==1 else args[1]
+            rf = args[0]
+            return pin.jointJacobian(self.model, self.data, q, index, rf_frame, update_kinematics)
 
     def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL):
         return pin.getFrameJacobian(self.model, self.data, index, rf_frame)
@@ -229,11 +234,14 @@ class RobotWrapper(object):
         return pin.getFrameJacobian(self.model, self.data, frame_id, rf_frame)
 
     '''
-        Similar to getFrameJacobian but it also calls before pin.computeJointJacobians and
+        Similar to getFrameJacobian but does not need pin.computeJointJacobians and
         pin.updateFramePlacements to update internal value of self.data related to frames.
     '''
-    def frameJacobian(self, q, frame_id, rf_frame=pin.ReferenceFrame.LOCAL):
-        return pin.frameJacobian(self.model, self.data, q, frame_id, rf_frame)
+    def frameJacobian(self, q, frame_id, rf_frame=None):
+        if rf_frame: # use deprecated signature (19 Feb 2019)
+            return pin.frameJacobian(self.model, self.data, q, frame_id, rf_frame)
+        else: # use normal signature
+            return pin.frameJacobian(self.model, self.data, q, frame_id)
 
 
     # --- ACCESS TO NAMES ----
diff --git a/src/algorithm/jacobian.hpp b/src/algorithm/jacobian.hpp
index 33470bcd45d5854801a8120942441d420a59bae1..2445d217a1c9da462c0f98a01306fc097e59b08b 100644
--- a/src/algorithm/jacobian.hpp
+++ b/src/algorithm/jacobian.hpp
@@ -132,7 +132,7 @@ namespace pinocchio
   
   ///
   /// \brief Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame or in the local frame (rf = LOCAL) of the joint.
-  /// \note This jacobian is extracted from data.J. You have to run pinocchio::computeJacobians before calling it.
+  /// \note This jacobian is extracted from data.J. You have to run pinocchio::computeJointJacobians before calling it.
   ///
   /// \deprecated This function is now deprecated. Please refer now to pinocchio::getJointJacobian for similar function with updated name.
   ///
@@ -167,9 +167,10 @@ namespace pinocchio
   ///
   /// \return The Jacobian of the specific joint frame expressed in the local frame of the joint (matrix 6 x model.nv).
   ///
-  /// \remark This function is equivalent to call first computeJacobians(model,data,q) and then call getJointJacobian(model,data,jointId,LOCAL,J).
+  /// \remark The result of this function is equivalent to call first computeJointJacobians(model,data,q) and then call getJointJacobian(model,data,jointId,LOCAL,J),
+  ///         but forwardKinematics is not fully computed.
   ///         It is worth to call jacobian if you only need a single Jacobian for a specific joint. Otherwise, for several Jacobians, it is better
-  ///         to call computeJacobians(model,data,q) followed by getJointJacobian(model,data,jointId,LOCAL,J) for each Jacobian.
+  ///         to call computeJointJacobians(model,data,q) followed by getJointJacobian(model,data,jointId,LOCAL,J) for each Jacobian.
   ///
   template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename Matrix6Like>
   inline void jointJacobian(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
@@ -191,9 +192,10 @@ namespace pinocchio
   ///
   /// \return The Jacobian of the specific joint frame expressed in the local frame of the joint (matrix 6 x model.nv).
   ///
-  /// \remark This function is equivalent to call first computeJacobians(model,data,q) and then call getJointJacobian<LOCAL>(model,data,jointId,J).
+  /// \remark The result of this function is equivalent to call first computeJointJacobians(model,data,q) and then call getJointJacobian<LOCAL>(model,data,jointId,J),
+  ///         but forwardKinematics is not fully computed.
   ///         It is worth to call jacobian if you only need a single Jacobian for a specific joint. Otherwise, for several Jacobians, it is better
-  ///         to call computeJacobians(model,data,q) followed by getJointJacobian<LOCAL>(model,data,jointId,J) for each Jacobian.
+  ///         to call computeJointJacobians(model,data,q) followed by getJointJacobian<LOCAL>(model,data,jointId,J) for each Jacobian.
   ///
   PINOCCHIO_DEPRECATED
   inline void jacobian(const Model & model,
@@ -271,7 +273,7 @@ namespace pinocchio
   
   ///
   /// \brief Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (rf = WORLD) or in the local frame (rf = LOCAL) of the joint.
-  /// \note This jacobian is extracted from data.dJ. You have to run pinocchio::computeJacobiansTimeVariation before calling it.
+  /// \note This jacobian is extracted from data.dJ. You have to run pinocchio::computeJointJacobiansTimeVariation before calling it.
   ///
   /// \tparam JointCollection Collection of Joint types.
   /// \tparam Matrix6xLike Type of the matrix containing the joint Jacobian.
@@ -291,7 +293,7 @@ namespace pinocchio
   
   ///
   /// \brief Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (rf = WORLD) or in the local frame (rf = LOCAL) of the joint.
-  /// \note This jacobian is extracted from data.dJ. You have to run pinocchio::computeJacobiansTimeVariation before calling it.
+  /// \note This jacobian is extracted from data.dJ. You have to run pinocchio::computeJointJacobiansTimeVariation before calling it.
   ///
   /// \deprecated This function is now deprecated. Please refer now to pinocchio::getJointJacobianTimeVariation for similar function with updated name.
   ///
diff --git a/unittest/python/bindings_dynamics.py b/unittest/python/bindings_dynamics.py
index 1b287fb6ea3e4b53e32c816cf709c0481bd9ca73..de2fda3b09ba3581af9f31d1ac3c6f5c14e713d5 100644
--- a/unittest/python/bindings_dynamics.py
+++ b/unittest/python/bindings_dynamics.py
@@ -27,7 +27,7 @@ class TestDynamicsBindings(TestCase):
         self.tolerance = 1e-9
 
         # we compute J on a different self.data
-        self.J = pin.jointJacobian(self.model,self.model.createData(),self.q,self.model.getJointId('lleg6_joint'),pin.ReferenceFrame.LOCAL,True)
+        self.J = pin.jointJacobian(self.model,self.model.createData(),self.q,self.model.getJointId('lleg6_joint'))
         self.gamma = zero(6)
 
     def test_forwardDynamics7(self):