From ce15fa78252a88f87a72f6ee03d590bbaebf9f08 Mon Sep 17 00:00:00 2001 From: Anders Blomdell <anders.blomdell@control.lth.se> Date: Thu, 10 Dec 2020 13:33:34 +0100 Subject: [PATCH] First working version --- dynamixel/channel/__init__.py | 3 + dynamixel/channel/channel.py | 115 ++++++++++++++++++++++ dynamixel/model/2xc430_w250.py | 65 ------------ dynamixel/model/2xl430_w250_t.py | 65 ------------ dynamixel/model/ax_12a.py | 84 ++++++++-------- dynamixel/model/ax_12w.py | 84 ++++++++-------- dynamixel/model/ax_18a.py | 84 ++++++++-------- dynamixel/model/dual_xc430_w250.py | 65 ++++++++++++ dynamixel/model/dual_xl430_w250_t.py | 65 ++++++++++++ dynamixel/model/dx_113.py | 84 ++++++++-------- dynamixel/model/dx_116.py | 84 ++++++++-------- dynamixel/model/dx_117.py | 84 ++++++++-------- dynamixel/model/ex_106+.py | 48 --------- dynamixel/model/ex_106.py | 48 +++++++++ dynamixel/model/h42_20_s300_r.py | 104 ++++++++++---------- dynamixel/model/h42_20_s300_r_a.py | 134 ++++++++++++------------- dynamixel/model/h54_100_s500_r.py | 104 ++++++++++---------- dynamixel/model/h54_100_s500_r_a.py | 134 ++++++++++++------------- dynamixel/model/h54_200_s500_r.py | 104 ++++++++++---------- dynamixel/model/h54_200_s500_r_a.py | 134 ++++++++++++------------- dynamixel/model/l42_10_s300_r.py | 104 ++++++++++---------- dynamixel/model/l54_30_s400_r.py | 104 ++++++++++---------- dynamixel/model/l54_30_s500_r.py | 104 ++++++++++---------- dynamixel/model/l54_50_s290_r.py | 104 ++++++++++---------- dynamixel/model/l54_50_s500_r.py | 104 ++++++++++---------- dynamixel/model/m42_10_s260_r.py | 104 ++++++++++---------- dynamixel/model/m42_10_s260_r_a.py | 134 ++++++++++++------------- dynamixel/model/m54_40_s250_r.py | 104 ++++++++++---------- dynamixel/model/m54_40_s250_r_a.py | 134 ++++++++++++------------- dynamixel/model/m54_60_s250_r.py | 104 ++++++++++---------- dynamixel/model/m54_60_s250_r_a.py | 134 ++++++++++++------------- dynamixel/model/mx_106t_r.py | 98 +++++++++---------- dynamixel/model/mx_106t_r_2.0.py | 128 ++++++++++++------------ dynamixel/model/mx_12w.py | 90 ++++++++--------- dynamixel/model/mx_28t_r_at_ar.py | 90 ++++++++--------- dynamixel/model/mx_28t_r_at_ar_2.0.py | 124 +++++++++++------------ dynamixel/model/mx_64t_r_at_ar.py | 96 +++++++++--------- dynamixel/model/mx_64t_r_at_ar_2.0.py | 128 ++++++++++++------------ dynamixel/model/ph42_020_s300_r.py | 136 +++++++++++++------------- dynamixel/model/ph54_100_s500_r.py | 136 +++++++++++++------------- dynamixel/model/ph54_200_s500_r.py | 136 +++++++++++++------------- dynamixel/model/pm42_010_s260_r.py | 136 +++++++++++++------------- dynamixel/model/pm54_040_s250_r.py | 136 +++++++++++++------------- dynamixel/model/pm54_060_s250_r.py | 136 +++++++++++++------------- dynamixel/model/rx_10.py | 84 ++++++++-------- dynamixel/model/rx_24f.py | 84 ++++++++-------- dynamixel/model/rx_28.py | 84 ++++++++-------- dynamixel/model/rx_64.py | 84 ++++++++-------- dynamixel/model/xc430_w150_t.py | 122 +++++++++++------------ dynamixel/model/xc430_w240_t.py | 122 +++++++++++------------ dynamixel/model/xh430_v210_r.py | 126 ++++++++++++------------ dynamixel/model/xh430_v350_r.py | 126 ++++++++++++------------ dynamixel/model/xh430_w210_t_r.py | 126 ++++++++++++------------ dynamixel/model/xh430_w350_t_r.py | 126 ++++++++++++------------ dynamixel/model/xh540_v150_r.py | 130 ++++++++++++------------ dynamixel/model/xh540_v270_r.py | 130 ++++++++++++------------ dynamixel/model/xh540_w150_t_r.py | 130 ++++++++++++------------ dynamixel/model/xh540_w270_t_r.py | 130 ++++++++++++------------ dynamixel/model/xl430_w250_t.py | 122 +++++++++++------------ dynamixel/model/xl_320.py | 82 ++++++++-------- dynamixel/model/xm430_w210_t_r.py | 126 ++++++++++++------------ dynamixel/model/xm430_w350_t_r.py | 126 ++++++++++++------------ dynamixel/model/xm540_w150_t_r.py | 130 ++++++++++++------------ dynamixel/model/xm540_w270_t_r.py | 130 ++++++++++++------------ dynamixel/model/xw540_t140_r.py | 124 +++++++++++------------ dynamixel/model/xw540_t260_r.py | 124 +++++++++++------------ dynamixel/protocol/Protocol2.py | 2 - dynamixel/protocol/__init__.py | 1 - dynamixel/servo/__init__.py | 71 ++++++++++++-- three_wheel_example.py | 33 +++++++ tools/html2desc.py | 32 +++--- 71 files changed, 3707 insertions(+), 3496 deletions(-) create mode 100644 dynamixel/channel/channel.py delete mode 100644 dynamixel/model/2xc430_w250.py delete mode 100644 dynamixel/model/2xl430_w250_t.py create mode 100644 dynamixel/model/dual_xc430_w250.py create mode 100644 dynamixel/model/dual_xl430_w250_t.py delete mode 100644 dynamixel/model/ex_106+.py create mode 100644 dynamixel/model/ex_106.py delete mode 100644 dynamixel/protocol/Protocol2.py delete mode 100644 dynamixel/protocol/__init__.py create mode 100755 three_wheel_example.py diff --git a/dynamixel/channel/__init__.py b/dynamixel/channel/__init__.py index e69de29..954dd7b 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 0000000..f5e082f --- /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 80b014c..0000000 --- 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 3e3ed98..0000000 --- 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 4572b88..026154e 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 9ab069d..12dd749 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 ccdf5e1..61236ce 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 0000000..7a4fa49 --- /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 0000000..5acfe77 --- /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 ed75651..45bbf0c 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 8aedc02..ab075c6 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 a8c09e2..42d03b5 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 5fa6e3d..0000000 --- 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 0000000..adcb338 --- /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 8fdb2d4..27543df 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 471fabb..6b9af01 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 4870760..3513769 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 fdf100e..8ce2b33 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 b8fd5e2..185e233 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 d42186b..3f33e20 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 e5b1888..6dada2b 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 c6a0355..18373b0 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 5ad457b..8cdcd3b 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 0d301b4..0c7c060 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 c047b61..0aeac95 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 7b73819..7038cff 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 a867531..b11180e 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 906479c..9e4b8a3 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 a8d8702..c17da62 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 6a3136f..670c061 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 4b837af..28c2c27 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 93c1c1f..42c0000 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 fccc138..cbb9d72 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 b455db0..824e30f 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 cba2d3a..7707abf 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 6ceaaa6..7553e37 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 68b8d2e..3a62ca1 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 6115df3..579f736 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 32b2269..fbb70f0 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 9e80eec..d9e8a73 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 d1fe857..8aff141 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 e2bc049..b82f5d9 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 8289ef9..db44d55 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 ef29728..19ba4c0 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 2d3372b..6080a60 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 40b2602..d2403ef 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 71fbb7d..e65e5be 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 88dbce4..e9f2257 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 4c997a3..81cfb57 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 ca90954..cbe1915 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 7a4c3ef..2faa4b5 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 db5ae3b..f50eba7 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 3bd9ae2..c731ead 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 3b28cb9..860ce9e 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 8aacad0..51acc8f 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 d54166c..ad377fc 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 68447a1..b6ab17c 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 5cb5457..8646689 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 66a0e40..ef5d8e3 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 fc3e80f..dc735ae 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 8fd374f..0106d0f 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 9c16b6c..4f96f04 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 668d68f..85adab3 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 4247363..3856875 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 b54630f..a0fa43e 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 3dfb867..b4d92c7 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 e4fbcd3..0000000 --- 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 27f95fa..0000000 --- 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 ca0b806..3f2700c 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 0000000..65de1b3 --- /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 c9afa6b..15bda5a 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 -- GitLab