Skip to content

Commit 90812de

Browse files
committed
style: fix linting
1 parent 44df26b commit 90812de

4 files changed

Lines changed: 5 additions & 4 deletions

File tree

extensions/rcs_fr3/src/rcs_fr3/creators.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,11 @@ def __init__(self, allow_elbow_flips: bool = False):
3636
self.allow_elbow_flips = allow_elbow_flips
3737
self.kin = FrankaKinematics(robot_type="fr3")
3838

39-
def forward(self, q0: np.ndarray[tuple[typing.Literal[7]], np.dtype[np.float64]], tcp_offset: Pose) -> Pose:
39+
def forward(self, q0: np.ndarray[tuple[typing.Literal[7]], np.dtype[np.float64]], tcp_offset: Pose) -> Pose: # type: ignore
4040
print("forward called")
4141
return Pose(pose_matrix=self.kin.forward(q0, tcp_offset.pose_matrix()))
4242

43-
def inverse(
43+
def inverse( # type: ignore
4444
self, pose: Pose, q0: np.ndarray[tuple[typing.Literal[7]], np.dtype[np.float64]], tcp_offset: Pose
4545
) -> np.ndarray[tuple[typing.Literal[7]], np.dtype[np.float64]] | None:
4646
tcp_offset = self.kin.FrankaHandTCPOffset

extensions/rcs_so101/src/rcs_so101/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from rcs_so101._core import SO101IK, __version__
1+
from rcs_so101._core import __version__
22
from rcs_so101._core.so101_ik import SO101IK
33
from rcs_so101.creators import RCSSO101EnvCreator
44
from rcs_so101.hw import SO101, SO101Config, SO101Gripper

extensions/rcs_ur5e/src/rcs_ur5e/hw.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -278,7 +278,7 @@ def set_cartesian_position(self, pose: common.Pose) -> None:
278278
if q is None:
279279
print("IK failed")
280280
return
281-
self.set_joint_position(q[0:6])
281+
self.set_joint_position(q[0:6]) # type: ignore
282282
return
283283

284284
def set_joint_position(self, q: np.ndarray[tuple[typing.Any], np.dtype[np.float64]]) -> None:

python/rcs/_core/common.pyi

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,7 @@ class HandState:
130130
def __init__(self) -> None: ...
131131

132132
class Kinematics:
133+
def __init__(self) -> None: ...
133134
def forward(self, q0: numpy.ndarray[tuple[M], numpy.dtype[numpy.float64]], tcp_offset: Pose = ...) -> Pose: ...
134135
def inverse(
135136
self, pose: Pose, q0: numpy.ndarray[tuple[M], numpy.dtype[numpy.float64]], tcp_offset: Pose = ...

0 commit comments

Comments
 (0)