robotis_def.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 ################################################################################
00005 # Copyright 2017 ROBOTIS CO., LTD.
00006 #
00007 # Licensed under the Apache License, Version 2.0 (the "License");
00008 # you may not use this file except in compliance with the License.
00009 # You may obtain a copy of the License at
00010 #
00011 #     http://www.apache.org/licenses/LICENSE-2.0
00012 #
00013 # Unless required by applicable law or agreed to in writing, software
00014 # distributed under the License is distributed on an "AS IS" BASIS,
00015 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00016 # See the License for the specific language governing permissions and
00017 # limitations under the License.
00018 ################################################################################
00019 
00020 # Author: Ryu Woon Jung (Leon)
00021 
00022 BROADCAST_ID = 0xFE  # 254
00023 MAX_ID = 0xFC  # 252
00024 
00025 # Instruction for DXL Protocol
00026 INST_PING = 1
00027 INST_READ = 2
00028 INST_WRITE = 3
00029 INST_REG_WRITE = 4
00030 INST_ACTION = 5
00031 INST_FACTORY_RESET = 6
00032 INST_SYNC_WRITE = 131  # 0x83
00033 INST_BULK_READ = 146  # 0x92
00034 # --- Only for 2.0 ---
00035 INST_REBOOT = 8
00036 INST_STATUS = 85  # 0x55
00037 INST_SYNC_READ = 130  # 0x82
00038 INST_BULK_WRITE = 147  # 0x93
00039 
00040 # Communication Result
00041 COMM_SUCCESS = 0  # tx or rx packet communication success
00042 COMM_PORT_BUSY = -1000  # Port is busy (in use)
00043 COMM_TX_FAIL = -1001  # Failed transmit instruction packet
00044 COMM_RX_FAIL = -1002  # Failed get status packet
00045 COMM_TX_ERROR = -2000  # Incorrect instruction packet
00046 COMM_RX_WAITING = -3000  # Now recieving status packet
00047 COMM_RX_TIMEOUT = -3001  # There is no status packet
00048 COMM_RX_CORRUPT = -3002  # Incorrect status packet
00049 COMM_NOT_AVAILABLE = -9000  #
00050 
00051 
00052 # Macro for Control Table Value
00053 def DXL_MAKEWORD(a, b):
00054     return (a & 0xFF) | ((b & 0xFF) << 8)
00055 
00056 
00057 def DXL_MAKEDWORD(a, b):
00058     return (a & 0xFFFF) | (b & 0xFFFF) << 16
00059 
00060 
00061 def DXL_LOWORD(l):
00062     return l & 0xFFFF
00063 
00064 
00065 def DXL_HIWORD(l):
00066     return (l >> 16) & 0xFFFF
00067 
00068 
00069 def DXL_LOBYTE(w):
00070     return w & 0xFF
00071 
00072 
00073 def DXL_HIBYTE(w):
00074     return (w >> 8) & 0xFF


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11