diff --git a/gello/agents/gello_agent.py b/gello/agents/gello_agent.py index fca60c3..60ebd80 100644 --- a/gello/agents/gello_agent.py +++ b/gello/agents/gello_agent.py @@ -76,15 +76,16 @@ PORT_CONFIG_MAP: Dict[str, DynamixelRobotConfig] = { gripper_config=(8, 195, 152), ), # Left UR - "/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBEIA-if00-port0": DynamixelRobotConfig( + # "/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBEIA-if00-port0": DynamixelRobotConfig( + "/dev/cu.usbserial-FT7WBEIA": DynamixelRobotConfig( joint_ids=(1, 2, 3, 4, 5, 6), joint_offsets=( 0, 1 * np.pi / 2 + np.pi, np.pi / 2 + 0 * np.pi, - 0 * np.pi + np.pi / 2, - np.pi - 2 * np.pi / 2, - -1 * np.pi / 2 + 2 * np.pi, + 2 * np.pi + np.pi / 2, + np.pi - 2 * np.pi / 2 + 2 * np.pi, + -1 * np.pi / 2 + 1 * np.pi, ), joint_signs=(1, 1, -1, 1, 1, 1), gripper_config=(7, 20, -22), diff --git a/gello/dm_control_tasks/arms/manipulator.py b/gello/dm_control_tasks/arms/manipulator.py index 6f251e8..068d786 100644 --- a/gello/dm_control_tasks/arms/manipulator.py +++ b/gello/dm_control_tasks/arms/manipulator.py @@ -225,5 +225,5 @@ class ArmObservables(composer.Observables): self.flange_position, # self.flange_orientation, # self.flange_velocity, - self.flange_angular_velocity, + # self.flange_angular_velocity, ] + self._collect_from_attachments("proprioception")