diff --git a/python/ur_simple_control/managers.py b/python/ur_simple_control/managers.py
index f43ee36f1b474fb93d73a80e0135ca6ed39dbd8c..5bef9eb4a248efe67092c79b5025ba0149309406 100644
--- a/python/ur_simple_control/managers.py
+++ b/python/ur_simple_control/managers.py
@@ -10,6 +10,7 @@ from rtde_control import RTDEControlInterface
 from rtde_receive import RTDEReceiveInterface
 from rtde_io import RTDEIOInterface
 from ur_simple_control.util.grippers.robotiq.robotiq_gripper import RobotiqGripper
+from ur_simple_control.util.grippers.rs485_robotiq.rs485_robotiq import RobotiqHand
 from ur_simple_control.util.grippers.on_robot.twofg import TWOFG
 import copy
 import signal
@@ -107,7 +108,7 @@ def getMinimalArgParser():
             help="whether you want to have some real-time matplotlib graphs (parts of log_dict you select)", default=True)
     parser.add_argument('--gripper', type=str, \
             help="gripper you're using (no gripper is the default)", \
-                        default="none", choices=['none', 'robotiq', 'onrobot'])
+                        default="none", choices=['none', 'robotiq', 'onrobot', 'rs485'])
     # TODO: make controlloop manager run in a while True loop and remove this
     # ==> max-iterations actually needs to be an option. sometimes you want to simulate and exit
     #     if the convergence does not happen in a reasonable amount of time,
@@ -509,6 +510,15 @@ class RobotManager:
                 self.gripper = RobotiqGripper()
                 self.gripper.connect(args.robot_ip, 63352)
                 self.gripper.activate()
+            if self.args.gripper == "rs485":
+                self.gripper = RobotiqHand()
+                self.gripper.connect(args.robot_ip, 54321)
+                self.gripper.activate()
+                result = self.gripper.wait_activate_complete()
+                if result != 0x31:
+                    print("ERROR: can't activate gripper!! - exiting")
+                    self.gripper.disconnect()
+                    exit()
             if self.args.gripper == "onrobot":
                 self.gripper = TWOFG()
 
diff --git a/python/ur_simple_control/util/grippers/abstract_gripper.py b/python/ur_simple_control/util/grippers/abstract_gripper.py
index b8672d2969b9fe18aa594704c918e26f2e85d872..a261f05aabf9aebbefe80c331a9f4686af1f1d9c 100644
--- a/python/ur_simple_control/util/grippers/abstract_gripper.py
+++ b/python/ur_simple_control/util/grippers/abstract_gripper.py
@@ -1,11 +1,12 @@
-from abc import ABC
+import abc
 
-class AbstractGripper(ABC):
+
+class AbstractGripper(abc.ABC):
     """
     AbstractGripper
     ------------------
     Abstract gripper class enforcing all grippers to have the same API toward RobotManager.
-    The point of this is to avoid having too many ifs in RobotManager 
+    The point of this is to avoid having too many ifs in RobotManager
     which reduce its readability, while achieving the same effect
     of moving the stupid hardware bookkeeping out of sight.
     Bookkeeping here refers to various grippers using different interfaces and differently
@@ -13,17 +14,23 @@ class AbstractGripper(ABC):
     with a certain speed and certain final gripping force.
     There are also the classic expected open(), close(), isGripping() quality-of-life functions.
     """
-     
 
+    def connect(self):
+        pass
+
+    @abc.abstractmethod
     def move(self, position, speed=None, gripping_force=None):
         pass
 
+    @abc.abstractmethod
     def open(self):
         pass
 
+    @abc.abstractmethod
     def close(self):
         pass
 
+
 #    def setVelocity(self):
 #        pass
 #
diff --git a/python/ur_simple_control/util/grippers/robotiq/robotiq_gripper.py b/python/ur_simple_control/util/grippers/robotiq/robotiq_gripper.py
index 977db0c09042be89a0a6c348b36dcdcbcc33d2fb..6d0299b77516b5374cec1684d822f960d587ffd9 100644
--- a/python/ur_simple_control/util/grippers/robotiq/robotiq_gripper.py
+++ b/python/ur_simple_control/util/grippers/robotiq/robotiq_gripper.py
@@ -12,27 +12,35 @@ class RobotiqGripper(AbstractGripper):
     """
     Communicates with the gripper directly, via socket with string commands, leveraging string names for variables.
     """
+
     # WRITE VARIABLES (CAN ALSO READ)
-    ACT = 'ACT'  # act : activate (1 while activated, can be reset to clear fault status)
-    GTO = 'GTO'  # gto : go to (will perform go to with the actions set in pos, for, spe)
-    ATR = 'ATR'  # atr : auto-release (emergency slow move)
-    ADR = 'ADR'  # adr : auto-release direction (open(1) or close(0) during auto-release)
-    FOR = 'FOR'  # for : force (0-255)
-    SPE = 'SPE'  # spe : speed (0-255)
-    POS = 'POS'  # pos : position (0-255), 0 = open
+    ACT = (
+        "ACT"  # act : activate (1 while activated, can be reset to clear fault status)
+    )
+    GTO = (
+        "GTO"  # gto : go to (will perform go to with the actions set in pos, for, spe)
+    )
+    ATR = "ATR"  # atr : auto-release (emergency slow move)
+    ADR = (
+        "ADR"  # adr : auto-release direction (open(1) or close(0) during auto-release)
+    )
+    FOR = "FOR"  # for : force (0-255)
+    SPE = "SPE"  # spe : speed (0-255)
+    POS = "POS"  # pos : position (0-255), 0 = open
     # READ VARIABLES
-    STA = 'STA'  # status (0 = is reset, 1 = activating, 3 = active)
-    PRE = 'PRE'  # position request (echo of last commanded position)
-    OBJ = 'OBJ'  # object detection (0 = moving, 1 = outer grip, 2 = inner grip, 3 = no object at rest)
-    FLT = 'FLT'  # fault (0=ok, see manual for errors if not zero)
+    STA = "STA"  # status (0 = is reset, 1 = activating, 3 = active)
+    PRE = "PRE"  # position request (echo of last commanded position)
+    OBJ = "OBJ"  # object detection (0 = moving, 1 = outer grip, 2 = inner grip, 3 = no object at rest)
+    FLT = "FLT"  # fault (0=ok, see manual for errors if not zero)
 
-    ENCODING = 'UTF-8'  # ASCII and UTF-8 both seem to work
+    ENCODING = "UTF-8"  # ASCII and UTF-8 both seem to work
 
     class GripperStatus(Enum):
         """
         Gripper status reported by the gripper. The integer values have to
         match what the gripper sends.
         """
+
         RESET = 0
         ACTIVATING = 1
         # UNUSED = 2  # This value is currently not used by the gripper firmware
@@ -43,6 +51,7 @@ class RobotiqGripper(AbstractGripper):
         Object status reported by the gripper. The integer values have to match
         what the gripper sends.
         """
+
         MOVING = 0
         STOPPED_OUTER_OBJECT = 1
         STOPPED_INNER_OBJECT = 2
@@ -81,15 +90,15 @@ class RobotiqGripper(AbstractGripper):
         Sends the appropriate command via socket to set the value of n
         variables, and waits for its 'ack' response.
         :param var_dict: Dictionary of variables to set (variable_name, value).
-        :return: True on successful reception of ack, 
-                 false if no ack was received, indicating the set may not 
+        :return: True on successful reception of ack,
+                 false if no ack was received, indicating the set may not
                  have been effective.
         """
         # construct unique command
         cmd = "SET"
         for variable, value in var_dict.items():
             cmd += f" {variable} {str(value)}"
-        cmd += '\n'  # new line is required for the command to finish
+        cmd += "\n"  # new line is required for the command to finish
         # atomic commands send/rcv
         with self.command_lock:
             self.socket.sendall(cmd.encode(self.ENCODING))
@@ -102,7 +111,7 @@ class RobotiqGripper(AbstractGripper):
         variable, and waits for its 'ack' response.
         :param variable: Variable to set.
         :param value: Value to set for the variable.
-        :return: True on successful reception of ack, 
+        :return: True on successful reception of ack,
                  false if no ack was received, indicating the set may not
                  have been effective.
         """
@@ -127,13 +136,15 @@ class RobotiqGripper(AbstractGripper):
         # 2 bytes, instead of an integer. We assume integer here
         var_name, value_str = data.decode(self.ENCODING).split()
         if var_name != variable:
-            raise ValueError(f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'")
+            raise ValueError(
+                f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'"
+            )
         value = int(value_str)
         return value
 
     @staticmethod
     def _is_ack(data: str):
-        return data == b'ack'
+        return data == b"ack"
 
     def _reset(self):
         """
@@ -154,12 +165,11 @@ class RobotiqGripper(AbstractGripper):
         """
         self._set_var(self.ACT, 0)
         self._set_var(self.ATR, 0)
-        while (not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0):
+        while not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0:
             self._set_var(self.ACT, 0)
             self._set_var(self.ATR, 0)
         time.sleep(0.5)
 
-
     def activate(self, auto_calibrate: bool = True):
         """
         Resets the activation flag in the gripper, and sets it back to one,
@@ -194,12 +204,12 @@ class RobotiqGripper(AbstractGripper):
         """
         if not self.is_active():
             self._reset()
-            while (not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0):
+            while not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0:
                 time.sleep(0.01)
 
             self._set_var(self.ACT, 1)
             time.sleep(1.0)
-            while (not self._get_var(self.ACT) == 1 or not self._get_var(self.STA) == 3):
+            while not self._get_var(self.ACT) == 1 or not self._get_var(self.STA) == 3:
                 time.sleep(0.01)
 
         # auto-calibrate position range if desired
@@ -211,7 +221,9 @@ class RobotiqGripper(AbstractGripper):
         Returns whether the gripper is active.
         """
         status = self._get_var(self.STA)
-        return RobotiqGripper.GripperStatus(status) == RobotiqGripper.GripperStatus.ACTIVE
+        return (
+            RobotiqGripper.GripperStatus(status) == RobotiqGripper.GripperStatus.ACTIVE
+        )
 
     def get_min_position(self) -> int:
         """
@@ -267,21 +279,29 @@ class RobotiqGripper(AbstractGripper):
             raise RuntimeError(f"Calibration failed opening to start: {str(status)}")
 
         # try to close as far as possible, and record the number
-        (position, status) = self.move_and_wait_for_pos(self.get_closed_position(), 64, 1)
+        (position, status) = self.move_and_wait_for_pos(
+            self.get_closed_position(), 64, 1
+        )
         if RobotiqGripper.ObjectStatus(status) != RobotiqGripper.ObjectStatus.AT_DEST:
-            raise RuntimeError(f"Calibration failed because of an object: {str(status)}")
+            raise RuntimeError(
+                f"Calibration failed because of an object: {str(status)}"
+            )
         assert position <= self._max_position
         self._max_position = position
 
         # try to open as far as possible, and record the number
         (position, status) = self.move_and_wait_for_pos(self.get_open_position(), 64, 1)
         if RobotiqGripper.ObjectStatus(status) != RobotiqGripper.ObjectStatus.AT_DEST:
-            raise RuntimeError(f"Calibration failed because of an object: {str(status)}")
+            raise RuntimeError(
+                f"Calibration failed because of an object: {str(status)}"
+            )
         assert position >= self._min_position
         self._min_position = position
 
         if log:
-            print(f"Gripper auto-calibrated to [{self.get_min_position()}, {self.get_max_position()}]")
+            print(
+                f"Gripper auto-calibrated to [{self.get_min_position()}, {self.get_max_position()}]"
+            )
 
     def move(self, position: int, speed=255, gripping_force=0) -> Tuple[bool, int]:
         """
@@ -302,7 +322,14 @@ class RobotiqGripper(AbstractGripper):
         clip_for = clip_val(self._min_force, gripping_force, self._max_force)
 
         # moves to the given position with the given speed and gripping_force
-        var_dict = OrderedDict([(self.POS, clip_pos), (self.SPE, clip_spe), (self.FOR, clip_for), (self.GTO, 1)])
+        var_dict = OrderedDict(
+            [
+                (self.POS, clip_pos),
+                (self.SPE, clip_spe),
+                (self.FOR, clip_for),
+                (self.GTO, 1),
+            ]
+        )
         return self._set_vars(var_dict), clip_pos
 
     def open(self):
@@ -311,7 +338,9 @@ class RobotiqGripper(AbstractGripper):
     def close(self):
         self.move(255, 255, 0)
 
-    def move_and_wait_for_pos(self, position: int, speed: int, force: int) -> Tuple[int, ObjectStatus]:  # noqa
+    def move_and_wait_for_pos(
+        self, position: int, speed: int, force: int
+    ) -> Tuple[int, ObjectStatus]:  # noqa
         """
         Sends commands to start moving towards the given position, with the
         specified speed and force, and then waits for the move to complete.
@@ -335,7 +364,9 @@ class RobotiqGripper(AbstractGripper):
 
         # wait until not moving
         cur_obj = self._get_var(self.OBJ)
-        while RobotiqGripper.ObjectStatus(cur_obj) == RobotiqGripper.ObjectStatus.MOVING:
+        while (
+            RobotiqGripper.ObjectStatus(cur_obj) == RobotiqGripper.ObjectStatus.MOVING
+        ):
             cur_obj = self._get_var(self.OBJ)
 
         # report the actual position and the object status
diff --git a/python/ur_simple_control/util/grippers/rs485_robotiq/rs485_robotiq.py b/python/ur_simple_control/util/grippers/rs485_robotiq/rs485_robotiq.py
new file mode 100644
index 0000000000000000000000000000000000000000..e40f457dcfc4b389d1d705fea064838ab8468c70
--- /dev/null
+++ b/python/ur_simple_control/util/grippers/rs485_robotiq/rs485_robotiq.py
@@ -0,0 +1,134 @@
+from ur_simple_control.util.grippers.abstract_gripper import AbstractGripper
+
+import socket
+import time
+import struct
+import threading
+
+
+class RobotiqHand(AbstractGripper):
+    def __init__(self):
+        self.so = None
+        self._cont = False
+        self._sem = None
+        self._heartbeat_th = None
+        self._max_position = 255
+        self._min_position = 0
+
+    def _heartbeat_worker(self):
+        while self._cont:
+            self.status()
+            time.sleep(0.5)
+
+    def connect(self, ip, port):
+        self.so = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
+        self.so.connect((ip, port))
+        self._cont = True
+        self._sem = threading.Semaphore(1)
+        self._heartbeat_th = threading.Thread(target=self._heartbeat_worker)
+        self._heartbeat_th.start()
+
+    def disconnect(self):
+        self._cont = False
+        self._heartbeat_th.join()
+        self._heartbeat_th = None
+        self.so.close()
+        self.so = None
+        self._sem = None
+
+    def _calc_crc(self, command):
+        crc_registor = 0xFFFF
+        for data_byte in command:
+            tmp = crc_registor ^ data_byte
+            for _ in range(8):
+                if tmp & 1 == 1:
+                    tmp = tmp >> 1
+                    tmp = 0xA001 ^ tmp
+                else:
+                    tmp = tmp >> 1
+            crc_registor = tmp
+        crc = bytearray(struct.pack("<H", crc_registor))
+        return crc
+
+    def send_command(self, command):
+        with self._sem:
+            crc = self._calc_crc(command)
+            data = command + crc
+            self.so.sendall(data)
+            time.sleep(0.001)
+            data = self.so.recv(1024)
+        return bytearray(data)
+
+    def status(self):
+        command = bytearray(b"\x09\x03\x07\xd0\x00\x03")
+        return self.send_command(command)
+
+    def reset(self):
+        command = bytearray(b"\x09\x10\x03\xe8\x00\x03\x06\x00\x00\x00\x00\x00\x00")
+        return self.send_command(command)
+
+    def activate(self):
+        command = bytearray(b"\x09\x10\x03\xe8\x00\x03\x06\x01\x00\x00\x00\x00\x00")
+        return self.send_command(command)
+
+    def wait_activate_complete(self):
+        while True:
+            data = self.status()
+            if data[5] != 0x00:
+                return data[3]
+            if data[3] == 0x31 and data[7] < 4:
+                return data[3]
+
+    def adjust(self):
+        self.move(255, 64, 1)
+        (status, position, force) = self.wait_move_complete()
+        self._max_position = position
+        self.move(0, 64, 1)
+        (status, position, force) = self.wait_move_complete()
+        self._min_position = position
+
+    def get_position_mm(self, position):
+        if position > self._max_position:
+            position = self._max_position
+        elif position < self._min_position:
+            position = self._min_position
+        position_mm = (
+            85.0
+            * (self._max_position - position)
+            / (self._max_position - self._min_position)
+        )
+        # print 'max=%d, min=%d, pos=%d pos_mm=%.1f' % (self._max_position, self._min_position, position, position_mm)
+        return position_mm
+
+    def get_force_mA(self, force):
+        return 10.0 * force
+
+    # position: 0x00...open, 0xff...close
+    # speed: 0x00...minimum, 0xff...maximum
+    # force: 0x00...minimum, 0xff...maximum
+    def move(self, position, speed, force):
+        # print('move hand')
+        command = bytearray(b"\x09\x10\x03\xe8\x00\x03\x06\x09\x00\x00\x00\x00\x00")
+        command[10] = position
+        command[11] = speed
+        command[12] = force
+        return self.send_command(command)
+
+    # result: (status, position, force)
+    def wait_move_complete(self):
+        while True:
+            data = self.status()
+            if data[5] != 0x00:
+                return (-1, data[7], data[8])
+            if data[3] == 0x79:
+                return (2, data[7], data[8])
+            if data[3] == 0xB9:
+                return (1, data[7], data[8])
+            if data[3] == 0xF9:
+                return (0, data[7], data[8])
+
+    def open(self):
+        self.move(0, 255, 255)
+
+    def close(self):
+        self.move(255, 255, 0)