diff --git a/dynamixel/channel/__init__.py b/dynamixel/channel/__init__.py
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..954dd7bf52abadedf747f61101f62d706e24dfa0 100644
--- a/dynamixel/channel/__init__.py
+++ b/dynamixel/channel/__init__.py
@@ -0,0 +1,3 @@
+from .channel import Channel
+from .channel import Protocol1
+from .channel import Protocol2
diff --git a/dynamixel/channel/channel.py b/dynamixel/channel/channel.py
new file mode 100644
index 0000000000000000000000000000000000000000..f5e082fa5aac84ec2e0795ff064824543da2dff0
--- /dev/null
+++ b/dynamixel/channel/channel.py
@@ -0,0 +1,115 @@
+#!/usr/bin/python3
+
+import dynamixel_sdk as sdk
+import serial.tools
+import serial.tools.list_ports
+
+class Channel:
+
+    def __init__(self, speed, serial_number=None, device=None):
+        if serial_number != None and device != None:
+            raise Exception('Either serial_number or port should be specified')
+
+        # Hackish way to check baud-rate
+        if sdk.PortHandler.getCFlagBaud(None, speed) < 0:
+            raise Exception('Baud rate error "%d"' % speed)
+
+        # Scan available USB devices
+        devices = {}
+        for v,p,s,d in [ (p.vid, p.pid, p.serial_number, p.device)
+                         for p
+                         in serial.tools.list_ports.comports() ]:
+            devices[s] = d
+            pass
+        if serial_number and serial_number in devices:
+            port = devices[serial_number]
+            pass
+        elif device and device in devices.values():
+            port = device
+            pass
+        elif len(devices) == 1:
+            port = list(devices.values())[0]
+            print("Warning, defaulting to: ", devices)
+        else:
+            raise Exception(f'Select one of: {devices}')
+
+        self.port_handler = sdk.PortHandler(port)
+        if not self.port_handler.openPort():
+            raise Exception("self.port_handler.openPort()")
+        if not self.port_handler.setBaudRate(speed):
+            raise Exception(f"self.port_handler.setBaudRate({speed})")
+            
+        # Check id (i.e. FT2H2W9I)...
+
+        self._protocol = {}
+        pass
+
+    def protocol(self, protocol):
+        if  protocol in self._protocol:
+            return self._protocol[protocol]
+        else:
+            self._protocol[protocol] = protocol(self.port_handler)
+            return self._protocol[protocol]
+        
+    def add(self, device):
+        print('Add', device)
+        pass
+    
+    
+    pass
+
+class Protocol1:
+
+    pass
+
+class Protocol2:
+
+    def __init__(self, port_handler):
+        self.port_handler = port_handler
+        self.packet_handler = sdk.PacketHandler(2.0)
+        pass
+
+    def read(self, servo, row):
+        if row.size == 1:
+            value, comm_result, error = self.packet_handler.read1ByteTxRx(
+                self.port_handler, servo._id, row.address)
+            pass
+        elif row.size == 2:
+            value, comm_result, error = self.packet_handler.read2ByteTxRx(
+                self.port_handler, servo._id, row.address)
+            pass
+        elif row.size == 4:
+            value, comm_result, error = self.packet_handler.read4ByteTxRx(
+                self.port_handler, servo._id, row.address)
+            pass
+        else:
+            raise Exception('Invalid size', row)
+        if comm_result != 0:
+            raise Exception("Comunication error", comm_result)
+        if error != 0:
+            raise Exception("Servo error", error)
+        return value
+        
+    def write(self, servo, row, value):
+        if row.size == 1:
+            comm_result, error = self.packet_handler.write1ByteTxRx(
+                self.port_handler, servo._id, row.address, value)
+            pass
+        elif row.size == 2:
+            comm_result, error = self.packet_handler.write2ByteTxRx(
+                self.port_handler, servo._id, row.address, value)
+            pass
+        elif row.size == 4:
+            comm_result, error = self.packet_handler.write4ByteTxRx(
+                self.port_handler, servo._id, row.address, value)
+            pass
+        else:
+            raise Exception('Invalid size', row)
+        if comm_result != 0:
+            raise Exception("Comunication error", comm_result)
+        if error != 0:
+            raise Exception("Servo error", error)
+        pass
+        
+    pass
+
diff --git a/dynamixel/model/2xc430_w250.py b/dynamixel/model/2xc430_w250.py
deleted file mode 100644
index 80b014c1c45f930207f17b6348455d8b3bd6ca25..0000000000000000000000000000000000000000
--- a/dynamixel/model/2xc430_w250.py
+++ /dev/null
@@ -1,65 +0,0 @@
-
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
-
-class 2XC430_W250(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1160),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=None),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=60),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='velocity_limit', address=44, size=4, default=275),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=700),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
-
-    def __init__(self, id):
-        super(2XC430_W250, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
diff --git a/dynamixel/model/2xl430_w250_t.py b/dynamixel/model/2xl430_w250_t.py
deleted file mode 100644
index 3e3ed98688245e232f930eb816d13fd7eeb206a9..0000000000000000000000000000000000000000
--- a/dynamixel/model/2xl430_w250_t.py
+++ /dev/null
@@ -1,65 +0,0 @@
-
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
-
-class 2XL430_W250_T(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1090),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=None),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=72),
-        Row(name='max_voltage_limit', address=32, size=2, default=140),
-        Row(name='min_voltage_limit', address=34, size=2, default=60),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='velocity_limit', address=44, size=4, default=250),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1800),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=2000),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=640),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
-
-    def __init__(self, id):
-        super(2XL430_W250_T, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
diff --git a/dynamixel/model/ax_12a.py b/dynamixel/model/ax_12a.py
index 4572b88ae87bf14c4d25a0ef2fa5a6febe27687c..026154e9d3f1123a9335a6dc8faea562f4fd956d 100644
--- a/dynamixel/model/ax_12a.py
+++ b/dynamixel/model/ax_12a.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class AX_12A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=12),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=1),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=70),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=140),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=12),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=70),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=140),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(AX_12A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(AX_12A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ax_12w.py b/dynamixel/model/ax_12w.py
index 9ab069dd53caa33f69c11ca48a9d42fc750ac737..12dd749152c6009a71681691356b072c4c93dc72 100644
--- a/dynamixel/model/ax_12w.py
+++ b/dynamixel/model/ax_12w.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class AX_12W(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=300),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=1),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=70),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=140),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=4),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=4),
-        Row(name='cw_compliance_slope', address=28, size=1, default=64),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=64),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=300),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=70),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=140),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=4),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=4),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=64),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=64),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(AX_12W, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(AX_12W, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ax_18a.py b/dynamixel/model/ax_18a.py
index ccdf5e1a1c970497ce89b3da30809b4d19ed5b73..61236cec369d7bb5c04cbc5ed4b4098724ab8d3c 100644
--- a/dynamixel/model/ax_18a.py
+++ b/dynamixel/model/ax_18a.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class AX_18A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=18),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=1),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=75),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=140),
-        Row(name='max_torque', address=14, size=2, default=983),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=18),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=75),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=140),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=983),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(AX_18A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(AX_18A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/dual_xc430_w250.py b/dynamixel/model/dual_xc430_w250.py
new file mode 100644
index 0000000000000000000000000000000000000000..7a4fa491cb5db3e8fd27102bd2b41990808c804f
--- /dev/null
+++ b/dynamixel/model/dual_xc430_w250.py
@@ -0,0 +1,65 @@
+
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
+
+class DUAL_XC430_W250(Servo):
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1160),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=None),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=60),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=275),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=700),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
+
+    def __init__(self, channel, id):
+        super(DUAL_XC430_W250, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/dual_xl430_w250_t.py b/dynamixel/model/dual_xl430_w250_t.py
new file mode 100644
index 0000000000000000000000000000000000000000..5acfe77eeec4c2d3dbf20634d25ca5d8b8f37afa
--- /dev/null
+++ b/dynamixel/model/dual_xl430_w250_t.py
@@ -0,0 +1,65 @@
+
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
+
+class DUAL_XL430_W250_T(Servo):
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1090),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=None),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=72),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=140),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=60),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=250),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1800),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=2000),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=640),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
+
+    def __init__(self, channel, id):
+        super(DUAL_XL430_W250_T, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/dx_113.py b/dynamixel/model/dx_113.py
index ed75651b030ba1c0b3df8e0d5cb360e6f369cccd..45bbf0cd56a490cc1e67bf4d7fbc76baf48a32f7 100644
--- a/dynamixel/model/dx_113.py
+++ b/dynamixel/model/dx_113.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class DX_113(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=113),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=85),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=0),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=0),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=113),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=85),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=0),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=0),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(DX_113, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(DX_113, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/dx_116.py b/dynamixel/model/dx_116.py
index 8aedc021b91bd1ddb5587fe7c14fbd728a231077..ab075c62a4dd12184f3b14fb32261437a496e2b9 100644
--- a/dynamixel/model/dx_116.py
+++ b/dynamixel/model/dx_116.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class DX_116(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=116),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=85),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=0),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=0),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=116),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=85),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=0),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=0),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(DX_116, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(DX_116, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/dx_117.py b/dynamixel/model/dx_117.py
index a8c09e2d4e32793ed031e940bb7d4e50105b5a2d..42d03b52c49bbc70a6dbdbc56735c8f450baa777 100644
--- a/dynamixel/model/dx_117.py
+++ b/dynamixel/model/dx_117.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class DX_117(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=117),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=117),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(DX_117, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(DX_117, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ex_106+.py b/dynamixel/model/ex_106+.py
deleted file mode 100644
index 5fa6e3d9f5105db36e9e5dad4beaae4c9e13713e..0000000000000000000000000000000000000000
--- a/dynamixel/model/ex_106+.py
+++ /dev/null
@@ -1,48 +0,0 @@
-
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
-
-class EX_106+(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=107),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=4095),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=240),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=0),
-        Row(name='sensed_current', address=56, size=2, default=None)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
-
-    def __init__(self, id):
-        super(EX_106+, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
diff --git a/dynamixel/model/ex_106.py b/dynamixel/model/ex_106.py
new file mode 100644
index 0000000000000000000000000000000000000000..adcb33876cc0bb008a450be5e937ca3a24dbc067
--- /dev/null
+++ b/dynamixel/model/ex_106.py
@@ -0,0 +1,48 @@
+
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
+
+class EX_106(Servo):
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=107),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=4095),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=240),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=0),
+        'sensed_current': Row(name='sensed_current', address=56, size=2, default=None)
+    }
+    PROTOCOL = Protocol1
+
+    def __init__(self, channel, id):
+        super(EX_106, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h42_20_s300_r.py b/dynamixel/model/h42_20_s300_r.py
index 8fdb2d4499d7bb410206f9090cf837bf92860de0..27543dfe881fec5ea1879d106ffe5b9405b1c701 100644
--- a/dynamixel/model/h42_20_s300_r.py
+++ b/dynamixel/model/h42_20_s300_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H42_20_S300_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=51200),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=255),
-        Row(name='torque_limit', address=30, size=2, default=465),
-        Row(name='velocity_limit', address=32, size=4, default=10300),
-        Row(name='max_position_limit', address=36, size=4, default=151875),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=40),
-        Row(name='velocity_p_gain', address=588, size=2, default=440),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=51200),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=255),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=465),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=10300),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=151875),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=40),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=440),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H42_20_S300_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H42_20_S300_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h42_20_s300_r_a.py b/dynamixel/model/h42_20_s300_r_a.py
index 471fabb574ad51510e2a953269221c376b830352..6b9af01203979ed37ee3d491adbcb438e411c229 100644
--- a/dynamixel/model/h42_20_s300_r_a.py
+++ b/dynamixel/model/h42_20_s300_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H42_20_S300_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=51201),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=4500),
-        Row(name='acceleration_limit', address=40, size=4, default=10765),
-        Row(name='velocity_limit', address=44, size=4, default=2920),
-        Row(name='max_position_limit', address=48, size=4, default=303454),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=51201),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=4500),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10765),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2920),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=303454),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H42_20_S300_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H42_20_S300_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h54_100_s500_r.py b/dynamixel/model/h54_100_s500_r.py
index 48707606e09eb43afaee68410f3eba92408e6a6f..351376916d2c8ac9ffbd7e6e15aeacc39c9aedea 100644
--- a/dynamixel/model/h54_100_s500_r.py
+++ b/dynamixel/model/h54_100_s500_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H54_100_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=53768),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=310),
-        Row(name='velocity_limit', address=32, size=4, default=17000),
-        Row(name='max_position_limit', address=36, size=4, default=250961),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=256),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=53768),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=310),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=17000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=250961),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=256),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H54_100_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H54_100_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h54_100_s500_r_a.py b/dynamixel/model/h54_100_s500_r_a.py
index fdf100e2f90ae7e1504af2638b87180392196986..8ce2b3328bda3a63a62a605ab8d3000ca75cb6c9 100644
--- a/dynamixel/model/h54_100_s500_r_a.py
+++ b/dynamixel/model/h54_100_s500_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H54_100_S500_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=53769),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=50),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=15900),
-        Row(name='acceleration_limit', address=40, size=4, default=10639),
-        Row(name='velocity_limit', address=44, size=4, default=2920),
-        Row(name='max_position_limit', address=48, size=4, default=501433),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=53769),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=15900),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10639),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2920),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=501433),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H54_100_S500_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H54_100_S500_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h54_200_s500_r.py b/dynamixel/model/h54_200_s500_r.py
index b8fd5e22337d530f2bfda45167bd7b8eacb8a318..185e23335a4a001e738e307b70e58991809477b1 100644
--- a/dynamixel/model/h54_200_s500_r.py
+++ b/dynamixel/model/h54_200_s500_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H54_200_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=54024),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=620),
-        Row(name='velocity_limit', address=32, size=4, default=17000),
-        Row(name='max_position_limit', address=36, size=4, default=250961),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=14),
-        Row(name='velocity_p_gain', address=588, size=2, default=399),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=54024),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=620),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=17000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=250961),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=14),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=399),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H54_200_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H54_200_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/h54_200_s500_r_a.py b/dynamixel/model/h54_200_s500_r_a.py
index d42186b0055ee300a323c0f75596032c2acb61a7..3f33e2038a0b3d0837131c2927c164c49bbeaa42 100644
--- a/dynamixel/model/h54_200_s500_r_a.py
+++ b/dynamixel/model/h54_200_s500_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class H54_200_S500_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=54025),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=22740),
-        Row(name='acceleration_limit', address=40, size=4, default=9982),
-        Row(name='velocity_limit', address=44, size=4, default=2900),
-        Row(name='max_position_limit', address=48, size=4, default=501433),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=54025),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=22740),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=9982),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2900),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=501433),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(H54_200_S500_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(H54_200_S500_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/l42_10_s300_r.py b/dynamixel/model/l42_10_s300_r.py
index e5b188879204295b9c077edd03d669c09234e9e9..6dada2bf5f207914d6daec0c2e54e2181294b812 100644
--- a/dynamixel/model/l42_10_s300_r.py
+++ b/dynamixel/model/l42_10_s300_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class L42_10_S300_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=35072),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=10),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=987),
-        Row(name='velocity_limit', address=32, size=4, default=None),
-        Row(name='max_position_limit', address=36, size=4, default=2048),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=30),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=40),
-        Row(name='velocity_p_gain', address=588, size=2, default=440),
-        Row(name='position_p_gain', address=594, size=2, default=64),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=35072),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=987),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=None),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=2048),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=30),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=40),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=440),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=64),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(L42_10_S300_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(L42_10_S300_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/l54_30_s400_r.py b/dynamixel/model/l54_30_s400_r.py
index c6a0355e9620fea077afde0199f8cd19b49e7391..18373b003fc8ac6e01ba44304e2ad5414ef57efc 100644
--- a/dynamixel/model/l54_30_s400_r.py
+++ b/dynamixel/model/l54_30_s400_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class L54_30_S400_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=37928),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=100),
-        Row(name='velocity_limit', address=32, size=4, default=9000),
-        Row(name='max_position_limit', address=36, size=4, default=144197),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=412),
-        Row(name='position_p_gain', address=594, size=2, default=200),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=37928),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=100),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=9000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=144197),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=412),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=200),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(L54_30_S400_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(L54_30_S400_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/l54_30_s500_r.py b/dynamixel/model/l54_30_s500_r.py
index 5ad457b2d22fa224227a457bb70df3d61786595b..8cdcd3b29d68057b8b20ded7908ca54a17597282 100644
--- a/dynamixel/model/l54_30_s500_r.py
+++ b/dynamixel/model/l54_30_s500_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class L54_30_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=37896),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=100),
-        Row(name='velocity_limit', address=32, size=4, default=9000),
-        Row(name='max_position_limit', address=36, size=4, default=180692),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=256),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=37896),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=100),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=9000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=180692),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=256),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(L54_30_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(L54_30_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/l54_50_s290_r.py b/dynamixel/model/l54_50_s290_r.py
index 0d301b4239149ab59e7aa7b1f824b06ce0fbd016..0c7c06024722b2362b5eb6f6f42aa2af11b0d9e6 100644
--- a/dynamixel/model/l54_50_s290_r.py
+++ b/dynamixel/model/l54_50_s290_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class L54_50_S290_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=38176),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=120),
-        Row(name='velocity_limit', address=32, size=4, default=8000),
-        Row(name='max_position_limit', address=36, size=4, default=103846),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=412),
-        Row(name='position_p_gain', address=594, size=2, default=250),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=38176),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=120),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=8000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=103846),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=412),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=250),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(L54_50_S290_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(L54_50_S290_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/l54_50_s500_r.py b/dynamixel/model/l54_50_s500_r.py
index c047b61da7aafb6a8b5546eb24247e3ed4f880ac..0aeac9513968ded4a32e03c7786f9107024cbf36 100644
--- a/dynamixel/model/l54_50_s500_r.py
+++ b/dynamixel/model/l54_50_s500_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class L54_50_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=38152),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=120),
-        Row(name='velocity_limit', address=32, size=4, default=8000),
-        Row(name='max_position_limit', address=36, size=4, default=180692),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=256),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=38152),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=120),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=8000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=180692),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=256),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(L54_50_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(L54_50_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m42_10_s260_r.py b/dynamixel/model/m42_10_s260_r.py
index 7b738190a26e6bcb9e76ef4426282bc1329e23b5..7038cff3f78d5874f5c5a2d3007866546d7e16e0 100644
--- a/dynamixel/model/m42_10_s260_r.py
+++ b/dynamixel/model/m42_10_s260_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M42_10_S260_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=43288),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=300),
-        Row(name='velocity_limit', address=32, size=4, default=8000),
-        Row(name='max_position_limit', address=36, size=4, default=131593),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=72),
-        Row(name='velocity_p_gain', address=588, size=2, default=520),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=43288),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=300),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=8000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=131593),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=72),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=520),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M42_10_S260_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M42_10_S260_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m42_10_s260_r_a.py b/dynamixel/model/m42_10_s260_r_a.py
index a867531714fcec59803a8860417cda859fe5d149..b11180eaec42aa288514f64a1b26ddc606009be8 100644
--- a/dynamixel/model/m42_10_s260_r_a.py
+++ b/dynamixel/model/m42_10_s260_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M42_10_S260_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=43289),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=300),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=1461),
-        Row(name='acceleration_limit', address=40, size=4, default=10867),
-        Row(name='velocity_limit', address=44, size=4, default=2600),
-        Row(name='max_position_limit', address=48, size=4, default=262931),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=43289),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=300),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=1461),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10867),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2600),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=262931),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M42_10_S260_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M42_10_S260_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m54_40_s250_r.py b/dynamixel/model/m54_40_s250_r.py
index 906479c09401b595d287588e1b70a9807d854397..9e4b8a32aa18ea33108386d2386a4a0b009dcc7b 100644
--- a/dynamixel/model/m54_40_s250_r.py
+++ b/dynamixel/model/m54_40_s250_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M54_40_S250_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=46096),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=120),
-        Row(name='velocity_limit', address=32, size=4, default=8000),
-        Row(name='max_position_limit', address=36, size=4, default=125708),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=256),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=46096),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=120),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=8000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=125708),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=256),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M54_40_S250_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M54_40_S250_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m54_40_s250_r_a.py b/dynamixel/model/m54_40_s250_r_a.py
index a8d8702fb8207bea7643ad655b5ccae165b4fe2d..c17da629fc850e8d8d36fe73fdd30a591d71b783 100644
--- a/dynamixel/model/m54_40_s250_r_a.py
+++ b/dynamixel/model/m54_40_s250_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M54_40_S250_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=46097),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=4470),
-        Row(name='acceleration_limit', address=40, size=4, default=11037),
-        Row(name='velocity_limit', address=44, size=4, default=2840),
-        Row(name='max_position_limit', address=48, size=4, default=251173),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=46097),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=4470),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=11037),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2840),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=251173),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M54_40_S250_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M54_40_S250_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m54_60_s250_r.py b/dynamixel/model/m54_60_s250_r.py
index 6a3136f662df97f7e4b562be7c5f7968c050ebe8..670c061684ece6fb7d35b2f29687645a10b38fbe 100644
--- a/dynamixel/model/m54_60_s250_r.py
+++ b/dynamixel/model/m54_60_s250_r.py
@@ -1,56 +1,56 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M54_60_S250_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=46352),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='homing_offset', address=13, size=4, default=0),
-        Row(name='moving_threshold', address=17, size=4, default=50),
-        Row(name='temperature_limit', address=21, size=1, default=80),
-        Row(name='max_voltage_limit', address=22, size=2, default=400),
-        Row(name='min_voltage_limit', address=24, size=2, default=150),
-        Row(name='acceleration_limit', address=26, size=4, default=None),
-        Row(name='torque_limit', address=30, size=2, default=180),
-        Row(name='velocity_limit', address=32, size=4, default=8000),
-        Row(name='max_position_limit', address=36, size=4, default=125708),
-        Row(name='min_position_limit', address=40, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
-        Row(name='shutdown', address=48, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=562, size=1, default=0),
-        Row(name='led_red', address=563, size=1, default=0),
-        Row(name='led_green', address=564, size=1, default=0),
-        Row(name='led_blue', address=565, size=1, default=0),
-        Row(name='velocity_i_gain', address=586, size=2, default=16),
-        Row(name='velocity_p_gain', address=588, size=2, default=256),
-        Row(name='position_p_gain', address=594, size=2, default=32),
-        Row(name='goal_position', address=596, size=4, default=None),
-        Row(name='goal_velocity', address=600, size=4, default=0),
-        Row(name='goal_torque', address=604, size=2, default=0),
-        Row(name='goal_acceleration', address=606, size=4, default=0),
-        Row(name='moving', address=610, size=1, default=None),
-        Row(name='present_position', address=611, size=4, default=None),
-        Row(name='present_velocity', address=615, size=4, default=None),
-        Row(name='present_current', address=621, size=2, default=None),
-        Row(name='present_input_voltage', address=623, size=2, default=None),
-        Row(name='present_temperature', address=625, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
-        Row(name='registered_instruction', address=890, size=1, default=0),
-        Row(name='status_return_level', address=891, size=1, default=2),
-        Row(name='hardware_error_status', address=892, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=46352),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'homing_offset': RWRow(name='homing_offset', address=13, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=17, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=21, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=22, size=2, default=400),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=24, size=2, default=150),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=26, size=4, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=30, size=2, default=180),
+        'velocity_limit': RWRow(name='velocity_limit', address=32, size=4, default=8000),
+        'max_position_limit': RWRow(name='max_position_limit', address=36, size=4, default=125708),
+        'min_position_limit': RWRow(name='min_position_limit', address=40, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(44, 48)], size=1),
+        'shutdown': RWRow(name='shutdown', address=48, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(49, 561, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=562, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=563, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=564, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=565, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=586, size=2, default=16),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=588, size=2, default=256),
+        'position_p_gain': RWRow(name='position_p_gain', address=594, size=2, default=32),
+        'goal_position': RWRow(name='goal_position', address=596, size=4, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=600, size=4, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=604, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=606, size=4, default=0),
+        'moving': Row(name='moving', address=610, size=1, default=None),
+        'present_position': Row(name='present_position', address=611, size=4, default=None),
+        'present_velocity': Row(name='present_velocity', address=615, size=4, default=None),
+        'present_current': Row(name='present_current', address=621, size=2, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=623, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=625, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(626, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 890)], size=1),
+        'registered_instruction': Row(name='registered_instruction', address=890, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=891, size=1, default=2),
+        'hardware_error_status': Row(name='hardware_error_status', address=892, size=1, default=0)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M54_60_S250_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M54_60_S250_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/m54_60_s250_r_a.py b/dynamixel/model/m54_60_s250_r_a.py
index 4b837afd60b6a4691d09487edf89fa6d44311805..28c2c27c4a967949cb91f7d9ac8db19f11902101 100644
--- a/dynamixel/model/m54_60_s250_r_a.py
+++ b/dynamixel/model/m54_60_s250_r_a.py
@@ -1,71 +1,71 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class M54_60_S250_R_A(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=46353),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=50),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=7980),
-        Row(name='acceleration_limit', address=40, size=4, default=11145),
-        Row(name='velocity_limit', address=44, size=4, default=2830),
-        Row(name='max_position_limit', address=48, size=4, default=251173),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=46353),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=50),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=7980),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=11145),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2830),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=251173),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(M54_60_S250_R_A, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(M54_60_S250_R_A, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_106t_r.py b/dynamixel/model/mx_106t_r.py
index 93c1c1f45f3cd34cd20ce4c43aa64f747985abf5..42c00006c5a5585b9753ae6f525b2f86e4a7605c 100644
--- a/dynamixel/model/mx_106t_r.py
+++ b/dynamixel/model/mx_106t_r.py
@@ -1,53 +1,53 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class MX_106T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=320),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=4095),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=160),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36),
-        Row(name='multi_turn_offset', address=20, size=2, default=0),
-        Row(name='resolution_divider', address=22, size=1, default=1)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='d_gain', address=26, size=1, default=0),
-        Row(name='i_gain', address=27, size=1, default=0),
-        Row(name='p_gain', address=28, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=0),
-        Row(name='realtime_tick', address=50, size=2, default=0),
-        Row(name='current', address=68, size=2, default=0),
-        Row(name='torque_ctrl_mode_enable', address=70, size=1, default=0),
-        Row(name='goal_torque', address=71, size=2, default=0),
-        Row(name='goal_acceleration', address=73, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=320),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=4095),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=160),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36),
+        'multi_turn_offset': RWRow(name='multi_turn_offset', address=20, size=2, default=0),
+        'resolution_divider': RWRow(name='resolution_divider', address=22, size=1, default=1)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'd_gain': RWRow(name='d_gain', address=26, size=1, default=0),
+        'i_gain': RWRow(name='i_gain', address=27, size=1, default=0),
+        'p_gain': RWRow(name='p_gain', address=28, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=0),
+        'realtime_tick': Row(name='realtime_tick', address=50, size=2, default=0),
+        'current': RWRow(name='current', address=68, size=2, default=0),
+        'torque_ctrl_mode_enable': RWRow(name='torque_ctrl_mode_enable', address=70, size=1, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=71, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=73, size=1, default=0)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(MX_106T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_106T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_106t_r_2.0.py b/dynamixel/model/mx_106t_r_2.0.py
index fccc13865fe012a12e828862b927ccbfbff44477..cbb9d72da2f4a6ab1e7da491d1fbf589b649b9d2 100644
--- a/dynamixel/model/mx_106t_r_2.0.py
+++ b/dynamixel/model/mx_106t_r_2.0.py
@@ -1,68 +1,68 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class MX_106T_R_2.0(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=321),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='acceleration_limit', address=40, size=4, default=32767),
-        Row(name='velocity_limit', address=44, size=4, default=210),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=850),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=321),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=32767),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=210),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=850),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(MX_106T_R_2.0, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_106T_R_2.0, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_12w.py b/dynamixel/model/mx_12w.py
index b455db06ccd0b69cd038de471abac1fd5612929c..824e30fb06d430f3ba6a1fe0814a790afafa3fdd 100644
--- a/dynamixel/model/mx_12w.py
+++ b/dynamixel/model/mx_12w.py
@@ -1,49 +1,49 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class MX_12W(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=360),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=1),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=4095),
-        Row(name='temperature_limit', address=11, size=1, default=70),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=160),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36),
-        Row(name='multi_turn_offset', address=20, size=2, default=0),
-        Row(name='resolution_divider', address=22, size=1, default=1)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='d_gain', address=26, size=1, default=8),
-        Row(name='i_gain', address=27, size=1, default=0),
-        Row(name='p_gain', address=28, size=1, default=8),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32),
-        Row(name='realtime_tick', address=50, size=2, default=0),
-        Row(name='goal_acceleration', address=73, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=360),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=4095),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=70),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=160),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36),
+        'multi_turn_offset': RWRow(name='multi_turn_offset', address=20, size=2, default=0),
+        'resolution_divider': RWRow(name='resolution_divider', address=22, size=1, default=1)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'd_gain': RWRow(name='d_gain', address=26, size=1, default=8),
+        'i_gain': RWRow(name='i_gain', address=27, size=1, default=0),
+        'p_gain': RWRow(name='p_gain', address=28, size=1, default=8),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32),
+        'realtime_tick': Row(name='realtime_tick', address=50, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=73, size=1, default=0)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(MX_12W, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_12W, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_28t_r_at_ar.py b/dynamixel/model/mx_28t_r_at_ar.py
index cba2d3abe02678320e64f0722ef2963b00dd1503..7707abf0ed33abdfec5980f5f6cb7c78a4f0c242 100644
--- a/dynamixel/model/mx_28t_r_at_ar.py
+++ b/dynamixel/model/mx_28t_r_at_ar.py
@@ -1,49 +1,49 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class MX_28T_R_AT_AR(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=29),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=4095),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=160),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36),
-        Row(name='multi_turn_offset', address=20, size=2, default=0),
-        Row(name='resolution_divider', address=22, size=1, default=1)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='d_gain', address=26, size=1, default=0),
-        Row(name='i_gain', address=27, size=1, default=0),
-        Row(name='p_gain', address=28, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=0),
-        Row(name='realtime_tick', address=50, size=2, default=0),
-        Row(name='goal_acceleration', address=73, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=29),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=4095),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=160),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36),
+        'multi_turn_offset': RWRow(name='multi_turn_offset', address=20, size=2, default=0),
+        'resolution_divider': RWRow(name='resolution_divider', address=22, size=1, default=1)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'd_gain': RWRow(name='d_gain', address=26, size=1, default=0),
+        'i_gain': RWRow(name='i_gain', address=27, size=1, default=0),
+        'p_gain': RWRow(name='p_gain', address=28, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=0),
+        'realtime_tick': Row(name='realtime_tick', address=50, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=73, size=1, default=0)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(MX_28T_R_AT_AR, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_28T_R_AT_AR, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_28t_r_at_ar_2.0.py b/dynamixel/model/mx_28t_r_at_ar_2.0.py
index 6ceaaa6e8d9b7bddc643ebdfc2a04bceb6473cc6..7553e377b816bcd08d30b699874e134e8bb524d9 100644
--- a/dynamixel/model/mx_28t_r_at_ar_2.0.py
+++ b/dynamixel/model/mx_28t_r_at_ar_2.0.py
@@ -1,66 +1,66 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class MX_28T_R_AT_AR_2.0(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=30),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='acceleration_limit', address=40, size=4, default=32767),
-        Row(name='velocity_limit', address=44, size=4, default=230),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=850),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=30),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=32767),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=230),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=850),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(MX_28T_R_AT_AR_2.0, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_28T_R_AT_AR_2.0, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_64t_r_at_ar.py b/dynamixel/model/mx_64t_r_at_ar.py
index 68b8d2e058797c3c2aba2e5078313cf7f7c28059..3a62ca15ead7ce2e0419f087926adaf714228b44 100644
--- a/dynamixel/model/mx_64t_r_at_ar.py
+++ b/dynamixel/model/mx_64t_r_at_ar.py
@@ -1,52 +1,52 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class MX_64T_R_AT_AR(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=310),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=4095),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=240),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36),
-        Row(name='multi_turn_offset', address=20, size=2, default=0),
-        Row(name='resolution_divider', address=22, size=1, default=1)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='d_gain', address=26, size=1, default=0),
-        Row(name='i_gain', address=27, size=1, default=0),
-        Row(name='p_gain', address=28, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=0),
-        Row(name='realtime_tick', address=50, size=2, default=0),
-        Row(name='current', address=68, size=2, default=0),
-        Row(name='torque_ctrl_mode_enable', address=70, size=1, default=0),
-        Row(name='goal_torque', address=71, size=2, default=0),
-        Row(name='goal_acceleration', address=73, size=1, default=0)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=310),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=4095),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=240),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36),
+        'multi_turn_offset': RWRow(name='multi_turn_offset', address=20, size=2, default=0),
+        'resolution_divider': RWRow(name='resolution_divider', address=22, size=1, default=1)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'd_gain': RWRow(name='d_gain', address=26, size=1, default=0),
+        'i_gain': RWRow(name='i_gain', address=27, size=1, default=0),
+        'p_gain': RWRow(name='p_gain', address=28, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=0),
+        'realtime_tick': Row(name='realtime_tick', address=50, size=2, default=0),
+        'current': RWRow(name='current', address=68, size=2, default=0),
+        'torque_ctrl_mode_enable': RWRow(name='torque_ctrl_mode_enable', address=70, size=1, default=0),
+        'goal_torque': RWRow(name='goal_torque', address=71, size=2, default=0),
+        'goal_acceleration': RWRow(name='goal_acceleration', address=73, size=1, default=0)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(MX_64T_R_AT_AR, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_64T_R_AT_AR, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/mx_64t_r_at_ar_2.0.py b/dynamixel/model/mx_64t_r_at_ar_2.0.py
index 6115df37ed3c8c26305c42d6b5342db69f52450c..579f736912fdfa52ade582ad7e5d2603f604b62a 100644
--- a/dynamixel/model/mx_64t_r_at_ar_2.0.py
+++ b/dynamixel/model/mx_64t_r_at_ar_2.0.py
@@ -1,68 +1,68 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class MX_64T_R_AT_AR_2.0(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=311),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=1941),
-        Row(name='acceleration_limit', address=40, size=4, default=32767),
-        Row(name='velocity_limit', address=44, size=4, default=285),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=850),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=311),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=1941),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=32767),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=285),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=850),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(MX_64T_R_AT_AR_2.0, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(MX_64T_R_AT_AR_2.0, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ph42_020_s300_r.py b/dynamixel/model/ph42_020_s300_r.py
index 32b2269d9343f3e68880bcffc400154bfbf080f5..fbb70f078bfeceb70c4d4beef1928433e458b595 100644
--- a/dynamixel/model/ph42_020_s300_r.py
+++ b/dynamixel/model/ph42_020_s300_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PH42_020_S300_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2000),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=4500),
-        Row(name='acceleration_limit', address=40, size=4, default=10765),
-        Row(name='velocity_limit', address=44, size=4, default=2920),
-        Row(name='max_position_limit', address=48, size=4, default=303454),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2000),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=4500),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10765),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2920),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=303454),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PH42_020_S300_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PH42_020_S300_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ph54_100_s500_r.py b/dynamixel/model/ph54_100_s500_r.py
index 9e80eec3c1f2ffbc53bd69ee9521407379aa30b3..d9e8a737dd8071a072da7651a918c58f6b0531b0 100644
--- a/dynamixel/model/ph54_100_s500_r.py
+++ b/dynamixel/model/ph54_100_s500_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PH54_100_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2010),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=15900),
-        Row(name='acceleration_limit', address=40, size=4, default=10639),
-        Row(name='velocity_limit', address=44, size=4, default=2920),
-        Row(name='max_position_limit', address=48, size=4, default=501433),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2010),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=15900),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10639),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2920),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=501433),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PH54_100_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PH54_100_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/ph54_200_s500_r.py b/dynamixel/model/ph54_200_s500_r.py
index d1fe8571c8ae36d35b1c68abedb0401167db763d..8aff1417cc6aec14af1bb620f0be661e0f6b9be2 100644
--- a/dynamixel/model/ph54_200_s500_r.py
+++ b/dynamixel/model/ph54_200_s500_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PH54_200_S500_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2020),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=22740),
-        Row(name='acceleration_limit', address=40, size=4, default=9982),
-        Row(name='velocity_limit', address=44, size=4, default=2900),
-        Row(name='max_position_limit', address=48, size=4, default=501433),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2020),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=22740),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=9982),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2900),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=501433),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PH54_200_S500_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PH54_200_S500_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/pm42_010_s260_r.py b/dynamixel/model/pm42_010_s260_r.py
index e2bc0494e74618a57ccf29a4d4028cb72630fea7..b82f5d99e11a6e377b5277258287e748fedbc35e 100644
--- a/dynamixel/model/pm42_010_s260_r.py
+++ b/dynamixel/model/pm42_010_s260_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PM42_010_S260_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2100),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=1461),
-        Row(name='acceleration_limit', address=40, size=4, default=10867),
-        Row(name='velocity_limit', address=44, size=4, default=2600),
-        Row(name='max_position_limit', address=48, size=4, default=262931),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2100),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=1461),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=10867),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2600),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=262931),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PM42_010_S260_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PM42_010_S260_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/pm54_040_s250_r.py b/dynamixel/model/pm54_040_s250_r.py
index 8289ef9fef1740996c9b6329438eac9a42295014..db44d55fbe44e31058e0736eee06752291c7e5c7 100644
--- a/dynamixel/model/pm54_040_s250_r.py
+++ b/dynamixel/model/pm54_040_s250_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PM54_040_S250_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2110),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='sencondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=4470),
-        Row(name='acceleration_limit', address=40, size=4, default=11037),
-        Row(name='velocity_limit', address=44, size=4, default=2840),
-        Row(name='max_position_limit', address=48, size=4, default=251173),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2110),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'sencondary_id': RWRow(name='sencondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=4470),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=11037),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2840),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=251173),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PM54_040_S250_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PM54_040_S250_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/pm54_060_s250_r.py b/dynamixel/model/pm54_060_s250_r.py
index ef29728043bfd8b234c876c61909f898fd085f30..19ba4c0514a76e9797f32c95bacd3aee6cade539 100644
--- a/dynamixel/model/pm54_060_s250_r.py
+++ b/dynamixel/model/pm54_060_s250_r.py
@@ -1,72 +1,72 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class PM54_060_S250_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=2120),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=350),
-        Row(name='min_voltage_limit', address=34, size=2, default=150),
-        Row(name='pwm_limit', address=36, size=2, default=2009),
-        Row(name='current_limit', address=38, size=2, default=7980),
-        Row(name='acceleration_limit', address=40, size=4, default=11145),
-        Row(name='velocity_limit', address=44, size=4, default=2830),
-        Row(name='max_position_limit', address=48, size=4, default=251173),
-        Row(name='min_position_limit', address=52, size=4, default=None),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
-        Row(name='shutdown', address=63, size=1, default=58),
-        IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=512, size=1, default=0),
-        Row(name='led_red', address=513, size=1, default=0),
-        Row(name='led_green', address=514, size=1, default=0),
-        Row(name='led_blue', address=515, size=1, default=0),
-        Row(name='status_return_level', address=516, size=1, default=2),
-        Row(name='registered_instruction', address=517, size=1, default=0),
-        Row(name='hardware_error_status', address=518, size=1, default=0),
-        Row(name='velocity_i_gain', address=524, size=2, default=None),
-        Row(name='velocity_p_gain', address=526, size=2, default=None),
-        Row(name='position_d_gain', address=528, size=2, default=None),
-        Row(name='position_i_gain', address=530, size=2, default=None),
-        Row(name='position_p_gain', address=532, size=2, default=None),
-        Row(name='feedforward_2nd_gain', address=536, size=2, default=None),
-        Row(name='feedforward_1st_gain', address=538, size=2, default=None),
-        Row(name='bus_watchdog', address=546, size=1, default=None),
-        Row(name='goal_pwm', address=548, size=2, default=None),
-        Row(name='goal_current', address=550, size=2, default=None),
-        Row(name='goal_velocity', address=552, size=4, default=None),
-        Row(name='profile_acceleration', address=556, size=4, default=None),
-        Row(name='profile_velocity', address=560, size=4, default=None),
-        Row(name='goal_position', address=564, size=4, default=None),
-        Row(name='realtime_tick', address=568, size=2, default=None),
-        Row(name='moving', address=570, size=1, default=None),
-        Row(name='moving_status', address=571, size=1, default=None),
-        Row(name='present_pwm', address=572, size=2, default=None),
-        Row(name='present_current', address=574, size=2, default=None),
-        Row(name='present_velocity', address=576, size=4, default=None),
-        Row(name='present_position', address=580, size=4, default=None),
-        Row(name='velocity_trajectory', address=584, size=4, default=None),
-        Row(name='position_trajectory', address=588, size=4, default=None),
-        Row(name='present_input_voltage', address=592, size=2, default=None),
-        Row(name='present_temperature', address=594, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=2120),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=350),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=150),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=2009),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=7980),
+        'acceleration_limit': RWRow(name='acceleration_limit', address=40, size=4, default=11145),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=2830),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=251173),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=None),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 60)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=58),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 424, 2)], size=2)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=512, size=1, default=0),
+        'led_red': RWRow(name='led_red', address=513, size=1, default=0),
+        'led_green': RWRow(name='led_green', address=514, size=1, default=0),
+        'led_blue': RWRow(name='led_blue', address=515, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=516, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=517, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=518, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=524, size=2, default=None),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=526, size=2, default=None),
+        'position_d_gain': RWRow(name='position_d_gain', address=528, size=2, default=None),
+        'position_i_gain': RWRow(name='position_i_gain', address=530, size=2, default=None),
+        'position_p_gain': RWRow(name='position_p_gain', address=532, size=2, default=None),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=536, size=2, default=None),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=538, size=2, default=None),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=546, size=1, default=None),
+        'goal_pwm': RWRow(name='goal_pwm', address=548, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=550, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=552, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=556, size=4, default=None),
+        'profile_velocity': RWRow(name='profile_velocity', address=560, size=4, default=None),
+        'goal_position': RWRow(name='goal_position', address=564, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=568, size=2, default=None),
+        'moving': Row(name='moving', address=570, size=1, default=None),
+        'moving_status': Row(name='moving_status', address=571, size=1, default=None),
+        'present_pwm': Row(name='present_pwm', address=572, size=2, default=None),
+        'present_current': Row(name='present_current', address=574, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=576, size=4, default=None),
+        'present_position': Row(name='present_position', address=580, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=584, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=588, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=592, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=594, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(600, 608, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(634, 762)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(PM54_060_S250_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(PM54_060_S250_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/rx_10.py b/dynamixel/model/rx_10.py
index 2d3372b5cdd93f12b10d0a57eae59f93bae5abc8..6080a609deeea0e47a14c05c1632c87edb8f5098 100644
--- a/dynamixel/model/rx_10.py
+++ b/dynamixel/model/rx_10.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class RX_10(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=10),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=10),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(RX_10, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(RX_10, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/rx_24f.py b/dynamixel/model/rx_24f.py
index 40b2602840800603f2fac574ab74b518b314aefe..d2403effb9634978060138edc6363319193e8e8a 100644
--- a/dynamixel/model/rx_24f.py
+++ b/dynamixel/model/rx_24f.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class RX_24F(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=24),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=24),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(RX_24F, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(RX_24F, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/rx_28.py b/dynamixel/model/rx_28.py
index 71fbb7d0cbdd083b3e6740ab3834416c99249910..e65e5bea0762113921e1ebda5cbbdd4ce709176b 100644
--- a/dynamixel/model/rx_28.py
+++ b/dynamixel/model/rx_28.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class RX_28(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=28),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=28),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(RX_28, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(RX_28, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/rx_64.py b/dynamixel/model/rx_64.py
index 88dbce4e9c3c1886ddf97ae5ede337d9257bc7a7..e9f22576354bfbc78db12efb2aba5970818dc683 100644
--- a/dynamixel/model/rx_64.py
+++ b/dynamixel/model/rx_64.py
@@ -1,46 +1,46 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol1
 
 class RX_64(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=64),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=34),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='temperature_limit', address=11, size=1, default=80),
-        Row(name='min_voltage_limit', address=12, size=1, default=60),
-        Row(name='max_voltage_limit', address=13, size=1, default=190),
-        Row(name='max_torque', address=14, size=2, default=1023),
-        Row(name='status_return_level', address=16, size=1, default=2),
-        Row(name='alarm_led', address=17, size=1, default=36),
-        Row(name='shutdown', address=18, size=1, default=36)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='cw_compliance_margin', address=26, size=1, default=1),
-        Row(name='ccw_compliance_margin', address=27, size=1, default=1),
-        Row(name='cw_compliance_slope', address=28, size=1, default=32),
-        Row(name='ccw_compliance_slope', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=34, size=2, default=None),
-        Row(name='present_position', address=36, size=2, default=None),
-        Row(name='present_speed', address=38, size=2, default=None),
-        Row(name='present_load', address=40, size=2, default=None),
-        Row(name='present_voltage', address=42, size=1, default=None),
-        Row(name='present_temperature', address=43, size=1, default=None),
-        Row(name='registered', address=44, size=1, default=0),
-        Row(name='moving', address=46, size=1, default=0),
-        Row(name='lock', address=47, size=1, default=0),
-        Row(name='punch', address=48, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol1
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=64),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=34),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'temperature_limit': RWRow(name='temperature_limit', address=11, size=1, default=80),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=12, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=13, size=1, default=190),
+        'max_torque': RWRow(name='max_torque', address=14, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=16, size=1, default=2),
+        'alarm_led': RWRow(name='alarm_led', address=17, size=1, default=36),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=36)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'cw_compliance_margin': RWRow(name='cw_compliance_margin', address=26, size=1, default=1),
+        'ccw_compliance_margin': RWRow(name='ccw_compliance_margin', address=27, size=1, default=1),
+        'cw_compliance_slope': RWRow(name='cw_compliance_slope', address=28, size=1, default=32),
+        'ccw_compliance_slope': RWRow(name='ccw_compliance_slope', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=34, size=2, default=None),
+        'present_position': Row(name='present_position', address=36, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=38, size=2, default=None),
+        'present_load': Row(name='present_load', address=40, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=42, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=43, size=1, default=None),
+        'registered': Row(name='registered', address=44, size=1, default=0),
+        'moving': Row(name='moving', address=46, size=1, default=0),
+        'lock': RWRow(name='lock', address=47, size=1, default=0),
+        'punch': RWRow(name='punch', address=48, size=2, default=32)
+    }
+    PROTOCOL = Protocol1
 
-    def __init__(self, id):
-        super(RX_64, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(RX_64, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xc430_w150_t.py b/dynamixel/model/xc430_w150_t.py
index 4c997a32f220361a95c61b931c1fba63914fd4af..81cfb570019ae1b9b4e7b9845866a5ea807b6f72 100644
--- a/dynamixel/model/xc430_w150_t.py
+++ b/dynamixel/model/xc430_w150_t.py
@@ -1,65 +1,65 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XC430_W150_T(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1070),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=20),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=60),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='velocity_limit', address=44, size=4, default=460),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=460),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1070),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=20),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=60),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=460),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=460),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XC430_W150_T, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XC430_W150_T, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xc430_w240_t.py b/dynamixel/model/xc430_w240_t.py
index ca909543400b844c4fd7d4a6d5527a363485191b..cbe19159f54a62fb75d6ca1effd9b410f11ce189 100644
--- a/dynamixel/model/xc430_w240_t.py
+++ b/dynamixel/model/xc430_w240_t.py
@@ -1,65 +1,65 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XC430_W240_T(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1080),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=60),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='velocity_limit', address=44, size=4, default=306),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=700),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1080),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=60),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=306),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=700),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XC430_W240_T, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XC430_W240_T, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh430_v210_r.py b/dynamixel/model/xh430_v210_r.py
index 7a4c3efa8bd65a5e3f8a88e393f95f70cda5f67c..2faa4b53bfed464b33bd6d09c25341c04e4e6a1b 100644
--- a/dynamixel/model/xh430_v210_r.py
+++ b/dynamixel/model/xh430_v210_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH430_V210_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1050),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=300),
-        Row(name='min_voltage_limit', address=34, size=2, default=110),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=689),
-        Row(name='velocity_limit', address=44, size=4, default=230),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1050),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=300),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=110),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=689),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=230),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH430_V210_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH430_V210_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh430_v350_r.py b/dynamixel/model/xh430_v350_r.py
index db5ae3b26c21b7f77d8eec3e92bd490a74d65c53..f50eba79193180cec1bed4bbf0f0c5cf7a0b6328 100644
--- a/dynamixel/model/xh430_v350_r.py
+++ b/dynamixel/model/xh430_v350_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH430_V350_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1040),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=300),
-        Row(name='min_voltage_limit', address=34, size=2, default=110),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=689),
-        Row(name='velocity_limit', address=44, size=4, default=135),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1040),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=300),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=110),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=689),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=135),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH430_V350_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH430_V350_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh430_w210_t_r.py b/dynamixel/model/xh430_w210_t_r.py
index 3bd9ae23bd6f4854c40bcd74bd1d1bfead9417e3..c731ead05af54fa628dedc6a16b7d20cdec3618e 100644
--- a/dynamixel/model/xh430_w210_t_r.py
+++ b/dynamixel/model/xh430_w210_t_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH430_W210_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1010),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=648),
-        Row(name='velocity_limit', address=44, size=4, default=210),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=900),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1010),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=648),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=210),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=900),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH430_W210_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH430_W210_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh430_w350_t_r.py b/dynamixel/model/xh430_w350_t_r.py
index 3b28cb98b7c3926b06fb8e9d7485287bf9372522..860ce9ecb0d38f7e7f26364478e10fae2b891397 100644
--- a/dynamixel/model/xh430_w350_t_r.py
+++ b/dynamixel/model/xh430_w350_t_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH430_W350_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1000),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=648),
-        Row(name='velocity_limit', address=44, size=4, default=130),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=900),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1000),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=648),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=130),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=900),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH430_W350_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH430_W350_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh540_v150_r.py b/dynamixel/model/xh540_v150_r.py
index 8aacad073bbef6852e199ee339d0884895ed20b8..51acc8fc29040632439dba628b96b6d32819bfae 100644
--- a/dynamixel/model/xh540_v150_r.py
+++ b/dynamixel/model/xh540_v150_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH540_V150_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1150),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=300),
-        Row(name='min_voltage_limit', address=34, size=2, default=110),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=230),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1150),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=300),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=110),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=230),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH540_V150_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH540_V150_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh540_v270_r.py b/dynamixel/model/xh540_v270_r.py
index d54166c0ea04c9ac36e23b4c624f59f69ca41d3b..ad377fc7984f476e614373035f8a3459b9a1a3fc 100644
--- a/dynamixel/model/xh540_v270_r.py
+++ b/dynamixel/model/xh540_v270_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH540_V270_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1140),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=300),
-        Row(name='min_voltage_limit', address=34, size=2, default=110),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=128),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1140),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=300),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=110),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=128),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH540_V270_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH540_V270_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh540_w150_t_r.py b/dynamixel/model/xh540_w150_t_r.py
index 68447a1abed3d28225eef67e2fa7eae0182d81ae..b6ab17c60da1da3419d930d8e778c49b679bffb1 100644
--- a/dynamixel/model/xh540_w150_t_r.py
+++ b/dynamixel/model/xh540_w150_t_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH540_W150_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1110),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=300),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1110),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=300),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH540_W150_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH540_W150_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xh540_w270_t_r.py b/dynamixel/model/xh540_w270_t_r.py
index 5cb54575de6b8908db88b35a831a27a5f69a2397..86466896aed2eeaf70ec9fcecc84a5e07612b2d4 100644
--- a/dynamixel/model/xh540_w270_t_r.py
+++ b/dynamixel/model/xh540_w270_t_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XH540_W270_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1100),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=167),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1100),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=167),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XH540_W270_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XH540_W270_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xl430_w250_t.py b/dynamixel/model/xl430_w250_t.py
index 66a0e4004e07afa3d4d16303a6b0d0b3d79d3274..ef5d8e3db6c06fad4c1e4a9b2662f47fb804d63f 100644
--- a/dynamixel/model/xl430_w250_t.py
+++ b/dynamixel/model/xl430_w250_t.py
@@ -1,65 +1,65 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XL430_W250_T(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1060),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=72),
-        Row(name='max_voltage_limit', address=32, size=2, default=140),
-        Row(name='min_voltage_limit', address=34, size=2, default=60),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='velocity_limit', address=44, size=4, default=265),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1000),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=4000),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=640),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_load', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1060),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=72),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=140),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=60),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=265),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1000),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=4000),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=640),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_load': Row(name='present_load', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XL430_W250_T, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XL430_W250_T, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xl_320.py b/dynamixel/model/xl_320.py
index fc3e80f07fb84b5a1fa74ef5fc9693359834dc14..dc735aed42cc0d4d59dd798a84d566b13e60276a 100644
--- a/dynamixel/model/xl_320.py
+++ b/dynamixel/model/xl_320.py
@@ -1,45 +1,45 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XL_320(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=350),
-        Row(name='firmware_version', address=2, size=1, default=None),
-        Row(name='id', address=3, size=1, default=1),
-        Row(name='baud_rate', address=4, size=1, default=3),
-        Row(name='return_delay_time', address=5, size=1, default=250),
-        Row(name='cw_angle_limit', address=6, size=2, default=0),
-        Row(name='ccw_angle_limit', address=8, size=2, default=1023),
-        Row(name='control_mode', address=11, size=1, default=2),
-        Row(name='temperature_limit', address=12, size=1, default=65),
-        Row(name='min_voltage_limit', address=13, size=1, default=60),
-        Row(name='max_voltage_limit', address=14, size=1, default=90),
-        Row(name='max_torque', address=15, size=2, default=1023),
-        Row(name='status_return_level', address=17, size=1, default=2),
-        Row(name='shutdown', address=18, size=1, default=3)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=24, size=1, default=0),
-        Row(name='led', address=25, size=1, default=0),
-        Row(name='d_gain', address=27, size=1, default=0),
-        Row(name='i_gain', address=28, size=1, default=0),
-        Row(name='p_gain', address=29, size=1, default=32),
-        Row(name='goal_position', address=30, size=2, default=None),
-        Row(name='moving_speed', address=32, size=2, default=None),
-        Row(name='torque_limit', address=35, size=2, default=None),
-        Row(name='present_position', address=37, size=2, default=None),
-        Row(name='present_speed', address=39, size=2, default=None),
-        Row(name='present_load', address=41, size=2, default=None),
-        Row(name='present_voltage', address=45, size=1, default=None),
-        Row(name='present_temperature', address=46, size=1, default=None),
-        Row(name='registered', address=47, size=1, default=0),
-        Row(name='moving', address=49, size=1, default=0),
-        Row(name='hardware_error_status', address=50, size=1, default=0),
-        Row(name='punch', address=51, size=2, default=32)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=350),
+        'firmware_version': Row(name='firmware_version', address=2, size=1, default=None),
+        'id': RWRow(name='id', address=3, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=4, size=1, default=3),
+        'return_delay_time': RWRow(name='return_delay_time', address=5, size=1, default=250),
+        'cw_angle_limit': RWRow(name='cw_angle_limit', address=6, size=2, default=0),
+        'ccw_angle_limit': RWRow(name='ccw_angle_limit', address=8, size=2, default=1023),
+        'control_mode': RWRow(name='control_mode', address=11, size=1, default=2),
+        'temperature_limit': RWRow(name='temperature_limit', address=12, size=1, default=65),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=13, size=1, default=60),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=14, size=1, default=90),
+        'max_torque': RWRow(name='max_torque', address=15, size=2, default=1023),
+        'status_return_level': RWRow(name='status_return_level', address=17, size=1, default=2),
+        'shutdown': RWRow(name='shutdown', address=18, size=1, default=3)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=24, size=1, default=0),
+        'led': RWRow(name='led', address=25, size=1, default=0),
+        'd_gain': RWRow(name='d_gain', address=27, size=1, default=0),
+        'i_gain': RWRow(name='i_gain', address=28, size=1, default=0),
+        'p_gain': RWRow(name='p_gain', address=29, size=1, default=32),
+        'goal_position': RWRow(name='goal_position', address=30, size=2, default=None),
+        'moving_speed': RWRow(name='moving_speed', address=32, size=2, default=None),
+        'torque_limit': RWRow(name='torque_limit', address=35, size=2, default=None),
+        'present_position': Row(name='present_position', address=37, size=2, default=None),
+        'present_speed': Row(name='present_speed', address=39, size=2, default=None),
+        'present_load': Row(name='present_load', address=41, size=2, default=None),
+        'present_voltage': Row(name='present_voltage', address=45, size=1, default=None),
+        'present_temperature': Row(name='present_temperature', address=46, size=1, default=None),
+        'registered': Row(name='registered', address=47, size=1, default=0),
+        'moving': Row(name='moving', address=49, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=50, size=1, default=0),
+        'punch': RWRow(name='punch', address=51, size=2, default=32)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XL_320, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XL_320, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xm430_w210_t_r.py b/dynamixel/model/xm430_w210_t_r.py
index 8fd374f0e8747cde3da6e1487616422e369ef8e7..0106d0f31bcc22097f7b6525f531c1e1056badbc 100644
--- a/dynamixel/model/xm430_w210_t_r.py
+++ b/dynamixel/model/xm430_w210_t_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XM430_W210_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1030),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=1193),
-        Row(name='velocity_limit', address=44, size=4, default=330),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1030),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=1193),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=330),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XM430_W210_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XM430_W210_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xm430_w350_t_r.py b/dynamixel/model/xm430_w350_t_r.py
index 9c16b6c3706197ce3e38761423c676b1c1c69f0c..4f96f04b8d8d8d21d379c4eee7bb5b9a5b00e50c 100644
--- a/dynamixel/model/xm430_w350_t_r.py
+++ b/dynamixel/model/xm430_w350_t_r.py
@@ -1,67 +1,67 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XM430_W350_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1020),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=1193),
-        Row(name='velocity_limit', address=44, size=4, default=200),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1020),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=1193),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=200),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XM430_W350_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XM430_W350_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xm540_w150_t_r.py b/dynamixel/model/xm540_w150_t_r.py
index 668d68f4ec5bc9f3b34dec7cf4bd577a8740f5ff..85adab307fbeca39f58a4faf662d22fd2bd5a18c 100644
--- a/dynamixel/model/xm540_w150_t_r.py
+++ b/dynamixel/model/xm540_w150_t_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XM540_W150_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1130),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=230),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1130),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=230),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XM540_W150_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XM540_W150_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xm540_w270_t_r.py b/dynamixel/model/xm540_w270_t_r.py
index 4247363f47835a468cf90ec6e94253f6ac56b928..38568752d687f06eebf21fb1f34bb29944847dba 100644
--- a/dynamixel/model/xm540_w270_t_r.py
+++ b/dynamixel/model/xm540_w270_t_r.py
@@ -1,69 +1,69 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XM540_W270_T_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1120),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=128),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='led', address=65, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1120),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=128),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'external_port_mode': IndirectRow(name='external_port_mode', addresses=[range(56, 59)], size=1),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'led': RWRow(name='led', address=65, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'external_port_data': IndirectRow(name='external_port_data', addresses=[range(152, 158, 2)], size=2),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XM540_W270_T_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XM540_W270_T_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xw540_t140_r.py b/dynamixel/model/xw540_t140_r.py
index b54630f6d7f4c5cc0b9d56ac3a4e777a60100d20..a0fa43ecd2e4c633315315da057d376db3ee3048 100644
--- a/dynamixel/model/xw540_t140_r.py
+++ b/dynamixel/model/xw540_t140_r.py
@@ -1,66 +1,66 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XW540_T140_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1180),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=304),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1180),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=304),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XW540_T140_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XW540_T140_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/model/xw540_t260_r.py b/dynamixel/model/xw540_t260_r.py
index 3dfb8678d6e10f1dc6e23b7bc4508bbf0aa67137..b4d92c72d6d72b89472fda7c029aceefa2cce0da 100644
--- a/dynamixel/model/xw540_t260_r.py
+++ b/dynamixel/model/xw540_t260_r.py
@@ -1,66 +1,66 @@
 
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import Protocol2
 
 class XW540_T260_R(Servo):
-    EEPROM = [
-        Row(name='model_number', address=0, size=2, default=1170),
-        Row(name='model_information', address=2, size=4, default=None),
-        Row(name='firmware_version', address=6, size=1, default=None),
-        Row(name='id', address=7, size=1, default=1),
-        Row(name='baud_rate', address=8, size=1, default=1),
-        Row(name='return_delay_time', address=9, size=1, default=250),
-        Row(name='drive_mode', address=10, size=1, default=0),
-        Row(name='operating_mode', address=11, size=1, default=3),
-        Row(name='secondary_id', address=12, size=1, default=255),
-        Row(name='protocol_type', address=13, size=1, default=2),
-        Row(name='homing_offset', address=20, size=4, default=0),
-        Row(name='moving_threshold', address=24, size=4, default=10),
-        Row(name='temperature_limit', address=31, size=1, default=80),
-        Row(name='max_voltage_limit', address=32, size=2, default=160),
-        Row(name='min_voltage_limit', address=34, size=2, default=95),
-        Row(name='pwm_limit', address=36, size=2, default=885),
-        Row(name='current_limit', address=38, size=2, default=2047),
-        Row(name='velocity_limit', address=44, size=4, default=167),
-        Row(name='max_position_limit', address=48, size=4, default=4095),
-        Row(name='min_position_limit', address=52, size=4, default=0),
-        Row(name='shutdown', address=63, size=1, default=52)
-    ]
-    RAM = [
-        Row(name='torque_enable', address=64, size=1, default=0),
-        Row(name='status_return_level', address=68, size=1, default=2),
-        Row(name='registered_instruction', address=69, size=1, default=0),
-        Row(name='hardware_error_status', address=70, size=1, default=0),
-        Row(name='velocity_i_gain', address=76, size=2, default=1920),
-        Row(name='velocity_p_gain', address=78, size=2, default=100),
-        Row(name='position_d_gain', address=80, size=2, default=0),
-        Row(name='position_i_gain', address=82, size=2, default=0),
-        Row(name='position_p_gain', address=84, size=2, default=800),
-        Row(name='feedforward_2nd_gain', address=88, size=2, default=0),
-        Row(name='feedforward_1st_gain', address=90, size=2, default=0),
-        Row(name='bus_watchdog', address=98, size=1, default=0),
-        Row(name='goal_pwm', address=100, size=2, default=None),
-        Row(name='goal_current', address=102, size=2, default=None),
-        Row(name='goal_velocity', address=104, size=4, default=None),
-        Row(name='profile_acceleration', address=108, size=4, default=0),
-        Row(name='profile_velocity', address=112, size=4, default=0),
-        Row(name='goal_position', address=116, size=4, default=None),
-        Row(name='realtime_tick', address=120, size=2, default=None),
-        Row(name='moving', address=122, size=1, default=0),
-        Row(name='moving_status', address=123, size=1, default=0),
-        Row(name='present_pwm', address=124, size=2, default=None),
-        Row(name='present_current', address=126, size=2, default=None),
-        Row(name='present_velocity', address=128, size=4, default=None),
-        Row(name='present_position', address=132, size=4, default=None),
-        Row(name='velocity_trajectory', address=136, size=4, default=None),
-        Row(name='position_trajectory', address=140, size=4, default=None),
-        Row(name='present_input_voltage', address=144, size=2, default=None),
-        Row(name='present_temperature', address=146, size=1, default=None),
-        IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
-        IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
-    ]
-    PROTOCOL = dynamixel.protocol.Protocol2
+    EEPROM = {
+        'model_number': Row(name='model_number', address=0, size=2, default=1170),
+        'model_information': Row(name='model_information', address=2, size=4, default=None),
+        'firmware_version': Row(name='firmware_version', address=6, size=1, default=None),
+        'id': RWRow(name='id', address=7, size=1, default=1),
+        'baud_rate': RWRow(name='baud_rate', address=8, size=1, default=1),
+        'return_delay_time': RWRow(name='return_delay_time', address=9, size=1, default=250),
+        'drive_mode': RWRow(name='drive_mode', address=10, size=1, default=0),
+        'operating_mode': RWRow(name='operating_mode', address=11, size=1, default=3),
+        'secondary_id': RWRow(name='secondary_id', address=12, size=1, default=255),
+        'protocol_type': RWRow(name='protocol_type', address=13, size=1, default=2),
+        'homing_offset': RWRow(name='homing_offset', address=20, size=4, default=0),
+        'moving_threshold': RWRow(name='moving_threshold', address=24, size=4, default=10),
+        'temperature_limit': RWRow(name='temperature_limit', address=31, size=1, default=80),
+        'max_voltage_limit': RWRow(name='max_voltage_limit', address=32, size=2, default=160),
+        'min_voltage_limit': RWRow(name='min_voltage_limit', address=34, size=2, default=95),
+        'pwm_limit': RWRow(name='pwm_limit', address=36, size=2, default=885),
+        'current_limit': RWRow(name='current_limit', address=38, size=2, default=2047),
+        'velocity_limit': RWRow(name='velocity_limit', address=44, size=4, default=167),
+        'max_position_limit': RWRow(name='max_position_limit', address=48, size=4, default=4095),
+        'min_position_limit': RWRow(name='min_position_limit', address=52, size=4, default=0),
+        'shutdown': RWRow(name='shutdown', address=63, size=1, default=52)
+    }
+    RAM = {
+        'torque_enable': RWRow(name='torque_enable', address=64, size=1, default=0),
+        'status_return_level': RWRow(name='status_return_level', address=68, size=1, default=2),
+        'registered_instruction': Row(name='registered_instruction', address=69, size=1, default=0),
+        'hardware_error_status': Row(name='hardware_error_status', address=70, size=1, default=0),
+        'velocity_i_gain': RWRow(name='velocity_i_gain', address=76, size=2, default=1920),
+        'velocity_p_gain': RWRow(name='velocity_p_gain', address=78, size=2, default=100),
+        'position_d_gain': RWRow(name='position_d_gain', address=80, size=2, default=0),
+        'position_i_gain': RWRow(name='position_i_gain', address=82, size=2, default=0),
+        'position_p_gain': RWRow(name='position_p_gain', address=84, size=2, default=800),
+        'feedforward_2nd_gain': RWRow(name='feedforward_2nd_gain', address=88, size=2, default=0),
+        'feedforward_1st_gain': RWRow(name='feedforward_1st_gain', address=90, size=2, default=0),
+        'bus_watchdog': RWRow(name='bus_watchdog', address=98, size=1, default=0),
+        'goal_pwm': RWRow(name='goal_pwm', address=100, size=2, default=None),
+        'goal_current': RWRow(name='goal_current', address=102, size=2, default=None),
+        'goal_velocity': RWRow(name='goal_velocity', address=104, size=4, default=None),
+        'profile_acceleration': RWRow(name='profile_acceleration', address=108, size=4, default=0),
+        'profile_velocity': RWRow(name='profile_velocity', address=112, size=4, default=0),
+        'goal_position': RWRow(name='goal_position', address=116, size=4, default=None),
+        'realtime_tick': Row(name='realtime_tick', address=120, size=2, default=None),
+        'moving': Row(name='moving', address=122, size=1, default=0),
+        'moving_status': Row(name='moving_status', address=123, size=1, default=0),
+        'present_pwm': Row(name='present_pwm', address=124, size=2, default=None),
+        'present_current': Row(name='present_current', address=126, size=2, default=None),
+        'present_velocity': Row(name='present_velocity', address=128, size=4, default=None),
+        'present_position': Row(name='present_position', address=132, size=4, default=None),
+        'velocity_trajectory': Row(name='velocity_trajectory', address=136, size=4, default=None),
+        'position_trajectory': Row(name='position_trajectory', address=140, size=4, default=None),
+        'present_input_voltage': Row(name='present_input_voltage', address=144, size=2, default=None),
+        'present_temperature': Row(name='present_temperature', address=146, size=1, default=None),
+        'indirect_address': IndirectRow(name='indirect_address', addresses=[range(168, 224, 2), range(578, 634, 2)], size=2),
+        'indirect_data': IndirectRow(name='indirect_data', addresses=[range(224, 252), range(634, 662)], size=1)
+    }
+    PROTOCOL = Protocol2
 
-    def __init__(self, id):
-        super(XW540_T260_R, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super(XW540_T260_R, self).__init__(channel=channel, id=id)
diff --git a/dynamixel/protocol/Protocol2.py b/dynamixel/protocol/Protocol2.py
deleted file mode 100644
index e4fbcd3d64d9a02d1a87cee5ca322cbba98b60db..0000000000000000000000000000000000000000
--- a/dynamixel/protocol/Protocol2.py
+++ /dev/null
@@ -1,2 +0,0 @@
-class Protocol2:
-    pass
diff --git a/dynamixel/protocol/__init__.py b/dynamixel/protocol/__init__.py
deleted file mode 100644
index 27f95fa05da874602d72216cd44249757096d8eb..0000000000000000000000000000000000000000
--- a/dynamixel/protocol/__init__.py
+++ /dev/null
@@ -1 +0,0 @@
-from . import Protocol2
diff --git a/dynamixel/servo/__init__.py b/dynamixel/servo/__init__.py
index ca0b8063733eb45217fe963f57bb3f183e6e822f..3f2700c53cf8e163fa5be6998f7c8b4e7bca7418 100644
--- a/dynamixel/servo/__init__.py
+++ b/dynamixel/servo/__init__.py
@@ -1,13 +1,52 @@
 class Servo:
-    def __init__(self, id, eeprom, ram, protocol):
+
+    def __init__(self, channel, id):
+        self._channel = channel
         self._id = id
-        self._control_table = dict(
-            [ (r.name, r) for r in eeprom ] +
-            [ (r.name, r) for r in ram ]
-        )
-        self.protocol = protocol
+        self._accessor = {}
+        self._protocol = channel.protocol(self.PROTOCOL)
+        if self.model_number.read() != self.model_number.default:
+            raise Exception("Wrong servo connected")
+        pass
+
+    def __getattr__(self, key):
+        if key in self._accessor:
+            return self._accessor[key]
+        elif key in self.EEPROM:
+            self._accessor[key] = self.EEPROM[key].accessor(self)
+            return self._accessor[key]
+        elif key in self.RAM:
+            self._accessor[key] = self.RAM[key].accessor(self)
+            return self._accessor[key]
+        raise KeyError(key)
+
+    def read(self, row):
+        return self._protocol.read(self, row)
+
+    def write(self, row, value):
+        self._protocol.write(self, row, value)
+        pass
+
+    pass
+
+class Accessor:
+
+    def __init__(self, row, servo):
+        self._row = row
+        self._servo = servo
+        self.default = self._row.default
         pass
 
+    def read(self):
+        return self._servo.read(self._row)
+
+    pass
+
+class RWAccessor(Accessor):
+
+    def write(self, value):
+        return self._servo.write(self._row, value)
+
     pass
 
 class Row:
@@ -18,7 +57,21 @@ class Row:
         self.size = size
         self.default = default
         pass
+
+    def accessor(self, servo):
+        return Accessor(self, servo)
     
+    def __repr__(self):
+        return (f"{self.__class__.__name__}('{self.name}', {self.address}, "
+                f"{self.size}, {self.default})")
+
+    pass
+
+class RWRow(Row):
+
+    def accessor(self, servo):
+        return RWAccessor(self, servo)
+
     pass
 
 class IndirectRow:
@@ -26,5 +79,9 @@ class IndirectRow:
         self.name = name
         self.addresses = addresses
         self.size = size
-       
+        pass
+
+    def accessor(self, channel):
+        raise Exception("Implement me")
+
     pass
diff --git a/three_wheel_example.py b/three_wheel_example.py
new file mode 100755
index 0000000000000000000000000000000000000000..65de1b3c68f332cca93fa61ef214ca0dc16d92f5
--- /dev/null
+++ b/three_wheel_example.py
@@ -0,0 +1,33 @@
+#!/usr/bin/python3
+
+from dynamixel.model.xm430_w210_t_r import XM430_W210_T_R
+import dynamixel.channel
+import time
+
+if __name__ == '__main__':
+    channel = dynamixel.channel.Channel(speed=1000000)
+    servos = [ XM430_W210_T_R(channel, 1),
+               XM430_W210_T_R(channel, 2),
+               XM430_W210_T_R(channel, 3) ]
+    for s in servos:
+        s.torque_enable.write(0)
+        print(s.model_number.read(), s.id.read())
+        s.operating_mode.write(1)
+        s.bus_watchdog.write(0) # Clear old watchdog error
+        s.bus_watchdog.write(100) # 2 second timeout
+        s.torque_enable.write(1)
+        pass
+    for i in range(331):
+        print(i)
+        for s in servos:
+            s.goal_velocity.write(i)
+            pass
+        print([ s.present_position.read() for s in servos ])
+        time.sleep(0.1)
+    for i in range(330,100,-10):
+        print(i)
+        for s in servos:
+            s.goal_velocity.write(i)
+            pass
+        print([ s.present_position.read() for s in servos ])
+        time.sleep(0.1)
diff --git a/tools/html2desc.py b/tools/html2desc.py
index c9afa6b70b3367d1e7258762cf9b409601cd8df0..15bda5a5c82f4e2be4ea5dbeabba19c9e380c05b 100755
--- a/tools/html2desc.py
+++ b/tools/html2desc.py
@@ -174,7 +174,11 @@ def Parse(path):
                 title = (st.text
                          .replace('/', '_')
                          .replace('(', '_')
-                         .replace(')', ''))
+                         .replace(')', '')
+                         .replace('+', ''))
+                if m := re.match('^2(.*)$', title):
+                    title = f'DUAL-{m.group(1)}'
+                    pass
                 pass
             elif st.tag == 'table':
                 # Only save control tables
@@ -223,7 +227,7 @@ for path in sys.argv[1:]:
                         pass
                     yield range(start, current + size, size)
                     pass
-                return (f"IndirectRow(name='{r[1].name}', "
+                return (f"'{r[1].name}': IndirectRow(name='{r[1].name}', "
                         f"addresses={list(ranges(r))}, "
                         f"size={r[1].size})")
             def expand_row(r):
@@ -231,7 +235,9 @@ for path in sys.argv[1:]:
                     return expand_indirect_row(r)
                     pass
                 else:
-                    return (f"Row(name='{r.name}', "
+                    return (f"'{r.name}': "
+                            f"{'W' in r.access and 'RW' or ''}Row("
+                            f"name='{r.name}', "
                             f"address={r.address}, "
                             f"size={r.size}, default={r.default})")
                     pass
@@ -244,21 +250,21 @@ for path in sys.argv[1:]:
             py_model = model.replace('-', '_')
             indent = ',\n        '
             f.write(f'''
-from dynamixel.servo import Servo, Row, IndirectRow
-import dynamixel.protocol
+from dynamixel.servo import Servo
+from dynamixel.servo import Row, RWRow, IndirectRow
+from dynamixel.channel import {max(protocol)}
 
 class {py_model}(Servo):
-    EEPROM = [
+    EEPROM = {{
         {indent.join(expand_table(EEPROM[model]))}
-    ]
-    RAM = [
+    }}
+    RAM = {{
         {indent.join(expand_table(RAM[model]))}
-    ]
-    PROTOCOL = dynamixel.protocol.{max(protocol)}
+    }}
+    PROTOCOL = {max(protocol)}
 
-    def __init__(self, id):
-        super({py_model}, self).__init__(
-            id=id, eeprom=self.EEPROM, ram=self.RAM, protocol=self.PROTOCOL)
+    def __init__(self, channel, id):
+        super({py_model}, self).__init__(channel=channel, id=id)
 ''')
             pass
         pass