Skip to content

Commit afacfd7

Browse files
committed
minor: remove unnecessary scipy and etc.
1 parent c7630e5 commit afacfd7

3 files changed

Lines changed: 2 additions & 28 deletions

File tree

extensions/rcs_xarm7/src/rcs_xarm7/env_cartesian_control.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,6 @@ def main():
7070
if truncated or terminated:
7171
logger.info("Truncated or terminated!")
7272
return
73-
print(obs)
74-
#sleep(2.0)
7573
for _ in range(10):
7674
# move 1cm in negative x direction (backward) and open gripper
7775
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1}

extensions/rcs_xarm7/src/rcs_xarm7/hw.py

Lines changed: 2 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@
77

88
from rcs import common
99

10-
from scipy.spatial.transform import Rotation as R
11-
1210

1311
@dataclass(kw_only=True)
1412
class XArm7Config(common.RobotConfig):
@@ -37,21 +35,16 @@ def __init__(self, ip: str):
3735
center_of_gravity=self._config.payload_tcp,
3836
wait=True,
3937
)
40-
41-
# def get_base_pose_in_world_coordinates(self) -> Pose: ...
4238

4339
def get_cartesian_position(self) -> common.Pose:
4440
code, xyzrpy = self._xarm.get_position(is_radian=True)
4541
if code != 0:
4642
raise RuntimeError("couldn't get cartesian position from xarm")
4743

48-
translation = np.array(xyzrpy[:3], dtype=np.float64).reshape((3, 1)) * 0.001
44+
translation_meter = np.array(xyzrpy[:3], dtype=np.float64) * 0.001
4945
rpy = xyzrpy[3:]
50-
quat = R.from_euler('xyz', rpy).as_quat() # [x, y, z, w]
51-
quat = np.array(quat, dtype=np.float64).reshape((4, 1))
5246

53-
# return common.Pose(quaternion=quat, translation=translation)
54-
return common.Pose(rpy_vector=rpy, translation=translation)
47+
return common.Pose(rpy_vector=rpy, translation=translation_meter)
5548

5649
def get_ik(self) -> common.IK | None:
5750
return self.ik
@@ -92,8 +85,3 @@ def __enter__(self):
9285

9386
def __exit__(self, exc_type, exc_value, traceback):
9487
self._xarm.disconnect()
95-
96-
97-
# def to_pose_in_robot_coordinates(self, pose_in_world_coordinates: Pose) -> Pose: ...
98-
# def to_pose_in_world_coordinates(self, pose_in_robot_coordinates: Pose) -> Pose: ...
99-

extensions/rcs_xarm7/src/rcs_xarm7/test.py

Lines changed: 0 additions & 12 deletions
This file was deleted.

0 commit comments

Comments
 (0)