deprecated.py
Go to the documentation of this file.
1 #
2 # Copyright (c) 2018-2020 CNRS INRIA
3 #
4 
5 ## In this file, are reported some deprecated functions that are still maintained until the next important future releases ##
6 
7 from __future__ import print_function
8 
9 import warnings as _warnings
10 
11 from . import pinocchio_pywrap as pin
12 from .deprecation import deprecated, DeprecatedWarning
13 
14 # This function is only deprecated when using a specific signature. Therefore, it needs special care
15 # Marked as deprecated on 16 Sept 2019
16 def impulseDynamics(model, data, *args):
17  if len(args)==5 and type(args[4]) is bool:
18  message = ("This function signature has been deprecated and will be removed in future releases of Pinocchio. "
19  "Please change for the new signature of impulseDynamics(model,data[,q],v_before,J[,r_coeff[,inv_damping]]).")
20  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
21  q = args[0]
22  v_before = args[1]
23  J = args[2]
24  r_coeff = args[3]
25  updateKinematics = args[4]
26  inv_damping = 0.
27  if updateKinematics:
28  return pin.impulseDynamics(model,data,q,v_before,J,r_coeff,inv_damping)
29  else:
30  return pin.impulseDynamics(model,data,v_before,J,r_coeff,inv_damping)
31 
32  return pin.impulseDynamics(model, data, *args)
33 
34 impulseDynamics.__doc__ = (
35  pin.impulseDynamics.__doc__
36  + '\n\nimpulseDynamics( (Model)Model, (Data)Data, (object)Joint configuration q (size Model::nq), (object)Joint velocity before impact v_before (size Model::nv), (object)Contact Jacobian J (size nb_constraint * Model::nv), (float)Coefficient of restitution r_coeff (0 = rigid impact; 1 = fully elastic impact), (bool)updateKinematics) -> object :'
37  + '\n This function signature has been deprecated and will be removed in future releases of Pinocchio.'
38 )
39 
40 # This function is only deprecated when using a specific signature. Therefore, it needs special care
41 # Marked as deprecated on 2 Oct 2019
42 def forwardDynamics(model, data, *args):
43  if len(args)==7 and type(args[6]) is bool:
44  message = ("This function signature has been deprecated and will be removed in future releases of Pinocchio. "
45  "Please change for the new signature of forwardDynamics(model,data[,q],v,tau,J,gamma[,inv_damping]).")
46  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
47  q = args[0]
48  v = args[1]
49  tau = args[2]
50  J = args[3]
51  gamma = args[4]
52  inv_damping = args[5]
53  updateKinematics = args[6]
54  if updateKinematics:
55  return pin.forwardDynamics(model,data,q,v,tau,J,gamma,inv_damping)
56  else:
57  return pin.forwardDynamics(model,data,tau,J,gamma,inv_damping)
58 
59  return pin.forwardDynamics(model, data, *args)
60 
61 forwardDynamics.__doc__ = (
62  pin.forwardDynamics.__doc__
63  + '\n\nforwardDynamics( (Model)Model, (Data)Data, (object)Joint configuration q (size Model::nq), (object)Joint velocity v (size Model::nv), (object)Joint torque tau (size Model::nv), (object)Contact Jacobian J (size nb_constraint * Model::nv), (object)Contact drift gamma (size nb_constraint), (float)(double) Damping factor for cholesky decomposition of JMinvJt. Set to zero if constraints are full rank, (bool)Update kinematics) -> object :'
64 + '\n This function signature has been deprecated and will be removed in future releases of Pinocchio.'
65 )
66 
67 @deprecated("This function has been renamed computeJointJacobian and will be removed in future releases of Pinocchio. Please change for new computeJointJacobian.")
68 def jointJacobian(model, data, q, jointId):
69  return pin.computeJointJacobian(model,data,q,jointId)
70 
71 @deprecated("This function has been renamed computeFrameJacobian and will be removed in future releases of Pinocchio. Please change for new computeFrameJacobian.")
72 def frameJacobian(model, data, q, frameId):
73  return pin.computeFrameJacobian(model,data,q,frameId)
74 
75 def computeCentroidalDynamics(model, data, q, v, a = None):
76  if a is None:
77  message = ("This function signature has been renamed and will be removed in future releases of Pinocchio. "
78  "Please change for the new signature of computeCentroidalMomentum(model,data,q,v).")
79  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
80  return pin.computeCentroidalMomentum(model,data,q,v)
81  else:
82  message = ("This function signature has been renamed and will be removed in future releases of Pinocchio. "
83  "Please change for the new signature of computeCentroidalMomentumTimeVariation(model,data,q,v,a).")
84  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
85  return pin.computeCentroidalMomentum(model,data,q,v,a)
86 
87 computeCentroidalDynamics.__doc__ = ( "This function has been renamed computeCentroidalMomentum or computeCentroidalMomentumTimeVariation to either only compute the centroidal momentum quantity or also its time derivative respectively." )
88 
89 class GeometryObject(pin.GeometryObject):
90  @property
91  @deprecated("The fcl property has been renamed geometry. Please use GeometryObject.geometry instead")
92  def fcl(self):
93  return self.geometry
94 
95 @deprecated("This function is now called SE3ToXYZQUATtuple. Please change for this new signature to delete this warning.")
97  return pin.SE3ToXYZQUATtuple(M)
98 
99 @deprecated("This function is now called SE3ToXYZQUAT. Please change for this new signature to delete this warning.")
101  return pin.SE3ToXYZQUAT(M)
102 
103 @deprecated("This function is now called XYZQUATToSE3. Please change for this new signature to delete this warning.")
105  return pin.XYZQUATToSE3(x)
106 
107 def buildGeomFromUrdf(model, filename, *args):
108 
109  arg3 = args[0]
110  if isinstance(arg3,(str,list,pin.StdVec_StdString)):
111  package_dir = arg3
112  geom_type = args[1]
113 
114  if len(args) >= 3:
115  mesh_loader = args[2]
116  message = ("This function signature is now deprecated and will be removed in future releases of Pinocchio. "
117  "Please change for the new signature buildGeomFromUrdf(model,filename,type,package_dirs,mesh_loader).")
118  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
119  return pin.buildGeomFromUrdf(model,filename,geom_type,package_dir,mesh_loader)
120  else:
121  message = ("This function signature is now deprecated and will be removed in future releases of Pinocchio. "
122  "Please change for the new signature buildGeomFromUrdf(model,filename,type,package_dirs).")
123  _warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
124  return pin.buildGeomFromUrdf(model,filename,geom_type,package_dir)
125  else:
126  return pin.buildGeomFromUrdf(model, filename, *args)
127 
128 buildGeomFromUrdf.__doc__ = (
129  pin.buildGeomFromUrdf.__doc__
130 )
131 
132 @deprecated("This function is now deprecated and will be removed in future releases of Pinocchio. "
133  "Please change for the new function computePotentialEnergy.")
134 def potentialEnergy(model,data,q,update_kinematics=True):
135  if update_kinematics:
136  return pin.computePotentialEnergy(model,data,q)
137  else:
138  return pin.computePotentialEnergy(model,data)
139 
140 potentialEnergy.__doc__ += '\n' + pin.computePotentialEnergy.__doc__
141 
142 @deprecated("This function is now deprecated and will be removed in future releases of Pinocchio. "
143  "Please change for the new function computeKineticEnergy.")
144 def kineticEnergy(model,data,q,v,update_kinematics=True):
145  if update_kinematics:
146  return pin.computeKineticEnergy(model,data,q,v)
147  else:
148  return pin.computeKineticEnergy(model,data)
149 
150 kineticEnergy.__doc__ += '\n' + pin.computeKineticEnergy.__doc__
151 
152 from .utils import npToTTuple, npToTuple
153 pin.rpy.npToTTuple = deprecated("This function was moved to the utils submodule.")(npToTTuple)
154 pin.rpy.npToTuple = deprecated("This function was moved to the utils submodule.")(npToTuple)
155 
156 # Marked as deprecated on 26 Mar 2020
157 @deprecated("This function is now deprecated without replacement.")
158 def setGeometryMeshScales(geom_model, mesh_scale):
159  import numpy as np
160  if not isinstance(mesh_scale, np.ndarray):
161  mesh_scale = np.array([mesh_scale]*3)
162  for geom in geom_model.geometryObjects:
163  geom.meshScale = mesh_scale
def setGeometryMeshScales(geom_model, mesh_scale)
Definition: deprecated.py:158
def jointJacobian(model, data, q, jointId)
Definition: deprecated.py:68
def forwardDynamics(model, data, args)
Definition: deprecated.py:42
def frameJacobian(model, data, q, frameId)
Definition: deprecated.py:72
def potentialEnergy(model, data, q, update_kinematics=True)
Definition: deprecated.py:134
def se3ToXYZQUATtuple(M)
Definition: deprecated.py:96
def computeCentroidalDynamics(model, data, q, v, a=None)
Definition: deprecated.py:75
def impulseDynamics(model, data, args)
Definition: deprecated.py:16
def buildGeomFromUrdf(model, filename, args)
Definition: deprecated.py:107
def kineticEnergy(model, data, q, v, update_kinematics=True)
Definition: deprecated.py:144
def deprecated(instructions)
Definition: deprecation.py:7


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02