Skip to content

Commit

Permalink
Merge pull request #153 from cmower/fix-151
Browse files Browse the repository at this point in the history
Fix 151
  • Loading branch information
cmower authored Aug 11, 2023
2 parents ea3a58c + cd44b3d commit 3e7608f
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 108 deletions.
4 changes: 2 additions & 2 deletions example/experiment1.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@ def __init__(self, robot, eff_link, base_link=None):
self.qd = self.builder.get_model_state(self.robot_name, 0, time_deriv=1)
self.qc = self.builder.add_parameter("qc", robot.ndof)
if base_link is None:
self.J = robot.get_global_geometric_jacobian(eff_link, self.qc)
self.J = robot.get_global_link_geometric_jacobian(eff_link, self.qc)
else:
self.J = robot.get_geometric_jacobian(eff_link, self.qc, base_link)
self.J = robot.get_link_geometric_jacobian(eff_link, self.qc, base_link)
self.veff = self.J @ self.qd
self._solver_duration = None

Expand Down
4 changes: 2 additions & 2 deletions example/experiment2.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,10 @@ def __init__(self):
qF = builder.get_model_state(self.name, t=0)
qd = (qF - qc) / dt
pg = builder.add_parameter("pg", 3) # goal position
Jp = robot.get_global_linear_jacobian(ee_link, qc)
Jp = robot.get_global_link_linear_jacobian(ee_link, qc)
pc = pos(qc)
p = pc + dt * Jp @ qd
Ja = robot.get_global_angular_geometric_jacobian(ee_link, qc)
Ja = robot.get_global_link_angular_geometric_jacobian(ee_link, qc)
va = Ja @ qd
Jg = robot.get_global_link_geometric_jacobian(ee_link, qF)
manip = cs.sqrt(cs.det(Jg @ Jg.T))
Expand Down
2 changes: 1 addition & 1 deletion example/pushing.py
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@ def __init__(self, dt, thresh_angle):
q = qc + dt * dq

# Get jacobian
Jl = kuka.get_global_linear_jacobian(link_ee, qc)
Jl = kuka.get_global_link_linear_jacobian(link_ee, qc)

# Get end-effector velocity
dp = Jl @ dq
Expand Down
103 changes: 0 additions & 103 deletions optas/models.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
"""! @brief Several Model classes are defined."""

import os
import warnings
import functools
Expand Down Expand Up @@ -1197,11 +1196,6 @@ def get_link_rpy_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_global_link_geometric_jacobian")
def get_global_geometric_jacobian(self, link, q):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_global_link_geometric_jacobian(
Expand All @@ -1224,7 +1218,6 @@ def get_global_link_geometric_jacobian(
jacobian_columns = []

for joint in self.urdf.joints:

if joint.type == "fixed":
continue

Expand Down Expand Up @@ -1260,7 +1253,6 @@ def get_global_link_geometric_jacobian(
jcol = cs.DM.zeros(6)
jacobian_columns.append(jcol)


# Sort columns of jacobian
jacobian_columns_ordered = [jacobian_columns[idx] for idx in joint_index_order]

Expand All @@ -1271,11 +1263,6 @@ def get_global_link_geometric_jacobian(

return J

@deprecation_warning("get_global_link_geometric_jacobian_function")
def get_global_geometric_jacobian_function(self, link, n=1):
"""! Deprecated function."""
pass

def get_global_link_geometric_jacobian_function(
self,
link: str,
Expand All @@ -1293,11 +1280,6 @@ def get_global_link_geometric_jacobian_function(
"J", link, self.get_global_link_geometric_jacobian, n=n
)

@deprecation_warning("get_global_link_analytical_jacobian")
def get_global_analytical_jacobian(self, link, q):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_global_link_analytical_jacobian(
Expand All @@ -1314,11 +1296,6 @@ def get_global_link_analytical_jacobian(
self.get_global_link_angular_analytical_jacobian(link, q),
)

@deprecation_warning("get_global_link_analytical_jacobian_function")
def get_global_analytical_jacobian_function(self, link):
"""! Deprecated function."""
pass

def get_global_link_analytical_jacobian_function(
self,
link: str,
Expand All @@ -1340,11 +1317,6 @@ def get_global_link_analytical_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_link_geometric_jacobian")
def get_geometric_jacobian(self):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_link_geometric_jacobian(
Expand All @@ -1371,11 +1343,6 @@ def get_link_geometric_jacobian(

return J

@deprecation_warning("get_link_geometric_jacobian_function")
def get_geometric_jacobian_function(self, link, base_link, n=1):
"""! Deprecated function."""
pass

def get_link_geometric_jacobian_function(
self,
link: str,
Expand All @@ -1400,11 +1367,6 @@ def get_link_geometric_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_link_analytical_jacobian")
def get_analytical_jacobian(self):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_link_analytical_jacobian(
Expand All @@ -1422,11 +1384,6 @@ def get_link_analytical_jacobian(
self.get_link_angular_analytical_jacobian(link, q, base_link),
)

@deprecation_warning("get_link_analytical_jacobian_function")
def get_analytical_jacobian_function(self, link, base_link):
"""! Deprecated function."""
pass

def get_link_analytical_jacobian_function(
self,
link: str,
Expand All @@ -1451,11 +1408,6 @@ def get_link_analytical_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_global_link_linear_jacobian")
def get_global_linear_jacobian(self, link, q):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_global_link_linear_jacobian(
Expand All @@ -1470,11 +1422,6 @@ def get_global_link_linear_jacobian(
J = self.get_global_link_geometric_jacobian(link, q)
return J[:3, :]

@deprecation_warning("get_global_link_linear_jacobian_function")
def get_global_linear_jacobian_function(self, link, n=1):
"""! Deprecated function."""
pass

def get_global_link_linear_jacobian_function(
self,
link: str,
Expand All @@ -1496,11 +1443,6 @@ def get_global_link_linear_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_link_linear_jacobian")
def get_linear_jacobian(self, link, q, base_link):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_link_linear_jacobian(
Expand All @@ -1516,11 +1458,6 @@ def get_link_linear_jacobian(
J = self.get_link_geometric_jacobian(link, q, base_link)
return J[:3, :]

@deprecation_warning("get_link_linear_jacobian_function")
def get_linear_jacobian_function(self, link, base_link, n=1):
"""! Deprecated function."""
pass

def get_link_linear_jacobian_function(
self, link: str, base_link: str, n: int = 1, numpy_output: bool = False
) -> cs.Function:
Expand All @@ -1541,11 +1478,6 @@ def get_link_linear_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_global_link_angular_geometric_jacobian")
def get_global_angular_geometric_jacobian(self, link, q):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_global_link_angular_geometric_jacobian(
Expand All @@ -1561,11 +1493,6 @@ def get_global_link_angular_geometric_jacobian(
J = self.get_global_link_geometric_jacobian(link, q)
return J[3:, :]

@deprecation_warning("get_global_link_angular_geometric_jacobian_function")
def get_global_angular_geometric_jacobian_function(self, link, n=1):
"""! Deprecated function."""
pass

def get_global_link_angular_geometric_jacobian_function(
self,
link: str,
Expand All @@ -1587,11 +1514,6 @@ def get_global_link_angular_geometric_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_global_link_angular_analytical_jacobian")
def get_global_angular_analytical_jacobian(self, link, q):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_global_link_angular_analytical_jacobian(
Expand All @@ -1605,11 +1527,6 @@ def get_global_link_angular_analytical_jacobian(
"""
return self.get_link_angular_analytical_jacobian(link, q, self.get_root_link())

@deprecation_warning("get_global_link_angular_analytical_jacobian_function")
def get_global_angular_analytical_jacobian_function(self, link):
"""! Deprecated function."""
pass

def get_global_link_angular_analytical_jacobian_function(
self,
link: str,
Expand All @@ -1631,11 +1548,6 @@ def get_global_link_angular_analytical_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_link_angular_geometric_jacobian")
def get_angular_geometric_jacobian(self, link, q, base_link):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_link_angular_geometric_jacobian(
Expand All @@ -1651,11 +1563,6 @@ def get_link_angular_geometric_jacobian(
J = self.get_link_geometric_jacobian(link, q, base_link)
return J[3:, :]

@deprecation_warning("get_link_angular_geometric_jacobian_function")
def get_angular_geometric_jacobian_function(self, link, base_link, n=1):
"""! Deprecated function."""
pass

def get_link_angular_geometric_jacobian_function(
self,
link: str,
Expand All @@ -1680,11 +1587,6 @@ def get_link_angular_geometric_jacobian_function(
numpy_output=numpy_output,
)

@deprecation_warning("get_link_angular_analytical_jacobian")
def get_angular_analytical_jacobian(self, link, q, base_link):
"""! Deprecated function."""
pass

@arrayify_args
@listify_output
def get_link_angular_analytical_jacobian(
Expand All @@ -1708,11 +1610,6 @@ def get_link_angular_analytical_jacobian(

return Ja(q)

@deprecation_warning("get_link_angular_analytical_jacobian_function")
def get_angular_analytical_jacobian_function(self, link, base_link):
"""! Deprecated function."""
pass

def get_link_angular_analytical_jacobian_function(
self,
link: str,
Expand Down

0 comments on commit 3e7608f

Please sign in to comment.