Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 7 additions & 1 deletion dxl2/connection.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,18 @@
import dynamixel_sdk as sdk
import glob

def get_ports():
a = glob.glob("/dev/ttyUSB*") + glob.gob("/dev/ttyusbserial*")
return a[0]

class Connection:
def __init__(self, port: str, baudrate: int = 1_000_000):
def __init__(self, port: str = None], baudrate: int = 1_000_000):
self.port = port
self.port_handler = sdk.PortHandler(port)
self.baudrate = baudrate
self.opened = False
if port == None:
self.ports = get_ports()

def open_port(self) -> bool:
ret = self.port_handler.openPort()
Expand Down
1 change: 1 addition & 0 deletions dxl2/motor.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,3 +46,4 @@ def read(self, instruction: Instruction) -> int:
}[width](self.conn.port_handler, self.id, start)
except KeyError:
raise NotImplementedError(f"Register width not supported {width}")

7 changes: 6 additions & 1 deletion dxl2/motor_chain.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,12 @@ def write_many_values(self, instruction: Instruction, vals: Dict[int, int]) -> b
self.conn.port_handler, self.packet_handler, pos, size
)
for k, v in vals.items():
if size == 2:
if size == 4:
dxl_addparam_result = groupSyncWrite.addParam(
k, util.create4ByteArray(v)
)

elif size == 2:
dxl_addparam_result = groupSyncWrite.addParam(
k, util.create2ByteArray(v)
)
Expand Down
10 changes: 10 additions & 0 deletions dxl2/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,3 +21,13 @@ def create2ByteArray(bin_value):
def create1ByteArray(bin_value):
byte_array = [DXL_LOBYTE(DXL_LOWORD(bin_value))]
return byte_array


def create4ByteArray(bin_values):
byte_array = [
DXL_LOBYTE(DXL_LOWORD(bin_value)),
DXL_HIBYTE(DXL_LOWORD(bin_value)),
DXL_LOBYTE(DXL_HIWORD(bin_value)),
DXL_HIBYTE(DXL_HIWORD(bin_value)),
]
return byte_array