diff --git a/Robotic_Arm/__init__.py b/Robotic_Arm/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/Robotic_Arm/libs/linux_arm/libapi_c.so b/Robotic_Arm/libs/linux_arm/libapi_c.so new file mode 100644 index 00000000..41c4bf4e Binary files /dev/null and b/Robotic_Arm/libs/linux_arm/libapi_c.so differ diff --git a/Robotic_Arm/libs/linux_x86/libapi_c.so b/Robotic_Arm/libs/linux_x86/libapi_c.so new file mode 100644 index 00000000..63be5d3e Binary files /dev/null and b/Robotic_Arm/libs/linux_x86/libapi_c.so differ diff --git a/Robotic_Arm/libs/win_32/api_c.dll b/Robotic_Arm/libs/win_32/api_c.dll new file mode 100644 index 00000000..0bd56cbd Binary files /dev/null and b/Robotic_Arm/libs/win_32/api_c.dll differ diff --git a/Robotic_Arm/libs/win_64/api_c.dll b/Robotic_Arm/libs/win_64/api_c.dll new file mode 100644 index 00000000..8710f5b9 Binary files /dev/null and b/Robotic_Arm/libs/win_64/api_c.dll differ diff --git a/Robotic_Arm/rm_ctypes_wrap.py b/Robotic_Arm/rm_ctypes_wrap.py new file mode 100644 index 00000000..5d251304 --- /dev/null +++ b/Robotic_Arm/rm_ctypes_wrap.py @@ -0,0 +1,5918 @@ +""" +封装C库接口与结构体 +@author Realman-Aisha +@date 2024-04-28 + +@details +此模块通过ctypes库封装了对C库接口的调用,简化了Python与C库之间的交互过程。它会自动加载对应环境的C库, +封装了设置参数类型、返回值类型等复杂步骤,并创建了与C库中定义的结构体相对应的Python类。 + +**重要提示** +- 请勿直接修改此文件,除非您了解其内部实现并清楚修改可能带来的后果。 +""" + +# __docformat__ = "restructuredtext" + +# Begin preamble for Python + +from enum import IntEnum +import re +import platform +import os.path +import glob +import ctypes.util +import ctypes +import sys +from ctypes import * # noqa: F401, F403 +# @cond HIDE_PRIVATE_CLASSES +_int_types = (ctypes.c_int16, ctypes.c_int32) +if hasattr(ctypes, "c_int64"): + # Some builds of ctypes apparently do not have ctypes.c_int64 + # defined; it's a pretty good bet that these builds do not + # have 64-bit pointers. + _int_types += (ctypes.c_int64,) +for t in _int_types: + if ctypes.sizeof(t) == ctypes.sizeof(ctypes.c_size_t): + c_ptrdiff_t = t +del t +del _int_types + + +class UserString: + def __init__(self, seq): + if isinstance(seq, bytes): + self.data = seq + elif isinstance(seq, UserString): + self.data = seq.data[:] + else: + self.data = str(seq).encode() + + def __bytes__(self): + return self.data + + def __str__(self): + return self.data.decode() + + def __repr__(self): + return repr(self.data) + + def __int__(self): + return int(self.data.decode()) + + def __long__(self): + return int(self.data.decode()) + + def __float__(self): + return float(self.data.decode()) + + def __complex__(self): + return complex(self.data.decode()) + + def __hash__(self): + return hash(self.data) + + def __le__(self, string): + if isinstance(string, UserString): + return self.data <= string.data + else: + return self.data <= string + + def __lt__(self, string): + if isinstance(string, UserString): + return self.data < string.data + else: + return self.data < string + + def __ge__(self, string): + if isinstance(string, UserString): + return self.data >= string.data + else: + return self.data >= string + + def __gt__(self, string): + if isinstance(string, UserString): + return self.data > string.data + else: + return self.data > string + + def __eq__(self, string): + if isinstance(string, UserString): + return self.data == string.data + else: + return self.data == string + + def __ne__(self, string): + if isinstance(string, UserString): + return self.data != string.data + else: + return self.data != string + + def __contains__(self, char): + return char in self.data + + def __len__(self): + return len(self.data) + + def __getitem__(self, index): + return self.__class__(self.data[index]) + + def __getslice__(self, start, end): + start = max(start, 0) + end = max(end, 0) + return self.__class__(self.data[start:end]) + + def __add__(self, other): + if isinstance(other, UserString): + return self.__class__(self.data + other.data) + elif isinstance(other, bytes): + return self.__class__(self.data + other) + else: + return self.__class__(self.data + str(other).encode()) + + def __radd__(self, other): + if isinstance(other, bytes): + return self.__class__(other + self.data) + else: + return self.__class__(str(other).encode() + self.data) + + def __mul__(self, n): + return self.__class__(self.data * n) + + __rmul__ = __mul__ + + def __mod__(self, args): + return self.__class__(self.data % args) + + # the following methods are defined in alphabetical order: + def capitalize(self): + return self.__class__(self.data.capitalize()) + + def center(self, width, *args): + return self.__class__(self.data.center(width, *args)) + + def count(self, sub, start=0, end=sys.maxsize): + return self.data.count(sub, start, end) + + def decode(self, encoding=None, errors=None): # XXX improve this? + if encoding: + if errors: + return self.__class__(self.data.decode(encoding, errors)) + else: + return self.__class__(self.data.decode(encoding)) + else: + return self.__class__(self.data.decode()) + + def encode(self, encoding=None, errors=None): # XXX improve this? + if encoding: + if errors: + return self.__class__(self.data.encode(encoding, errors)) + else: + return self.__class__(self.data.encode(encoding)) + else: + return self.__class__(self.data.encode()) + + def endswith(self, suffix, start=0, end=sys.maxsize): + return self.data.endswith(suffix, start, end) + + def expandtabs(self, tabsize=8): + return self.__class__(self.data.expandtabs(tabsize)) + + def find(self, sub, start=0, end=sys.maxsize): + return self.data.find(sub, start, end) + + def index(self, sub, start=0, end=sys.maxsize): + return self.data.index(sub, start, end) + + def isalpha(self): + return self.data.isalpha() + + def isalnum(self): + return self.data.isalnum() + + def isdecimal(self): + return self.data.isdecimal() + + def isdigit(self): + return self.data.isdigit() + + def islower(self): + return self.data.islower() + + def isnumeric(self): + return self.data.isnumeric() + + def isspace(self): + return self.data.isspace() + + def istitle(self): + return self.data.istitle() + + def isupper(self): + return self.data.isupper() + + def join(self, seq): + return self.data.join(seq) + + def ljust(self, width, *args): + return self.__class__(self.data.ljust(width, *args)) + + def lower(self): + return self.__class__(self.data.lower()) + + def lstrip(self, chars=None): + return self.__class__(self.data.lstrip(chars)) + + def partition(self, sep): + return self.data.partition(sep) + + def replace(self, old, new, maxsplit=-1): + return self.__class__(self.data.replace(old, new, maxsplit)) + + def rfind(self, sub, start=0, end=sys.maxsize): + return self.data.rfind(sub, start, end) + + def rindex(self, sub, start=0, end=sys.maxsize): + return self.data.rindex(sub, start, end) + + def rjust(self, width, *args): + return self.__class__(self.data.rjust(width, *args)) + + def rpartition(self, sep): + return self.data.rpartition(sep) + + def rstrip(self, chars=None): + return self.__class__(self.data.rstrip(chars)) + + def split(self, sep=None, maxsplit=-1): + return self.data.split(sep, maxsplit) + + def rsplit(self, sep=None, maxsplit=-1): + return self.data.rsplit(sep, maxsplit) + + def splitlines(self, keepends=0): + return self.data.splitlines(keepends) + + def startswith(self, prefix, start=0, end=sys.maxsize): + return self.data.startswith(prefix, start, end) + + def strip(self, chars=None): + return self.__class__(self.data.strip(chars)) + + def swapcase(self): + return self.__class__(self.data.swapcase()) + + def title(self): + return self.__class__(self.data.title()) + + def translate(self, *args): + return self.__class__(self.data.translate(*args)) + + def upper(self): + return self.__class__(self.data.upper()) + + def zfill(self, width): + return self.__class__(self.data.zfill(width)) + + +class MutableString(UserString): + """mutable string objects + + Python strings are immutable objects. This has the advantage, that + strings may be used as dictionary keys. If this property isn't needed + and you insist on changing string values in place instead, you may cheat + and use MutableString. + + But the purpose of this class is an educational one: to prevent + people from inventing their own mutable string class derived + from UserString and than forget thereby to remove (override) the + __hash__ method inherited from UserString. This would lead to + errors that would be very hard to track down. + + A faster and better solution is to rewrite your program using lists.""" + + def __init__(self, string=""): + self.data = string + + def __hash__(self): + raise TypeError("unhashable type (it is mutable)") + + def __setitem__(self, index, sub): + if index < 0: + index += len(self.data) + if index < 0 or index >= len(self.data): + raise IndexError + self.data = self.data[:index] + sub + self.data[index + 1:] + + def __delitem__(self, index): + if index < 0: + index += len(self.data) + if index < 0 or index >= len(self.data): + raise IndexError + self.data = self.data[:index] + self.data[index + 1:] + + def __setslice__(self, start, end, sub): + start = max(start, 0) + end = max(end, 0) + if isinstance(sub, UserString): + self.data = self.data[:start] + sub.data + self.data[end:] + elif isinstance(sub, bytes): + self.data = self.data[:start] + sub + self.data[end:] + else: + self.data = self.data[:start] + str(sub).encode() + self.data[end:] + + def __delslice__(self, start, end): + start = max(start, 0) + end = max(end, 0) + self.data = self.data[:start] + self.data[end:] + + def immutable(self): + return UserString(self.data) + + def __iadd__(self, other): + if isinstance(other, UserString): + self.data += other.data + elif isinstance(other, bytes): + self.data += other + else: + self.data += str(other).encode() + return self + + def __imul__(self, n): + self.data *= n + return self + + +class String(MutableString, ctypes.Union): + _fields_ = [("raw", ctypes.POINTER(ctypes.c_char)), + ("data", ctypes.c_char_p)] + + def __init__(self, obj=b""): + if isinstance(obj, (bytes, UserString)): + self.data = bytes(obj) + else: + self.raw = obj + + def __len__(self): + return self.data and len(self.data) or 0 + + def from_param(cls, obj): + # Convert None or 0 + if obj is None or obj == 0: + return cls(ctypes.POINTER(ctypes.c_char)()) + + # Convert from String + elif isinstance(obj, String): + return obj + + # Convert from bytes + elif isinstance(obj, bytes): + return cls(obj) + + # Convert from str + elif isinstance(obj, str): + return cls(obj.encode()) + + # Convert from c_char_p + elif isinstance(obj, ctypes.c_char_p): + return obj + + # Convert from POINTER(ctypes.c_char) + elif isinstance(obj, ctypes.POINTER(ctypes.c_char)): + return obj + + # Convert from raw pointer + elif isinstance(obj, int): + return cls(ctypes.cast(obj, ctypes.POINTER(ctypes.c_char))) + + # Convert from ctypes.c_char array + elif isinstance(obj, ctypes.c_char * len(obj)): + return obj + + # Convert from object + else: + return String.from_param(obj._as_parameter_) + + from_param = classmethod(from_param) + + +def ReturnString(obj, func=None, arguments=None): + return String.from_param(obj) + + +# As of ctypes 1.0, ctypes does not support custom error-checking +# functions on callbacks, nor does it support custom datatypes on +# callbacks, so we must ensure that all callbacks return +# primitive datatypes. +# +# Non-primitive return values wrapped with UNCHECKED won't be +# typechecked, and will be converted to ctypes.c_void_p. +def UNCHECKED(type): + if hasattr(type, "_type_") and isinstance(type._type_, str) and type._type_ != "P": + return type + else: + return ctypes.c_void_p + + +class GBKString(String): # 继承原String类 + @classmethod + def from_param(cls, obj): + if isinstance(obj, str): + return cls(obj.encode('gbk')) + return super().from_param(obj) + +# ctypes doesn't have direct support for variadic functions, so we have to write +# our own wrapper class +class _variadic_function(object): + def __init__(self, func, restype, argtypes, errcheck): + self.func = func + self.func.restype = restype + self.argtypes = argtypes + if errcheck: + self.func.errcheck = errcheck + + def _as_parameter_(self): + # So we can pass this variadic function as a function pointer + return self.func + + def __call__(self, *args): + fixed_args = [] + i = 0 + for argtype in self.argtypes: + # Typecheck what we can + fixed_args.append(argtype.from_param(args[i])) + i += 1 + return self.func(*fixed_args + list(args[i:])) + + +def ord_if_char(value): + """ + Simple helper used for casts to simple builtin types: if the argument is a + string type, it will be converted to it's ordinal value. + + This function will raise an exception if the argument is string with more + than one characters. + """ + return ord(value) if (isinstance(value, bytes) or isinstance(value, str)) else value + + +# End preamble + +_libs = {} +_libdirs = [] + +# Begin loader + +""" +Load libraries - appropriately for all our supported platforms +""" +# ---------------------------------------------------------------------------- +# Copyright (c) 2008 David James +# Copyright (c) 2006-2008 Alex Holkner +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# * Neither the name of pyglet nor the names of its +# contributors may be used to endorse or promote products +# derived from this software without specific prior written +# permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# ---------------------------------------------------------------------------- +# __all__ = ["rm_thread_mode_e", +# "rm_robot_arm_model_e", +# "rm_force_type_e", +# "rm_event_type_e", +# "rm_event_push_data_t", +# "rm_arm_current_trajectory_e", +# "rm_realtime_push_config_t", +# "rm_quat_t", +# "rm_position_t", +# "rm_frame_t", +# "rm_envelope_balls_list_t", +# "rm_pose_t", +# "rm_waypoint_t","rm_event_callback_ptr","rm_robot_handle","rm_algo_init_sys_data","rm_euler_t","rm_algo_euler2matrix"] + + +def _environ_path(name): + """Split an environment variable into a path-like list elements""" + if name in os.environ: + return os.environ[name].split(":") + return [] + + +class LibraryLoader: + """ + A base class For loading of libraries ;-) + Subclasses load libraries for specific platforms. + """ + + # library names formatted specifically for platforms + name_formats = ["%s"] + + class Lookup: + """Looking up calling conventions for a platform""" + + mode = ctypes.DEFAULT_MODE + + def __init__(self, path): + super(LibraryLoader.Lookup, self).__init__() + self.access = dict(cdecl=ctypes.cdll.LoadLibrary(path)) + + def get(self, name, calling_convention="cdecl"): + """Return the given name according to the selected calling convention""" + if calling_convention not in self.access: + raise LookupError( + "Unknown calling convention '{}' for function '{}'".format( + calling_convention, name + ) + ) + return getattr(self.access[calling_convention], name) + + def has(self, name, calling_convention="cdecl"): + """Return True if this given calling convention finds the given 'name'""" + if calling_convention not in self.access: + return False + return hasattr(self.access[calling_convention], name) + + def __getattr__(self, name): + return getattr(self.access["cdecl"], name) + + def __init__(self): + self.other_dirs = [] + + def __call__(self, libname): + """Given the name of a library, load it.""" + paths = self.getpaths(libname) + + for path in paths: + # noinspection PyBroadException + try: + return self.Lookup(path) + except Exception: # pylint: disable=broad-except + pass + + raise ImportError("Could not load %s." % libname) + + def getpaths(self, libname): + """Return a list of paths where the library might be found.""" + if os.path.isabs(libname): + yield libname + else: + # search through a prioritized series of locations for the library + + # we first search any specific directories identified by user + for dir_i in self.other_dirs: + for fmt in self.name_formats: + # dir_i should be absolute already + yield os.path.join(dir_i, fmt % libname) + + # check if this code is even stored in a physical file + try: + this_file = __file__ + except NameError: + this_file = None + + # then we search the directory where the generated python interface is stored + if this_file is not None: + for fmt in self.name_formats: + yield os.path.abspath(os.path.join(os.path.dirname(__file__), fmt % libname)) + + # now, use the ctypes tools to try to find the library + for fmt in self.name_formats: + path = ctypes.util.find_library(fmt % libname) + if path: + yield path + + # then we search all paths identified as platform-specific lib paths + for path in self.getplatformpaths(libname): + yield path + + # Finally, we'll try the users current working directory + for fmt in self.name_formats: + yield os.path.abspath(os.path.join(os.path.curdir, fmt % libname)) + + def getplatformpaths(self, _libname): # pylint: disable=no-self-use + """Return all the library paths available in this platform""" + return [] + + +# Darwin (Mac OS X) + + +class DarwinLibraryLoader(LibraryLoader): + """Library loader for MacOS""" + + name_formats = [ + "lib%s.dylib", + "lib%s.so", + "lib%s.bundle", + "%s.dylib", + "%s.so", + "%s.bundle", + "%s", + ] + + class Lookup(LibraryLoader.Lookup): + """ + Looking up library files for this platform (Darwin aka MacOS) + """ + + # Darwin requires dlopen to be called with mode RTLD_GLOBAL instead + # of the default RTLD_LOCAL. Without this, you end up with + # libraries not being loadable, resulting in "Symbol not found" + # errors + mode = ctypes.RTLD_GLOBAL + + def getplatformpaths(self, libname): + if os.path.pathsep in libname: + names = [libname] + else: + names = [fmt % libname for fmt in self.name_formats] + + for directory in self.getdirs(libname): + for name in names: + yield os.path.join(directory, name) + + @staticmethod + def getdirs(libname): + """Implements the dylib search as specified in Apple documentation: + + http://developer.apple.com/documentation/DeveloperTools/Conceptual/ + DynamicLibraries/Articles/DynamicLibraryUsageGuidelines.html + + Before commencing the standard search, the method first checks + the bundle's ``Frameworks`` directory if the application is running + within a bundle (OS X .app). + """ + + dyld_fallback_library_path = _environ_path( + "DYLD_FALLBACK_LIBRARY_PATH") + if not dyld_fallback_library_path: + dyld_fallback_library_path = [ + os.path.expanduser("~/lib"), + "/usr/local/lib", + "/usr/lib", + ] + + dirs = [] + + if "/" in libname: + dirs.extend(_environ_path("DYLD_LIBRARY_PATH")) + else: + dirs.extend(_environ_path("LD_LIBRARY_PATH")) + dirs.extend(_environ_path("DYLD_LIBRARY_PATH")) + dirs.extend(_environ_path("LD_RUN_PATH")) + + if hasattr(sys, "frozen") and getattr(sys, "frozen") == "macosx_app": + dirs.append(os.path.join( + os.environ["RESOURCEPATH"], "..", "Frameworks")) + + dirs.extend(dyld_fallback_library_path) + + return dirs + + +# Posix + + +class PosixLibraryLoader(LibraryLoader): + """Library loader for POSIX-like systems (including Linux)""" + + _ld_so_cache = None + + _include = re.compile(r"^\s*include\s+(?P.*)") + + name_formats = ["lib%s.so", "%s.so", "%s"] + + class _Directories(dict): + """Deal with directories""" + + def __init__(self): + dict.__init__(self) + self.order = 0 + + def add(self, directory): + """Add a directory to our current set of directories""" + if len(directory) > 1: + directory = directory.rstrip(os.path.sep) + # only adds and updates order if exists and not already in set + if not os.path.exists(directory): + return + order = self.setdefault(directory, self.order) + if order == self.order: + self.order += 1 + + def extend(self, directories): + """Add a list of directories to our set""" + for a_dir in directories: + self.add(a_dir) + + def ordered(self): + """Sort the list of directories""" + return (i[0] for i in sorted(self.items(), key=lambda d: d[1])) + + def _get_ld_so_conf_dirs(self, conf, dirs): + """ + Recursive function to help parse all ld.so.conf files, including proper + handling of the `include` directive. + """ + + try: + with open(conf) as fileobj: + for dirname in fileobj: + dirname = dirname.strip() + if not dirname: + continue + + match = self._include.match(dirname) + if not match: + dirs.add(dirname) + else: + for dir2 in glob.glob(match.group("pattern")): + self._get_ld_so_conf_dirs(dir2, dirs) + except IOError: + pass + + def _create_ld_so_cache(self): + # Recreate search path followed by ld.so. This is going to be + # slow to build, and incorrect (ld.so uses ld.so.cache, which may + # not be up-to-date). Used only as fallback for distros without + # /sbin/ldconfig. + # + # We assume the DT_RPATH and DT_RUNPATH binary sections are omitted. + + directories = self._Directories() + for name in ( + "LD_LIBRARY_PATH", + "SHLIB_PATH", # HP-UX + "LIBPATH", # OS/2, AIX + "LIBRARY_PATH", # BE/OS + ): + if name in os.environ: + directories.extend(os.environ[name].split(os.pathsep)) + + self._get_ld_so_conf_dirs("/etc/ld.so.conf", directories) + + bitage = platform.architecture()[0] + + unix_lib_dirs_list = [] + if bitage.startswith("64"): + # prefer 64 bit if that is our arch + unix_lib_dirs_list += ["/lib64", "/usr/lib64"] + + # must include standard libs, since those paths are also used by 64 bit + # installs + unix_lib_dirs_list += ["/lib", "/usr/lib"] + if sys.platform.startswith("linux"): + # Try and support multiarch work in Ubuntu + # https://wiki.ubuntu.com/MultiarchSpec + if bitage.startswith("32"): + # Assume Intel/AMD x86 compat + unix_lib_dirs_list += ["/lib/i386-linux-gnu", + "/usr/lib/i386-linux-gnu"] + elif bitage.startswith("64"): + # Assume Intel/AMD x86 compatible + unix_lib_dirs_list += [ + "/lib/x86_64-linux-gnu", + "/usr/lib/x86_64-linux-gnu", + ] + else: + # guess... + unix_lib_dirs_list += glob.glob("/lib/*linux-gnu") + directories.extend(unix_lib_dirs_list) + + cache = {} + lib_re = re.compile(r"lib(.*)\.s[ol]") + # ext_re = re.compile(r"\.s[ol]$") + for our_dir in directories.ordered(): + try: + for path in glob.glob("%s/*.s[ol]*" % our_dir): + file = os.path.basename(path) + + # Index by filename + cache_i = cache.setdefault(file, set()) + cache_i.add(path) + + # Index by library name + match = lib_re.match(file) + if match: + library = match.group(1) + cache_i = cache.setdefault(library, set()) + cache_i.add(path) + except OSError: + pass + + self._ld_so_cache = cache + + def getplatformpaths(self, libname): + if self._ld_so_cache is None: + self._create_ld_so_cache() + + result = self._ld_so_cache.get(libname, set()) + for i in result: + # we iterate through all found paths for library, since we may have + # actually found multiple architectures or other library types that + # may not load + yield i + + +# Windows +class WindowsLibraryLoader(LibraryLoader): + """Library loader for Microsoft Windows""" + + name_formats = ["%s.dll", "lib%s.dll", "%slib.dll", "%s"] + + class Lookup(LibraryLoader.Lookup): + """Lookup class for Windows libraries...""" + + def __init__(self, path): + super(WindowsLibraryLoader.Lookup, self).__init__(path) + self.access["stdcall"] = ctypes.windll.LoadLibrary(path) + + +# Platform switching + +# If your value of sys.platform does not appear in this dict, please contact +# the Ctypesgen maintainers. + +loaderclass = { + "darwin": DarwinLibraryLoader, + "cygwin": WindowsLibraryLoader, + "win32": WindowsLibraryLoader, + "msys": WindowsLibraryLoader, +} + +load_library = loaderclass.get(sys.platform, PosixLibraryLoader)() + + +def add_library_search_dirs(other_dirs): + """ + Add libraries to search paths. + If library paths are relative, convert them to absolute with respect to this + file's directory + """ + for path in other_dirs: + if not os.path.isabs(path): + path = os.path.abspath(path) + load_library.other_dirs.append(path) + + +del loaderclass + +# End loader + +module_path = os.path.abspath(__file__) +package_dir = os.path.dirname(module_path) +dll_path = os.path.join(package_dir, 'libs') + +# End loader +if platform.machine() == "x86_64": + dll_path = os.path.join(dll_path, 'linux_x86') + add_library_search_dirs([dll_path]) +elif sys.platform == "win32": + if sys.maxsize > 2**32: + dll_path = os.path.join(dll_path, 'win_64') + add_library_search_dirs([dll_path]) + else: + dll_path = os.path.join(dll_path, 'win_32') + add_library_search_dirs([dll_path]) + print(dll_path) +else: + dll_path = os.path.join(dll_path, 'linux_arm') + add_library_search_dirs([dll_path]) + +# Begin libraries +if sys.platform == "linux": + libname = "libapi_c.so" +elif sys.platform == "win32": + libname = "api_c.dll" +_libs[libname] = load_library(libname) + +__uint8_t = c_ubyte +__uint16_t = c_ushort +uint8_t = __uint8_t +uint16_t = __uint16_t +# @endcond + + +# 机械臂运动设置,非阻塞模式 +RM_MOVE_NBLOCK: int = 0 +# 机械臂运动设置,多线程阻塞模式 +RM_MOVE_MULTI_BLOCK: int = 1 +# 机械臂运动设置,单线程阻塞模式超时时间 +def RM_MOVE_SINGLE_BLOCK(timeout: int): + return timeout + + +class rm_thread_mode_e(IntEnum): + """线程模式枚举 + """ + # 单线程模式 + RM_SINGLE_MODE_E = 0 + # 双线程模式 + RM_DUAL_MODE_E = RM_SINGLE_MODE_E + 1 + # 多线程模式 + RM_TRIPLE_MODE_E = RM_DUAL_MODE_E + 1 + + +class rm_robot_arm_model_e(IntEnum): + """ + 机械臂型号枚举 + + 此枚举类定义了不同型号的机械臂型号。 + + Attributes: + RM_MODEL_RM_65_E (int): RM_65型号 + RM_MODEL_RM_75_E (int): RM_75型号 + RM_MODEL_RM_63_I_E (int): RML_63I型号(已弃用) + RM_MODEL_RM_63_II_E (int): RML_63II型号 + RM_MODEL_RM_63_III_E (int): RML_63III型号 + RM_MODEL_ECO_65_E (int): ECO_65型号 + RM_MODEL_ECO_62_E (int): ECO_62型号 + RM_MODEL_GEN_72_E (int): GEN_72型号 + RM_MODEL_ECO_63_E (int): ECO_63型号 + RM_MODEL_UNIVERSAL_E (int): 通用型,非标准机械臂型号 + RM_MODEL_ZM7L_E (int): ZM7L型号 + RM_MODEL_ZM7R_E (int): ZM7R型号 + RM_MODEL_RXL75_E (int): 人型机器人左臂 + RM_MODEL_RXR75_E (int): 人型机器人右臂 + """ + # RM_65型号 + RM_MODEL_RM_65_E = 0 + # RM_75型号 + RM_MODEL_RM_75_E = RM_MODEL_RM_65_E + 1 + # RML_63I型号(已弃用) + RM_MODEL_RM_63_I_E = RM_MODEL_RM_75_E + 1 + # RML_63II型号 + RM_MODEL_RM_63_II_E = RM_MODEL_RM_63_I_E + 1 + # RML_63III型号(已弃用) + RM_MODEL_RM_63_III_E = RM_MODEL_RM_63_II_E + 1 + # ECO_65型号 + RM_MODEL_ECO_65_E = RM_MODEL_RM_63_III_E + 1 + # ECO_62型号 + RM_MODEL_ECO_62_E = RM_MODEL_ECO_65_E + 1 + # GEN_72型号 + RM_MODEL_GEN_72_E = RM_MODEL_ECO_62_E + 1 + # ECO_63 + RM_MODEL_ECO_63_E = RM_MODEL_GEN_72_E + 1 + # 通用型,非标准机械臂型号 + RM_MODEL_UNIVERSAL_E = RM_MODEL_ECO_63_E + 1 + # ZM7L + RM_MODEL_ZM7L_E = RM_MODEL_UNIVERSAL_E + 1 + # ZM7R + RM_MODEL_ZM7R_E = RM_MODEL_ZM7L_E + 1 + # 人型机器人左臂 + RM_MODEL_RXL75_E = RM_MODEL_ZM7R_E + 1 + # 人型机器人右臂 + RM_MODEL_RXR75_E = RM_MODEL_RXL75_E + 1 + + +class rm_force_type_e(IntEnum): + """机械臂末端版本枚举 + """ + # 标准版本 + RM_MODEL_RM_B_E = 0 + # 一维力版本 + RM_MODEL_RM_ZF_E = (RM_MODEL_RM_B_E + 1) + # 六维力版本 + RM_MODEL_RM_SF_E = (RM_MODEL_RM_ZF_E + 1) + # 一体化六维力版 + RM_MODEL_RM_ISF_E = (RM_MODEL_RM_SF_E + 1) + +class rm_event_type_e(IntEnum): + """机械臂事件类型枚举 + """ + # 无事件 + RM_NONE_EVENT_E = 0 + # 当前轨迹到位 + RM_CURRENT_TRAJECTORY_STATE_E = RM_NONE_EVENT_E + 1 + # 在线编程运行结束 + RM_PROGRAM_RUN_FINISH_E = RM_CURRENT_TRAJECTORY_STATE_E + 1 + + +class rm_force_position_sensor_e(IntEnum): + """力位混合控制传感器类型枚举 + """ + # 一维力 + RM_FP_OF_SENSOR_E = 0 + # 六维力 + RM_FP_SF_SENSOR_E = RM_FP_OF_SENSOR_E + 1 + + +class rm_force_position_mode_e(IntEnum): + """力位混合控制模式枚举 + """ + # 基坐标系力控 + RM_FP_BASE_COORDINATE_E = 0 + # 工具坐标系力控 + RM_FP_TOOL_COORDINATE_E = RM_FP_BASE_COORDINATE_E + 1 + + +class rm_force_position_dir_e(IntEnum): + """力位混合控制模式(单方向)力控方向枚举 + """ + # 沿X轴 + RM_FP_X_E = 0 + # 沿Y轴 + RM_FP_Y_E = RM_FP_X_E + 1 + # 沿Z轴 + RM_FP_Z_E = RM_FP_Y_E + 1 + # 沿RX姿态方向 + RM_FP_RX_E = RM_FP_Z_E + 1 + # 沿RY姿态方向 + RM_FP_RY_E = RM_FP_RX_E + 1 + # 沿RZ姿态方向 + RM_FP_RZ_E = RM_FP_RY_E + 1 + + +class rm_event_push_data_t(Structure): + """表示机械臂到位等事件信息的结构体 + @details 此结构体用于接收关于机械臂的各类事件信息,如规划轨迹到位、在线编程到位等。 + 通过rm_get_arm_event_call_back接口注册回调函数处理本结构体数据。 + **Attributes**: + - handle_id (int) 机械臂连接id,用于标识特定的机械臂连接。 + - event_type (rm_event_type_e) 事件类型枚举,表示具体的事件类型。 + - 0:无事件 + - 1:当前规划轨迹到位 + - 2:当前在线编程到位 + - trajectory_state (bool) 表示已到位规划轨迹的状态,true-成功,false-失败 + - device (int) 表示当前已到位规划的设备标识符,用于进一步区分不同类型的设备。 + - 0:关节 + - 1:夹爪 + - 2:灵巧手 + - 3:升降机构 + - 4:扩展关节 + - 其他:保留 + - trajectory_connect (int) 表示当前已到位规划的轨迹是否连接下一条: + - 0:代表全部到位 + - 1:代表连接下一条轨迹 + - program_id (int) 当前到位的在线编程。 + """ + _fields_ = [ + ('handle_id', c_int), + ('event_type', c_int), + ('trajectory_state', c_bool), + ('device', c_int), + ('trajectory_connect', c_int), + ('program_id', c_int), + ] + + +class rm_arm_current_trajectory_e(IntEnum): + """机械臂当前规划类型枚举 + """ + # 无规划 + RM_NO_PLANNING_E = 0 + # 关节空间规划 + RM_JOINT_SPACE_PLANNING_E = 1 + # 笛卡尔空间直线规划 + RM_CARTESIAN_LINEAR_PLANNING_E = 2 + # 笛卡尔空间圆弧规划 + RM_CARTESIAN_ARC_PLANNING_E = 3 + # 示教轨迹复现规划 + RM_TRAJECTORY_REPLAY_PLANNING_E = 4 + +class rm_udp_custom_config_t(Structure): + """ + 自定义UDP上报项 + + **Attributes**: + - joint_speed (int): 关节速度。 + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + - lift_state (int): 升降关节信息。 + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + - expand_state (int): 扩展关节信息(升降关节和扩展关节为二选一,优先显示升降关节) + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + - hand_state (int): 灵巧手状态。 + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + - arm_current_status (int): 机械臂当前状态。 + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + - aloha_state (int): aloha主臂状态。 + 1:上报; 0:关闭上报; -1:不设置,保持之前的状态 + """ + _fields_ = [ + ('joint_speed', c_int), + ('lift_state', c_int), + ('expand_state', c_int), + ('hand_state', c_int), + ('arm_current_status', c_int), + ('aloha_state', c_int), + ('plus_base', c_int), + ('plus_state', c_int), + ] + + def __init__(self, joint_speed:int = -1,lift_state:int = -1,expand_state:int = -1,arm_current_status:int = -1,hand_state:int = -1,aloha_state:int = -1,plus_base = -1,plus_state = -1) -> None: + self.joint_speed = joint_speed + self.lift_state = lift_state + self.expand_state = expand_state + self.hand_state = hand_state + self.arm_current_status = arm_current_status + self.aloha_state = aloha_state + self.plus_base = plus_base + self.plus_state = plus_state + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + +class rm_realtime_push_config_t(Structure): + """ + UDP机械臂状态主动上报接口配置 + + **Attributes**: + - cycle (int): 广播周期,5ms的倍数 + - enable (bool): 使能,是否主动上报 + - port (int): 广播的端口号 + - force_coordinate (int): 系统外受力数据的坐标系(力传感器版本支持) + - -1:不支持力传感器 + - 0:传感器坐标系 + - 1:当前工作坐标系 + - 2:当前工具坐标系 + - ip (bytes): 自定义的上报目标IP地址 + - custom_config (rm_udp_custom_config_t): 自定义上报项 + """ + _fields_ = [ + ('cycle', c_int), + ('enable', c_bool), + ('port', c_int), + ('force_coordinate', c_int), + ('ip', c_char * int(28)), + ('custom_config', rm_udp_custom_config_t), + ] + + def __init__(self, cycle: int = 100, enable: bool = True, port: int = 8080, force_coordinate: int = -1, ip: str = "192.168.1.18", custom_config:rm_udp_custom_config_t = None) -> None: + """ + UDP机械臂状态主动上报接口配置构造函数 + + Args: + cycle (int, optional): 广播周期,5ms的倍数. Defaults to None. + enable (bool, optional): 使能,是否主动上报. Defaults to None. + port (int, optional): 广播的端口号. Defaults to None. + force_coordinate (int, optional): 系统外受力数据的坐标系(力传感器版本支持). Defaults to None. + - -1:不支持力传感器 + - 0:传感器坐标系 + - 1:当前工作坐标系 + - 2:当前工具坐标系 + ip (str, optional): 自定义的上报目标IP地址. Defaults to None. + """ + if all(param is None for param in [cycle, enable, port, force_coordinate, ip, custom_config]): + return + else: + self.cycle = cycle + self.enable = enable + self.port = port + self.force_coordinate = force_coordinate + self.ip = ip.encode('utf-8') + if custom_config==None: + custom_config=rm_udp_custom_config_t() + self.custom_config = custom_config + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_io_real_time_config_t(Structure): + _fields_ = [ + ('speed', c_int), + ('mode', c_int) + ] + + def __init__(self, speed:int = -1, mode:int = -1) -> None: + self.speed = speed + self.mode = mode + + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_io_config_t(Structure): + """ + 数字IO配置结构体 + + io_mode:模式,0-通用输入模式 + 1-通用输出模式 + 2-输入开始功能复用模式 + 3-输入暂停功能复用模式 + 4-输入继续功能复用模式 + 5-输入急停功能复用模式 + 6-输入进入电流环拖动复用模式 + 7-输入进入力只动位置拖动模式(六维力版本可配置) + 8-输入进入力只动姿态拖动模式(六维力版本可配置) + 9-输入进入力位姿结合拖动复用模式(六维力版本可配置) + 10-输入外部轴最大软限位复用模式(外部轴模式可配置) + 11-输入外部轴最小软限位复用模式(外部轴模式可配置) + 12-输入初始位姿功能复用模式 + 13-输出碰撞功能复用模式 + 14-实时调速功能复用模式 + io_real_time_config_t:实时调速功能,io配置 + speed:速度取值范围0-100 (当io_mode不为14时,默认值为-1) + mode :模式取值范围1或2 (当io_mode不为14时,默认值为-1) + 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值 + 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + """ + + _fields_ = [ + ('io_mode', c_int), + ('io_real_time_config_t', rm_io_real_time_config_t) + ] + + def __init__(self, io_mode: int = None, io_real_time_config_t: rm_io_real_time_config_t = None) -> None: + if all(param is None for param in [io_mode, io_real_time_config_t]): + return + else: + self.io_mode = io_mode + if io_real_time_config_t == None: + self.io_real_time_config_t = rm_io_real_time_config_t() + else: + self.io_real_time_config_t = io_real_time_config_t + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_io_get_t(Structure): + """ + 数字IO状态获取结构体 + **Attributes** + - io_state:数字io状态(0低 1高) + - io_config:io配置结构体 + """ + _fields_ = [ + ('io_state', c_int), + ('io_config', rm_io_config_t), + ] + def __init__(self, io_state: int = None, io_config: rm_io_config_t = None) -> None: + if all(param is None for param in [io_state, io_config]): + return + else: + self.io_state = io_state + if io_config == None: + self.rm_io_config_t = rm_io_config_t() + else: + self.io_config = io_config + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_quat_t(Structure): + """ + 表示四元数的结构体 + + **Attributes**: + - w (float): 四元数的实部(scalar part),通常用于表示旋转的角度和方向。 + - x (float): 四元数的虚部中的第一个分量(vector part)。 + - y (float): 四元数的虚部中的第二个分量。 + - z (float): 四元数的虚部中的第三个分量。 + """ + _fields_ = [ + ('w', c_float), + ('x', c_float), + ('y', c_float), + ('z', c_float), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_position_t(Structure): + """ + 位置结构体 + + **Attributes**: + - x (float): X轴坐标值,单位:m。 + - y (float): Y轴坐标值,单位:m。 + - z (float): Z轴坐标值,单位:m。 + + 这个结构体通常用于表示机器人、物体或其他任何可以在三维空间中定位的点的位置。 + """ + _fields_ = [ + ('x', c_float), + ('y', c_float), + ('z', c_float), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_euler_t(Structure): + """ + 表示欧拉角(Euler angles)的结构体 + + **Attributes**: + - rx (float): 绕X轴旋转的角度,单位:rad。 + - ry (float): 绕Y轴旋转的角度,单位:rad。 + - rz (float): 绕Z轴旋转的角度,单位:rad。 + """ + _fields_ = [ + ('rx', c_float), + ('ry', c_float), + ('rz', c_float), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_pose_t(Structure): + """ + 表示机械臂位置姿态的结构体 + + **Attributes**: + - position (rm_position_t): 位置,单位:m + - quaternion (rm_quat_t): 四元数 + - euler (rm_euler_t): 欧拉角,单位:rad + """ + _fields_ = [ + ('position', rm_position_t), + ('quaternion', rm_quat_t), + ('euler', rm_euler_t), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_frame_name_t(Structure): + """ + 坐标系名称结构体 + + **Attributes**: + - name (str): 不超过10个字符 + """ + _fields_ = [ + ('name', c_char * int(12)), + ] + + +class rm_frame_t(Structure): + """ + 表示一个坐标系的结构体 + + **Attributes**: + - frame_name (bytes): 坐标系名称,不超过10个字符(包括结尾的null字节)。 + - pose (rm_pose_t): 坐标系位姿,包含位置和姿态信息。 + - payload (float): 坐标系末端负载重量,单位:kg。 + - x (float), y (float), z (float): 坐标系末端负载质心位置坐标。 + """ + _fields_ = [ + ('frame_name', c_char * 12), # 11个字符 + 1个null字节 + ('pose', rm_pose_t), + ('payload', c_float), + ('x', c_float), + ('y', c_float), + ('z', c_float), + ] + + def __init__(self, frame_name: str = None, pose: tuple[float, float, float, float, float, float] = None, payload: float = None, x: float = None, y: float = None, z: float = None): + """ + + Args: + frame_name (str, optional): 坐标系名称,不超过10个字符。默认为 None。 + pose (tuple[float, float, float, float, float, float], optional): 表示坐标系位姿的元组,包含三个位置坐标(x, y, z)和三个欧拉角(rx, ry, rz)。 + payload (float, optional): 坐标系末端负载重量,单位:kg。默认为 None。 + x (float, optional): 坐标系末端负载质心位置的 x 坐标,单位:mm。默认为 None。 + y (float, optional): 坐标系末端负载质心位置的 y 坐标,单位:mm。默认为 None。 + z (float, optional): 坐标系末端负载质心位置的 z 坐标,单位:mm。默认为 None。 + + Raises: + ValueError: 如果frame_name的长度超过10个字符 + ValueError: 如果 pose 不是包含6个浮点数的元组,表示(x, y, z, rx, ry, rz) + """ + if frame_name is not None: + if len(frame_name) > 10: + raise ValueError("frame_name must not exceed 10 characters.") + self.frame_name = frame_name.encode( + 'utf-8')[:11] + b'\0' # 截断并添加null字节 + + if pose is not None: + if len(pose) != 6: + raise ValueError( + "pose must be a tuple of 6 floats representing (x, y, z, roll, pitch, yaw).") + pose_value = rm_pose_t() + pose_value.position = rm_position_t(pose[0], pose[1], pose[2]) + pose_value.euler = rm_euler_t(pose[3], pose[4], pose[5]) + self.pose = pose_value + + if payload is not None: + self.payload = payload + self.x = x + self.y = y + self.z = z + + def to_dictionary(self) -> dict[str, any]: + """将rm_frame_t对象转换为字典表现形式 + + Returns: + 包含坐标系信息的字典,包括以下键 + - 'name' (str): 坐标系名称 + - 'pose' (List[float]): 包含位置和欧拉角的列表,按顺序为 [x, y, z, rx, ry, rz] + - 'payload' (float): 坐标系末端负载重量,单位:kg + - 'x' (float): 坐标系末端负载位置,单位:m + - 'y' (float): 坐标系末端负载位置,单位:m + - 'z' (float): 坐标系末端负载位置,单位:m + """ + name = self.frame_name.decode("utf-8") + position = self.pose.position + euler = self.pose.euler + + output_dict = { + "name": name, + "pose": [round(item, 6) for item in [position.x, position.y, position.z, euler.rx, euler.ry, euler.rz]], + "payload": float(format(self.payload, ".3f")), + "x": float(format(self.x, ".3f")), + "y": float(format(self.y, ".3f")), + "z": float(format(self.z, ".3f")) + } + return output_dict + + +class rm_ctrl_version_t(Structure): + """ + 表示控制器ctrl 层软件信息的结构体 + + **Args:** + - 无(此结构体通常为调用接口获取数据填充)。 + + **Attributes:** + - build_time (bytes): 编译时间。 + - version (bytes): 版本号。 + """ + _fields_ = [ + ('build_time', c_char * int(20)), + ('version', c_char * int(10)), + ] + + def to_dict(self, recurse=True): + result = { + "build_time": self.build_time.decode("utf-8"), + "version": self.version.decode("utf-8") + } + + return result + + +class rm_dynamic_version_t(Structure): + """ + 表示动力学版本信息的结构体 + + **Args:** + - 无(此结构体通常为调用接口获取数据填充)。 + + **Attributes:** + - model_version (bytes): 动力学模型版本号。 + """ + _fields_ = [ + ('model_version', c_char * int(5)), + ] + + def to_dict(self): + result = { + "model_version": self.model_version.decode("utf-8") + } + + return result + + +class rm_planinfo_t(Structure): + """ + 表示控制器plan 层软件信息的结构体 + + **Args:** + - 无(此结构体通常为调用接口获取数据填充)。 + + **Attributes:** + - build_time (bytes): 编译时间。 + - version (bytes): 版本号。 + """ + _fields_ = [ + ('build_time', c_char * int(20)), + ('version', c_char * int(20)), + ] + + def to_dict(self): + result = { + "build_time": self.build_time.decode("utf-8"), + "version": self.version.decode("utf-8") + } + + return result + + +class rm_algorithm_version_t(Structure): + """ + 表示算法库信息的结构体 + + **Args:** + - 无(此结构体通常为调用接口获取数据填充)。 + + **Attributes:** + - version (bytes): 版本号。 + """ + _fields_ = [ + ('version', c_char * int(20)), + ] + + def to_dict(self): + result = { + "version": self.version.decode("utf-8") + } + + return result + + +class rm_software_build_info_t(Structure): + """ + 表示软件版本信息的结构体 + + **Args:** + - 无(此结构体通常为调用接口获取数据填充)。 + + **Attributes:** + - build_time (bytes): 编译时间。 + - version (bytes): 版本号。 + """ + _fields_ = [ + ('build_time', c_char * int(20)), + ('version', c_char * int(20)), + ] + + def to_dict(self): + out_dict = { + "build_time": self.build_time.decode("utf-8"), + "version": self.version.decode("utf-8") + } + return out_dict + +class rm_arm_software_version_t(Structure): + """ + 表示机械臂软件版本信息的结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + + Attributes: + product_version (bytes): 机械臂型号 + robot_controller_version (bytes): 机械臂控制器版本,若为四代控制器,则该字段为"4.0" + algorithm_info (rm_algorithm_version_t): 算法库信息 + ctrl_info (rm_software_build_info_t): ctrl 层软件信息 + dynamic_info (rm_dynamic_version_t): 动力学版本(三代) + plan_info (rm_software_build_info_t): plan 层软件信息(三代) + com_info (rm_software_build_info_t): communication 模块软件信息(四代) + program_info (rm_software_build_info_t): 流程图编程模块软件信息(四代) + """ + _fields_ = [ + ('product_version', c_char * int(20)), + ('robot_controller_version', c_char * int(10)), + ('algorithm_info', rm_algorithm_version_t), + ('ctrl_info', rm_software_build_info_t), + ('dynamic_info', rm_dynamic_version_t), + ('plan_info', rm_planinfo_t), + ('com_info', rm_software_build_info_t), + ('program_info', rm_software_build_info_t), + ] + + def to_dict(self, robot_controller_version = 4): + out_dict = { + "product_version": self.product_version.decode("utf-8"), + "algorithm_info": self.algorithm_info.to_dict(), + "ctrl_info": self.ctrl_info.to_dict(), + } + if(robot_controller_version == 3): + out_dict["dynamic_info"] = self.dynamic_info.to_dict() + out_dict["plan_info"] = self.plan_info.to_dict() + elif(robot_controller_version == 4): + out_dict["com_info"] = self.com_info.to_dict() + out_dict["program_info"] = self.program_info.to_dict() + out_dict["robot_controller_version"] = self.robot_controller_version.decode("utf-8") + return out_dict + + +class rm_err_t(Structure): + """ + 错误码结构体 + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes:** + err_len (uint8_t): 机械臂错误代码个数 + err (list[int]): 错误代码 + """ + _fields_ = [ + ('err_len', uint8_t), + ('err', c_int * int(24)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = { + "err_len":self.err_len, + "err":[] + } + err = list(self.err) + for i in range(self.err_len): + result["err"].append(f"{err[i]}") + return result + + +class rm_current_arm_state_t(Structure): + """ + 表示机械臂当前状态的结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes:** + pose (rm_pose_t): 机械臂的当前位姿信息。 + joint (list[float]): 机械臂当前关节角度,单位:°。 + err (rm_err_t): 机械臂错误代码。 + + 注意: + - 这些字段通常由外部系统或硬件提供,并通过适当的接口填充。 + - 在处理错误代码时,请参考相关的错误代码文档或枚举。 + """ + _fields_ = [ + ('pose', rm_pose_t), + ('joint', c_float * int(7)), + ('err', rm_err_t), + ] + + def to_dictionary(self, arm_dof): + position = self.pose.position + euler = self.pose.euler + + output_dict = { + "joint": list(self.joint[:arm_dof]), + "pose": [round(item, 6) for item in [position.x, position.y, position.z, euler.rx, euler.ry, euler.rz]], + 'err': self.err.to_dict(), + } + return output_dict + + +class rm_joint_status_t(Structure): + """ + 表示机械臂关节状态的结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + + **Attributes**: + joint_current (list[float]): 关节电流,单位mA,精度:0.001mA + joint_en_flag (list[bool]): 当前关节使能状态 ,1为上使能,0为掉使能 + joint_err_code (list[int]): 当前关节错误码 + joint_position (list[float]): 关节角度,单位°,精度:0.001° + joint_temperature (list[float]): 当前关节温度,精度0.001℃ + joint_voltage (list[float]): 当前关节电压,精度0.001V + joint_speed (list[float]): 当前关节速度,精度0.01°/s。 + """ + _fields_ = [ + ('joint_current', c_float * int(7)), + ('joint_en_flag', c_bool * int(7)), + ('joint_err_code', uint16_t * int(7)), + ('joint_position', c_float * int(7)), + ('joint_temperature', c_float * int(7)), + ('joint_voltage', c_float * int(7)), + ('joint_speed', c_float * int(7)), + ] + + def to_dict(self, recurse=True): + result = { + 'joint_current': list(self.joint_current), + 'joint_en_flag': list(self.joint_en_flag), + 'joint_err_code': list(self.joint_err_code), + 'joint_position': list(self.joint_position), + 'joint_temperature': list(self.joint_temperature), + 'joint_voltage': list(self.joint_voltage), + 'joint_speed': list(self.joint_speed), + } + return result + + +class rm_pos_teach_type_e(IntEnum): + """位置示教方向枚举 + """ + # 位置示教,x轴方向 + RM_X_DIR_E = 0 + # 位置示教,y轴方向 + RM_Y_DIR_E = RM_X_DIR_E + 1 + # 位置示教,z轴方向 + RM_Z_DIR_E = RM_Y_DIR_E + 1 + + +class rm_ort_teach_type_e(IntEnum): + """姿态示教方向枚举 + """ + # 姿态示教,绕x轴旋转 + RM_RX_ROTATE_E = 0 + # 姿态示教,绕y轴旋转 + RM_RY_ROTATE_E = (RM_RX_ROTATE_E + 1) + # 姿态示教,绕z轴旋转 + RM_RZ_ROTATE_E = (RM_RY_ROTATE_E + 1) + + +class rm_wifi_net_t(Structure): + """ + 无线网络信息结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - channel (int): 如果是 AP 模式,则存在此字段,标识 wifi 热点的物理信道号 + - ip (str): IP 地址 + - mac (str): MAC 地址 + - mask (str): 子网掩码 + - mode (str): 'ap' 代表热点模式,'sta' 代表联网模式,'off' 代表未开启无线模式 + - password (str): 密码 + - ssid (str): 网络名称 (SSID) + """ + _fields_ = [ + ('channel', c_int), + ('ip', c_char * int(16)), + ('mac', c_char * int(18)), + ('mask', c_char * int(16)), + ('mode', c_char * int(5)), + ('password', c_char * int(16)), + ('ssid', c_char * int(32)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + if self.mode.decode('utf-8') == "off": + del result['password'] + del result['ssid'] + del result['channel'] + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_arm_all_state_t(Structure): + """ + 机械臂所有状态参数 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - joint_current (list[float]): 关节电流,单位mA + - joint_en_flag (list[int]): 关节使能状态 + - joint_temperature (list[float]): 关节温度,单位℃ + - joint_voltage (list[float]): 关节电压,单位V + - joint_err_code (list[int]): 关节错误码 + - err (rm_err_t): 错误代码 + """ + _fields_ = [ + ('joint_current', c_float * int(7)), + ('joint_en_flag', c_int * int(7)), + ('joint_temperature', c_float * int(7)), + ('joint_voltage', c_float * int(7)), + ('joint_err_code', c_int * int(7)), + ('err', rm_err_t), + ] + + def to_dictionary(self): + output_dict = { + 'joint_current': list(self.joint_current), + 'joint_en_flag': list(self.joint_en_flag), + 'joint_temperature': list(self.joint_temperature), + 'joint_voltage': list(self.joint_voltage), + 'joint_err_code': list(self.joint_err_code), + 'err': self.err.to_dict(), + } + return output_dict + + +class rm_gripper_state_t(Structure): + """夹爪状态结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - enable_state (int): 夹爪使能标志,0 表示未使能,1 表示使能 + - status (int): 夹爪在线状态,0 表示离线, 1表示在线 + - error (int): 夹爪错误信息,低8位表示夹爪内部的错误信息bit5-7 保留bit4 内部通bit3 驱动器bit2 过流 bit1 过温bit0 堵转 + - mode (int): 当前工作状态:1 夹爪张开到最大且空闲,2 夹爪闭合到最小且空闲,3 夹爪停止且空闲,4 夹爪正在闭合,5 夹爪正在张开,6 夹爪闭合过程中遇到力控停止 + - current_force (int): 夹爪当前的压力,单位g + - temperature (int): 当前温度,单位℃ + - actpos (int): 夹爪开口度 + + """ + _fields_ = [ + ('enable_state', c_int), + ('status', c_int), + ('error', c_int), + ('mode', c_int), + ('current_force', c_int), + ('temperature', c_int), + ('actpos', c_int), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_force_data_t(Structure): + """ + 六维力传感器数据结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - force_data (list[float]): 当前力传感器原始数据,力的单位为N;力矩单位为Nm。 + - zero_force_data (list[float]): 当前力传感器系统外受力数据,力的单位为N;力矩单位为Nm。 + - work_zero_force_data (list[float]): 当前工作坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + - tool_zero_force_data (list[float]): 当前工具坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + """ + _fields_ = [ + ('force_data', c_float * int(6)), + ('zero_force_data', c_float * int(6)), + ('work_zero_force_data', c_float * int(6)), + ('tool_zero_force_data', c_float * int(6)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_fz_data_t(Structure): + """ + 一维力传感器数据结构体 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - Fz (float): 当前力传感器原始数据,力的单位为N;力矩单位为Nm。 + - zero_Fz (float): 传感器坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + - work_zero_Fz (float): 当前工作坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + - tool_zero_Fz (float): 当前工具坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + + """ + _fields_ = [ + ('Fz', c_float), + ('zero_Fz', c_float), + ('work_zero_Fz', c_float), + ('tool_zero_Fz', c_float), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_peripheral_read_write_params_t(Structure): + """ + 读写外设数据参数结构体 + + **Args**: + - port (int, optional): 通讯端口,0-控制器RS485端口,1-末端接口板RS485接口,3-控制器ModbusTCP设备,默认为 None + - address (int, optional): 数据起始地址,默认为 None + - device (int, optional): 外设设备地址,默认为 None + - num (int, optional): 数据数量,默认为 None + + **Attributes**: + - port (int): 通讯端口,0-控制器RS485端口,1-末端接口板RS485接口,3-控制器ModbusTCP设备 + - address (int): 数据起始地址 + - device (int): 外设设备地址 + - num (int): 数据数量 + """ + _fields_ = [ + ('port', c_int), + ('address', c_int), + ('device', c_int), + ('num', c_int), + ] + + def __init__(self, port=None, address=None, device=None, num=None): + if all(param is None for param in [port, address, device, num]): + return + else: + self.port = port + self.address = address + self.device = device + if num is not None: + self.num = num + + +class rm_expand_state_t(Structure): + """ + 表示扩展关节状态的结构体。 + + **Args**: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - pos (int): 扩展关节角度,单位度,精度 0.001°(若为升降机构高度,则s单位:mm,精度:1mm,范围:0 ~2300) + - current (int): 驱动电流,单位:mA,精度:1mA + - err_flag (int): 驱动错误代码,错误代码类型参考关节错误代码 + - mode (int): 当前工作状态 + - 0:空闲 + - 1:正方向速度运动 + - 2:正方向位置运动 + - 3:负方向速度运动 + - 4:负方向位置运动 + """ + _fields_ = [ + ('pos', c_int), + ('current', c_int), + ('err_flag', c_int), + ('mode', c_int), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + +# rm_expand_state_t = struct_anon_30 + + +class rm_send_project_t(Structure): + """ + 用于发送编程文件信息的结构体。 + + **Attributes:** + - project_path (c_char * 300): 下发文件路径文件路径及名称 + - project_path_len (c_int): 路径及名称长度 + - plan_speed (c_int): 规划速度比例系数 + - only_save (c_int): 0-保存并运行文件,1-仅保存文件,不运行 + - save_id (c_int): 保存到控制器中的编号 + - step_flag (c_int): 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式 + - auto_start (c_int): 设置默认在线编程文件,1-设置默认 0-设置非默认 + - project_type (c_int): 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件 + """ + _fields_ = [ + ('project_path', c_char * int(300)), + ('project_path_len', c_int), + ('plan_speed', c_int), + ('only_save', c_int), + ('save_id', c_int), + ('step_flag', c_int), + ('auto_start', c_int), + ('project_type', c_int), + ] + + def __init__(self, project_path: str = None, plan_speed: int = None, only_save: int = None, save_id: int = None, step_flag: int = None, auto_start: int = None, project_type: int = None): + """ + 文件下发结构体 + + @param project_path (str, optional): 下发文件路径文件路径及名称,默认为None + @param plan_speed (int, optional): 规划速度比例系数,默认为None + @param only_save (int, optional): 0-保存并运行文件,1-仅保存文件,不运行,默认为None + @param save_id (int, optional): 保存到控制器中的编号,默认为None + @param step_flag (int, optional): 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式,默认为None + @param auto_start (int, optional): 设置默认在线编程文件,1-设置默认 0-设置非默认,默认为None + @param project_type (int, optional): 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件 + """ + if all(param is None for param in [project_path, plan_speed, only_save, save_id, step_flag, auto_start,project_type]): + return + else: + if project_path is not None: + # 确保字符串不超过最大长度,并添加null终止符 + self.project_path = project_path.encode('utf-8') + + # 路径及名称长度 + self.project_path_len = len(self.project_path) + 1 # 包括null终止符 + + # 规划速度比例系数 + self.plan_speed = plan_speed if plan_speed is not None else 20 + # 0-保存并运行文件,1-仅保存文件,不运行 + self.only_save = only_save if only_save is not None else 0 + # 保存到控制器中的编号 + self.save_id = save_id if save_id is not None else 0 + # 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式 + self.step_flag = step_flag if step_flag is not None else 0 + # 设置默认在线编程文件,1-设置默认 0-设置非默认 + self.auto_start = auto_start if auto_start is not None else 0 + self.project_type = project_type if project_type is not None else 0 + + +class rm_trajectory_connect_config_e(IntEnum): + """轨迹连接配置枚举 + """ + # 立即规划并执行轨迹,不连接后续轨迹 + RM_TRAJECTORY_DISCONNECT_E = 0 + # 将当前轨迹与下一条轨迹一起规划 + RM_TRAJECTORY_CONNECT_E = RM_TRAJECTORY_DISCONNECT_E + 1 + + +class rm_trajectory_data_t(Structure): + """ + 在线编程存储信息 + + **Args**: + - 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - id (int): 在线编程文件id + - size(int): 文件大小 + - speed(int): 默认运行速度 + - trajectory_name (str): 文件名称 + """ + _fields_ = [ + ('id', c_int), + ('size', c_int), + ('speed', c_int), + ('trajectory_name', c_char * int(32)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_program_trajectorys_t(Structure): + """ + 查询在线编程列表 + + **Args**: + - 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息)。 + + **Attributes**: + - page_num (int): 页码 + - page_size (int): 每页大小 + - list_size (int): 返回总数量 + - vague_search (bytes): 模糊搜索字符串 + - trajectory_list (list): 符合的在线编程列表(包含 rm_trajectory_data_t 结构体的数组) + """ + _fields_ = [ + ('page_num', c_int), + ('page_size', c_int), + ('list_size', c_int), + ('vague_search', c_char * int(32)), + ('trajectory_list', rm_trajectory_data_t * int(100)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + non_empty_outputs = [] + for i in range(self.list_size): + if self.trajectory_list[i].trajectory_name != b'': # 判断列表是否为空 + output = self.trajectory_list[i].to_dict() + non_empty_outputs.append(output) + result["trajectory_list"] = non_empty_outputs + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_program_run_state_t(Structure): + """ + 机械臂程序运行状态结构体 + + **Args:** + - 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息) + + **Attributes:** + - run_state (int): 运行状态 0 未开始 1运行中 2暂停中 + - id (int): 运行轨迹编号 + - edit_id (int): 上次编辑的在线编程编号 id + - plan_num (int): 运行行数 + - total_loop (int): 循环指令数量 + - step_mode (int): 单步模式,1 为单步模式,0 为非单步模式 + - plan_speed (int): 全局规划速度比例 1-100 + - loop_num (int array[100]): 循环行数 + - loop_cont (int array[100]): 对应循环次数 + + """ + _fields_ = [ + ('run_state', c_int), + ('id', c_int), + ('edit_id', c_int), + ('plan_num', c_int), + ('total_loop', c_int), + ('step_mode', c_int), + ('plan_speed', c_int), + ('loop_num', c_int * int(100)), + ('loop_cont', c_int * int(100)), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + loop_num = [] + loop_cont = [] + for i in range(self.total_loop): + output = self.loop_num[i] + loop_num.append(output) + output1 = self.loop_cont[i] + loop_cont.append(output1) + result["loop_num"] = loop_num + result["loop_cont"] = loop_cont + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + if 0 == self.run_state: + del result['plan_num'] + del result['loop_num'] + del result['loop_cont'] + del result['total_loop'] + del result['step_mode'] + del result['plan_speed'] + + return result + + + +class rm_flowchart_run_state_t(Structure): + """ + 机械臂程序运行状态结构体 + + **Args:** + - 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息) + + **Attributes:** + - run_state (int): 运行状态 0 未开始 1运行中 2暂停中 + - id (int): 当前使能的文件id。 + - name (str): 当前使能的文件名称。 + - plan_speed (int): 当前使能的文件全局规划速度比例 1-100。 + - step_mode (int): 单步模式,0为空,1为正常, 2为单步。 + - modal_id (str): 运行到的流程图块的id。未运行则不返回 + + """ + _fields_ = [ + ('run_state', c_int), + ('id', c_int), + ('name', c_char * int(32)), + ('plan_speed', c_int), + ('step_mode', c_int), + ('modal_id', c_char * int(50)), + ] + + def to_dict(self, recurse=True): + output_dict = { + "run_state": self.run_state, + "id": self.id, + "name": self.name.decode("utf-8"), + "plan_speed": self.plan_speed, + "step_mode": self.step_mode, + "modal_id": self.modal_id.decode("utf-8"), + } + return output_dict + +class rm_waypoint_t(Structure): + """ + 机械臂全局路点结构体 + """ + _fields_ = [ + ('point_name', c_char * int(40)), + ('joint', c_float * int(7)), + ('pose', rm_pose_t), + ('work_frame', c_char * int(12)), + ('tool_frame', c_char * int(12)), + ('time', c_char * int(50)), + ] + + def __init__(self, point_name: str = None, joint: list[float] = None, pose: list[float] = None, work_frame: str = None, tool_frame: str = None, time: str = ''): + """ + 全局路点结构体初始化 + + @param point_name (str, optional): 路点名称. 默认为None + @param joint (list[float], optional): 关节角度列表,长度为7,单位:°. 默认为None + @param pose (list[float], optional): 位姿信息,包含位置和欧拉角. 默认为None + 该列表应为 [x, y, z, rx, ry, rz] 格式,其中 [x, y, z] 是位置,[rx, ry, rz] 是欧拉角. + @param work_frame (str, optional): 工作坐标系名称. 默认为None + @param tool_frame (str, optional):工具坐标系名称. 默认为None + @param time (str, optional): 路点新增或修改时间. 默认为空字符串 + """ + if all(param is None for param in [point_name, joint, pose, work_frame, tool_frame]): + return + else: + # 路点名称 + self.point_name = point_name.encode('GBK') + # 关节角度 + self.joint = (c_float * ARM_DOF)(*joint) + + pose_value = rm_pose_t() + pose_value.position = rm_position_t(*pose[:3]) + pose_value.euler = rm_euler_t(*pose[3:]) + # 位姿信息,包含位置和欧拉角 + self.pose = pose_value + + # 工作坐标系名称 + self.work_frame = work_frame.encode('utf-8') + # 工具坐标系名称 + self.tool_frame = tool_frame.encode('utf-8') + + # 路点新增或修改时间 + self.time = time.encode('utf-8') + + def to_dict(self): + """将类的变量返回为字典""" + name = self.point_name.decode("GBK") + work_name = self.work_frame.decode("utf-8") + tool_name = self.tool_frame.decode("utf-8") + time = self.time.decode("utf-8") + position = self.pose.position + euler = self.pose.euler + + output_dict = { + "point_name": name, + "joint": [float(format(self.joint[i], ".3f")) for i in range(ARM_DOF)], + "pose": [position.x, position.y, position.z, euler.rx, euler.ry, euler.rz], + "work_frame": work_name, + "tool_frame": tool_name, + "time": time, + } + return output_dict + + +class rm_waypoint_list_t(Structure): + """ + 机械臂全局路点列表获取结构体 + + Args: + 无(无直接构造参数,此结构体通常由机械臂提供数据并填充,通过访问对应的属性读取信息) + + Attributes: + - page_num (int): 页码 + - page_size (int): 每页大小(即每页包含的路径点数量) + - total_size (int): 路点列表的总大小(即总路点数量) + - vague_search (bytes): 模糊搜索字符串(用于搜索路径点时的关键字) + - list_len (int): 返回符合的全局路点列表长度 + - points_list (rm_waypoint_t array[100]): 返回符合的全局路点列表 + """ + _fields_ = [ + ('page_num', c_int), + ('page_size', c_int), + ('total_size', c_int), + ('vague_search', c_char * int(32)), + ('list_len', c_int), + ('points_list', rm_waypoint_t * int(100)), + ] + + def to_dict(self): + vague_search = self.vague_search.decode("utf-8") + non_empty_outputs = [] + for i in range(self.list_len): + if self.points_list[i].point_name != b'': # 判断列表是否为空 + output = self.points_list[i].to_dict() + non_empty_outputs.append(output) + + output_dict = { + "total_size": self.total_size, + "list_len": self.list_len, + "points_list": non_empty_outputs, + } + return output_dict + + +class rm_fence_config_cube_t(Structure): + """几何模型长方体参数""" + _fields_ = [ + ('x_min_limit', c_float), + ('x_max_limit', c_float), + ('y_min_limit', c_float), + ('y_max_limit', c_float), + ('z_min_limit', c_float), + ('z_max_limit', c_float), + ] + + def __init__(self, x_min: float = None, x_max: float = None, y_min: float = None, y_max: float = None, z_min: float = None, z_max: float = None): + """几何模型长方体参数初始化 + + Args: + x_min (float, optional): 长方体基于世界坐标系 X 方向最小位置,单位 m. Defaults to None. + x_max (float, optional): 长方体基于世界坐标系 X 方向最大位置,单位 m. Defaults to None. + y_min (float, optional): 长方体基于世界坐标系 Y 方向最小位置,单位 m. Defaults to None. + y_max (float, optional): 长方体基于世界坐标系 Y 方向最大位置,单位 m. Defaults to None. + z_min (float, optional): 长方体基于世界坐标系 Z 方向最小位置,单位 m. Defaults to None. + z_max (float, optional): 长方体基于世界坐标系 Z 方向最大位置,单位 m. Defaults to None. + """ + if all(param is None for param in [x_min, x_max, y_min, y_max, z_min, z_max]): + return + else: + # 长方体基于世界坐标系 X 方向最小位置,单位 m + self.x_min_limit = x_min + # 长方体基于世界坐标系 X 方向最大位置,单位 m + self.x_max_limit = x_max + # 长方体基于世界坐标系 Y 方向最小位置,单位 m + self.y_min_limit = y_min + # 长方体基于世界坐标系 Y 方向最大位置,单位 m + self.y_max_limit = y_max + # 长方体基于世界坐标系 Z 方向最小位置,单位 m + self.z_min_limit = z_min + # 长方体基于世界坐标系 Z 方向最大位置,单位 m + self.z_max_limit = z_max + + +class rm_fence_config_plane_t(Structure): + """几何模型点面矢量平面参数""" + _fields_ = [ + ('x1', c_float), + ('y1', c_float), + ('z1', c_float), + ('x2', c_float), + ('y2', c_float), + ('z2', c_float), + ('x3', c_float), + ('y3', c_float), + ('z3', c_float), + ] + + def __init__(self, x1: float = None, y1: float = None, z1: float = None, x2: float = None, y2: float = None, z2: float = None, x3: float = None, y3: float = None, z3: float = None): + """几何模型点面矢量平面参数初始化 + + Args: + x1 (float, optional): 点面矢量平面三点法中的第一个点x坐标,单位 m. Defaults to None. + y1 (float, optional): 点面矢量平面三点法中的第一个点y坐标,单位 m. Defaults to None. + z1 (float, optional): 点面矢量平面三点法中的第一个点z坐标,单位 m. Defaults to None. + x2 (float, optional): 点面矢量平面三点法中的第二个点x坐标,单位 m. Defaults to None. + y2 (float, optional): 点面矢量平面三点法中的第二个点y坐标,单位 m. Defaults to None. + z2 (float, optional): 点面矢量平面三点法中的第二个点z坐标,单位 m. Defaults to None. + x3 (float, optional): 点面矢量平面三点法中的第三个点x坐标,单位 m. Defaults to None. + y3 (float, optional): 点面矢量平面三点法中的第三个点y坐标,单位 m. Defaults to None. + z3 (float, optional): 点面矢量平面三点法中的第三个点z坐标,单位 m. Defaults to None. + """ + if all(param is None for param in [x1, y1, z1, x2, y2, z2, x3, y3, z3]): + return + else: + # 点面矢量平面三点法中的第一个点x坐标,单位 m + self.x1 = x1 + # 点面矢量平面三点法中的第一个点y坐标,单位 m + self.y1 = y1 + # 点面矢量平面三点法中的第一个点z坐标,单位 m + self.z1 = z1 + # 点面矢量平面三点法中的第二个点x坐标,单位 m + self.x2 = x2 + # 点面矢量平面三点法中的第二个点y坐标,单位 m + self.y2 = y2 + # 点面矢量平面三点法中的第二个点z坐标,单位 m + self.z2 = z2 + # 点面矢量平面三点法中的第三个点x坐标,单位 m + self.x3 = x3 + # 点面矢量平面三点法中的第三个点y坐标,单位 m + self.y3 = y3 + # 点面矢量平面三点法中的第三个点z坐标,单位 m + self.z3 = z3 + + +class rm_fence_config_sphere_t(Structure): + """几何模型球体参数""" + _fields_ = [ + ('x', c_float), + ('y', c_float), + ('z', c_float), + ('radius', c_float), + ] + + def __init__(self, x: float = None, y: float = None, z: float = None, radius: float = None): + """几何模型球体参数初始化 + + Args: + x (float, optional): 表示球心在世界坐标系 X 轴的坐标,单位 m. Defaults to None. + y (float, optional): 表示球心在世界坐标系 Y 轴的坐标,单位 m. Defaults to None. + z (float, optional): 表示球心在世界坐标系 Z 轴的坐标,单位 m. Defaults to None. + radius (float, optional): 表示半径,单位 m. Defaults to None. + """ + if all(param is None for param in [x, y, z, radius]): + return + else: + # 表示球心在世界坐标系 X 轴的坐标,单位 m + self.x = x + # 表示球心在世界坐标系 Y 轴的坐标,单位 m + self.y = y + # 表示球心在世界坐标系 Z 轴的坐标,单位 m + self.z = z + # 表示半径,单位 m + self.radius = radius + + +class rm_fence_config_t(Structure): + """电子围栏参数结构体""" + _fields_ = [ + ('form', c_int), + ('name', c_char * int(12)), + ('cube', rm_fence_config_cube_t), + ('plan', rm_fence_config_plane_t), + ('sphere', rm_fence_config_sphere_t), + ] + + def __init__(self, form=0, name='', cube: rm_fence_config_cube_t=None, plane=None, sphere=None): + """ + 电子围栏参数初始化 + + @param form (int, optional): 形状,1 表示长方体,2 表示点面矢量平面,3 表示球体. Defaults to 0. + @param name (str, optional): 电子围栏名称,不超过 10 个字节,支持字母、数字、下划线. Defaults to ''. + @param cube (rm_fence_config_cube_t, optional): 长方体参数. Defaults to None. + @param plane (rm_fence_config_plane_t, optional): 点面矢量平面参数. Defaults to None. + @param sphere (rm_fence_config_sphere_t, optional): 球体参数. Defaults to None. + """ + if all(param is None for param in [cube, plane, sphere]): + return + else: + # 形状,1 表示长方体,2 表示点面矢量平面,3 表示球体 + self.form = form + # 电子围栏名称 + self.name = name.encode('utf-8')[:12] # 将字符串编码为字节,并限制长度为12 + + if cube is not None and self.form == 1: + # 长方体参数 + self.cube = cube + else: + self.cube = rm_fence_config_cube_t() # 否则创建一个默认的cube实例 + + if plane is not None and self.form == 2: + # 点面矢量平面参数 + self.plane = plane + else: + self.plane = rm_fence_config_plane_t() + + if sphere is not None and self.form == 3: + # 球体参数 + self.sphere = sphere + else: + self.sphere = rm_fence_config_sphere_t() + + def to_dict(self): + name = self.name.decode("utf-8").strip() # 去除字符串两端的空白字符 + output_dict = {"name": name} + + if self.form == 1: # 立方体 + output_dict.update({ + "form": "cube", + "x_min_limit": float(format(self.cube.x_min_limit, ".3f")), + "x_max_limit": float(format(self.cube.x_max_limit, ".3f")), + "y_min_limit": float(format(self.cube.y_min_limit, ".3f")), + "y_max_limit": float(format(self.cube.y_max_limit, ".3f")), + "z_min_limit": float(format(self.cube.z_min_limit, ".3f")), + "z_max_limit": float(format(self.cube.z_max_limit, ".3f")), + }) + elif self.form == 2: # 点面矢量平面 + output_dict.update({ + "form": "point_face_vector_plane", + "x1": float(format(self.plan.x1, ".3f")), + "y1": float(format(self.plan.y1, ".3f")), + "z1": float(format(self.plan.z1, ".3f")), + "x2": float(format(self.plan.x2, ".3f")), + "y2": float(format(self.plan.y2, ".3f")), + "z2": float(format(self.plan.z2, ".3f")), + "x3": float(format(self.plan.x3, ".3f")), + "y3": float(format(self.plan.y3, ".3f")), + "z3": float(format(self.plan.z3, ".3f")), + }) + elif self.form == 3: # 球体 + output_dict.update({ + "form": "sphere", + "radius": float(format(self.sphere.radius, ".3f")), + "x": float(format(self.sphere.x, ".3f")), + "y": float(format(self.sphere.y, ".3f")), + "z": float(format(self.sphere.z, ".3f")), + }) + + return output_dict + + +class rm_fence_names_t(Structure): + """ + 几何模型名称结构体 + + **Attributes:** + - name (bytes): 几何模型名称,不超过10个字符 + """ + _fields_ = [ + # 几何模型名称,不超过10个字符 + ('name', c_char * int(12)), + ] + + +class rm_fence_config_list_t(Structure): + """ + 几何模型参数列表 + + **Attributes:** + - config (rm_fence_config_t[]): 几何模型参数列表,不超过10个 + """ + _fields_ = [ + ('config', rm_fence_config_t * int(10)), + ] + + +class rm_envelopes_ball_t(Structure): + """工具坐标系包络参数""" + _fields_ = [ + ('name', c_char * int(12)), + ('radius', c_float), + ('x', c_float), + ('y', c_float), + ('z', c_float), + ] + + def __init__(self, name: str = None, radius: float = None, x: float = None, y: float = None, z: float = None): + """工具坐标系包络参数初始化 + + **Args:** + name (str, optional): 工具包络球体的名称,1-10 个字节,支持字母数字下划线. Defaults to None. + radius (float, optional): 工具包络球体的半径,单位 0.001m. Defaults to None. + x (float, optional): 工具包络球体球心基于末端法兰坐标系的 X 轴坐标,单位 m. Defaults to None. + y (float, optional): 工具包络球体球心基于末端法兰坐标系的 Y 轴坐标,单位 m. Defaults to None. + z (float, optional): 工具包络球体球心基于末端法兰坐标系的 Z 轴坐标,单位 m. Defaults to None. + """ + if all(param is None for param in [name, radius, x, y, z]): + return + else: + # 工具包络球体的名称,1-10 个字节,支持字母数字下划线 + self.name = name.encode('utf-8') + # 工具包络球体的半径,单位 0.001m + self.radius = radius + # 工具包络球体球心基于末端法兰坐标系的 X 轴坐标,单位 m + self.x = x + # 工具包络球体球心基于末端法兰坐标系的 Y 轴坐标,单位 m + self.y = y + # 工具包络球体球心基于末端法兰坐标系的 Z 轴坐标,单位 m + self.z = z + + def to_dictionary(self): + """输出结果为字典""" + name = self.name.decode("utf-8") + # 创建一个字典,包含rm_envelopes_ball_t的所有属性 + output_dict = { + "name": name, + "radius": float(format(self.radius, ".3f")), + "x": float(format(self.x, ".3f")), + "y": float(format(self.y, ".3f")), + "z": float(format(self.z, ".3f")) + } + return output_dict + + +class rm_envelope_balls_list_t(Structure): + """工具的包络参数结构体,包含工具名称、包络球列表以及数量. + """ + _fields_ = [ + ('balls', rm_envelopes_ball_t * int(5)), + ('size', c_int), + ('tool_name', c_char * 12), + ] + + def __init__(self, tool_name: str = None, balls=None, size=None): + """工具的包络参数结构体 + @param tool_name (str, optional): 工具的名称。 + @param balls (list, optional): 一个包含rm_envelopes_ball_t实例的列表,表示包络球。 + @param size (int, optional): 包络球的数量。 + """ + if all(param is None for param in [tool_name, balls, size]): + return + else: + # 工具的名称。 + self.tool_name: str = tool_name.encode('utf-8') + """工具名称""" + # 包含rm_envelopes_ball_t实例的列表,表示包络球,最多5个。 + self.balls = (rm_envelopes_ball_t * 5)(*balls) + """包含rm_envelopes_ball_t实例的列表,表示包络球,最多5个。""" + # 包络球的数量。 + self.size = size + """包络球的数量。""" + + def to_dictionary(self): + """将类的变量输出为字典""" + name = self.tool_name.decode("utf-8") + + output_dict = { + "tool_name": name, + "list": [self.balls[i].to_dictionary() for i in range(self.size)], + "size": self.size, + } + + return output_dict + + +class rm_electronic_fence_enable_t(Structure): + """电子围栏/虚拟墙使能状态结构体""" + _fields_ = [ + ('enable_state', c_bool), + ('in_out_side', c_int), + ('effective_region', c_int), + ] + + def __init__(self, enable_state: bool = None, in_out_side: int = None, effective_region: int = None): + """工具的包络参数结构体 + @param enable_state (bool, optional): 电子围栏/虚拟墙使能状态,true 代表使能,false 代表禁使能 + @param in_out_side (int, optional): 0-机器人在电子围栏/虚拟墙内部,1-机器人在电子围栏外部 + @param effective_region (int, optional): 0-电子围栏针对整臂区域生效,1-虚拟墙针对末端生效 + """ + if all(param is None for param in [enable_state, in_out_side, effective_region]): + return + else: + # 电子围栏/虚拟墙使能状态,true 代表使能,false 代表禁使能 + self.enable_state = enable_state + # 0-机器人在电子围栏/虚拟墙内部,1-机器人在电子围栏外部 + self.in_out_side = in_out_side + # 0-电子围栏针对整臂区域生效,1-虚拟墙针对末端生效 + self.effective_region = effective_region + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + + return result + +class rm_movej_canfd_mode_t(Structure): + """ + 角度透传模式结构体 + + **Attributes**: + - joint (list[float]): 关节角度(若为六轴机械臂,那么最后一个元素无效),单位° + - expand (float): 扩展关节角度(若没有扩展关节,那么此成员值无效) + - follow (int): 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + - trajectory_mode (int): 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + - radio (int): 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),0~100 + """ + _fields_ = [ + ('joint', POINTER(c_float * 7)), + ('expand', c_float), + ('follow', c_bool), + ('trajectory_mode', c_int), + ('radio', c_int) + ] + +class rm_movev_canfd_mode_t(Structure): + """ + 笛卡尔速度透传模式结构体 + + 建议初始化方式:rm_movev_canfd_mode_t() (自动初始化为0值,避免未知错误) + + **Attributes**: + - cartesian_velocity (POINTER(c_float * 6)): 笛卡尔速度数组指针(6个元素,对应x、y、z、rx、ry、rz),单位:0.001mm/s(平移)、0.001rad/s(旋转),线速度最大值:0.250m/s,角速度最大值:0.6rad/s) + - follow (c_bool): 驱动器运动跟随模式,True为高跟随(透传周期需≤10ms),False为低跟随 + - trajectory_mode (c_int): 高跟随模式下的轨迹模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + - radio (c_int): 模式参数: + - trajectory_mode=0(完全透传):无效(默认模式,直接透传原始数据) + - trajectory_mode=1(曲线拟合):平滑系数(0~100,值越大轨迹越平滑,滞后越明显) + - trajectory_mode=2(滤波模式):滤波参数(0~1000,值越大轨迹越平滑,需持续发送最终目标点直至到达) + """ + _fields_ = [ + ('cartesian_velocity', POINTER(c_float * 6)), # 指向6元素float数组的指针(笛卡尔6自由度) + ('follow', c_bool), + ('trajectory_mode', c_int), + ('radio', c_int) + ] + +class rm_movep_canfd_mode_t(Structure): + """ + 姿态透传模式结构体 + **Attributes**: + - pose (rm_pose_t): 位姿 (优先采用四元数表达) + - follow (int): 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + - trajectory_mode (int): 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + - radio (int): 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),0~100 + """ + _fields_ = [ + ('pose', rm_pose_t), + ('follow', c_bool), + ('trajectory_mode', c_int), + ('radio', c_int) + ] + +class rm_force_sensor_t(Structure): + """ + 力控数据结构体 + + **Attributes**: + - force (list[float]): 当前力传感器原始数据,力的单位为N;力矩单位为Nm。 + - zero_force (list[float]): 当前力传感器系统外受力数据,力的单位为N;力矩单位为Nm。 + - coordinate (int): 系统外受力数据的坐标系,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 + """ + _fields_ = [ + ('force', c_float * int(6)), + ('zero_force', c_float * int(6)), + ('coordinate', c_int), + ] + + def to_dict(self, recurse=True): + result = { + 'force': list(self.force), + 'zero_force': list(self.zero_force), + 'coordinate': self.coordinate, + } + return result + + +class rm_udp_expand_state_t(Structure): + """ + 扩展关节状态 + + **Attributes**: + - pos (float): 当前角度 精度 0.001°,单位:° + - current (int): 当前驱动电流,单位:mA,精度:1mA + - err_flag (int): 驱动错误代码,错误代码类型参考关节错误代码 + - en_flag (int): 当前关节使能状态 ,1 为上使能,0 为掉使能 + - joint_id (int): 关节id号 + - mode (int): 当前升降状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 + """ + _fields_ = [ + ('pos', c_float), + ('current', c_int), + ('err_flag', c_int), + ('en_flag', c_int), + ('joint_id', c_int), + ('mode', c_int), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + +class rm_udp_lift_state_t(Structure): + """ + 升降机构状态 + + **Attributes**: + - height (int): 当前升降机构高度,单位:mm,精度:1mm + - pos (float): 当前角度 精度 0.001°,单位:° + - current (int): 当前驱动电流,单位:mA,精度:1mA + - err_flag (int): 驱动错误代码,错误代码类型参考关节错误代码 + - en_flag (int): 当前关节使能状态 ,1 为上使能,0 为掉使能 + """ + _fields_ = [ + ('height', c_int), + ('pos', c_float), + ('current', c_int), + ('err_flag', c_int), + ('en_flag', c_int), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + +class rm_udp_hand_state_t(Structure): + """ + 灵巧手状态 + + **Attributes**: + - hand_pos (int): 表示灵巧手位置 + - hand_angle (int): 表示灵巧手角度 + - hand_force (float): 表示灵巧手自由度力,单位mN + - hand_state (int): 表示灵巧手当前状态,由灵巧手厂商定义状态含义。例如因时状态码含义定义: + - 0: 正在松开 + - 1: 正在抓取 + - 2: 位置到位停止 + - 3: 力控到位停止 + - 5: 电流保护停止 + - 6: 电缸堵转停止 + - 7: 电缸故障停止 + - hand_err (int): 表示灵巧手系统错误,由灵巧手厂商定义错误含义,例如因时错误码如下:1表示有错误,0表示无错误 + """ + _fields_ = [ + ('hand_pos', c_int * int(6)), + ('hand_angle', c_int * int(6)), + ('hand_force', c_int * int(6)), + ('hand_state', c_int * int(6)), + ('hand_err', c_int), + ] + + def to_dict(self, recurse=True): + result = { + 'hand_pos': list(self.hand_pos), + 'hand_angle': list(self.hand_angle), + 'hand_force': list(self.hand_force), + 'hand_state': list(self.hand_state), + 'hand_err': self.hand_err, + } + return result + + +class rm_udp_aloha_state_t(Structure): + """ + aloha主臂状态 + + **Attributes**: + - io1_state (int): IO1状态(手柄光电检测),0为按键未触发,1为按键触发。 + - io2_state (int): IO2状态(手柄光电检测),0为按键未触发,1为按键触发。 + """ + _fields_ = [ + ('io1_state', c_int), + ('io2_state', c_int), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_udp_arm_current_status_e(IntEnum): + """udp推送机械臂状态枚举 + """ + RM_IDLE_E = 0 # 使能但空闲状态 + RM_MOVE_L_E = RM_IDLE_E + 1 # move L运动中状态 + RM_MOVE_J_E = RM_MOVE_L_E + 1 # move J运动中状态 + RM_MOVE_C_E = RM_MOVE_J_E + 1 # move C运动中状态 + RM_MOVE_S_E = RM_MOVE_C_E + 1 # move S运动中状态 + RM_MOVE_THROUGH_JOINT_E = RM_MOVE_S_E + 1 # 角度透传状态 + RM_MOVE_THROUGH_POSE_E = RM_MOVE_THROUGH_JOINT_E + 1 # 位姿透传状态 + RM_MOVE_THROUGH_FORCE_POSE_E = RM_MOVE_THROUGH_POSE_E + 1 # 力控透传状态 + RM_MOVE_THROUGH_CURRENT_E = RM_MOVE_THROUGH_FORCE_POSE_E + 1 # 电流环透传状态 + RM_STOP_E = RM_MOVE_THROUGH_CURRENT_E + 1 # 急停状态 + RM_SLOW_STOP_E = RM_STOP_E + 1 # 缓停状态 + RM_PAUSE_E = RM_SLOW_STOP_E + 1 # 暂停状态 + RM_CURRENT_DRAG_E = RM_PAUSE_E + 1 # 电流环拖动状态 + RM_SENSOR_DRAG_E = RM_CURRENT_DRAG_E + 1 # 六维力拖动状态 + RM_TECH_DEMONSTRATION_E = RM_SENSOR_DRAG_E + 1 # 示教状态 + RM_TRAJECTORY_REPRODUCTON_E = RM_TECH_DEMONSTRATION_E + 1 #轨迹复现状态 + RM_MOVE_INIT_POSITION_E = RM_TRAJECTORY_REPRODUCTON_E + 1 #长按蓝色按钮运动到初始位置状态 + RM_MOVEV_CANFD_E = RM_MOVE_INIT_POSITION_E + 1 #笛卡尔速度透传 + +class rm_plus_base_info_t(Structure): + _fields_ = [ + ("manu", c_char * 10), # 设备厂家 + ("type", c_int), # 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 + ("hv", c_char * int(10)), # 硬件版本 + ("sv", c_char * int(10)), # 软件版本 + ("bv", c_char * int(10)), # boot版本 + ("id", c_int), # 设备ID + ("dof", c_int), # 自由度 + ("check", c_int), # 自检开关 + ("bee", c_int), # 蜂鸣器开关 + ("force", c_bool), # 力控支持 + ("touch", c_bool), # 触觉支持 + ("touch_num", c_int), # 触觉个数 + ("touch_sw", c_int), # 触觉开关 + ("hand", c_int), # 手方向 1 :左手 2: 右手 + ("pos_up", c_int * 6), # 位置上限 + ("pos_low", c_int * 6), # 位置下限 + ("angle_up", c_int * 6), # 角度上限 + ("angle_low", c_int * 6), # 角度下限 + ("speed_up", c_int * 6), # 速度上限 + ("speed_low", c_int * 6), # 速度下限 + ("force_up", c_int * 6), # 力上限 + ("force_low", c_int * 6), # 力下限 + ] + + def to_dict(self, recurse=True): + output_dict = { + "manu": self.manu.decode('utf-8'), + "type": self.type, + "hv": self.hv.decode('utf-8'), + "sv": self.sv.decode('utf-8'), + "bv": self.bv.decode('utf-8'), + "id": self.id, + "dof": self.dof, + "check": self.check, + "bee": self.bee, + "force": self.force, + "touch": self.touch, + "touch_num": self.touch_num, + "touch_sw": self.touch_sw, + "hand": self.hand, + "pos_up": list(self.pos_up), + "pos_low": list(self.pos_low), + "angle_up": list(self.angle_up), + "angle_low": list(self.angle_low), + "speed_up": list(self.speed_up), + "speed_low": list(self.speed_low), + "force_up": list(self.force_up), + "force_low": list(self.force_low), + } + return output_dict + +class rm_plus_state_info_t(Structure): + _fields_ = [ + ("sys_state", c_int), # 系统状态 + ("dof_state", c_int * 6), # 各自由度当前状态 + ("dof_err", c_int * 6), # 各自由度错误信息 + ("pos", c_int * 6), # 各自由度当前位置 + ("speed", c_int * 6), # 各自由度当前速度,闭合正,松开负,单位:无量纲 + ("angle", c_int * 6), # 各自由度当前角度 + ("current", c_int * 6), # 各自由度当前电流 + ("normal_force", c_int * 18), # 自由度触觉三维力的法向力 + ("tangential_force", c_int * 18), # 自由度触觉三维力的切向力 + ("tangential_force_dir", c_int * 18), # 自由度触觉三维力的切向力方向 + ("tsa", c_uint32 * 12), # 自由度触觉自接近 + ("tma", c_uint32 * 12), # 自由度触觉互接近 + ("touch_data",c_int * 18), # 触觉传感器原始数据 + ("force",c_int * 6), # 自由度力矩,闭合正,松开负,单位0.001N + ] + + def to_dict(self, recurse=True): + output_dict = { + "sys_state" : self.sys_state, + "dof_state" : list(self.dof_state), + "dof_err" : list(self.dof_err), + "pos" : list(self.pos), + "speed" : list(self.speed), + "angle" : list(self.angle), + "current" : list(self.current), + "normal_force" : list(self.normal_force), + "tangential_force" : list(self.tangential_force), + "tangential_force_dir" : list(self.tangential_force_dir), + "tsa" : list(self.tsa), + "tma" : list(self.tma), + "touch_data" : list(self.touch_data), + "force" : list(self.force), + } + return output_dict + + +class rm_realtime_arm_joint_state_t(Structure): + """ + 机械臂实时状态推送信息结构体 + + **Attributes**: + - errCode (int): 数据解析错误码,-3为数据解析错误,代表推送的数据不完整或格式不正确 + - arm_ip (bytes): 推送数据的机械臂的IP地址 + - joint_status (rm_joint_status_t): 机械臂关节状态结构体 + - force_sensor (rm_force_sensor_t): 力传感器数据结构体 + - err (rm_err_t): 错误码结构体 + - waypoint (rm_pose_t): 当前位置姿态结构体 + - liftState (rm_udp_lift_state_t): 升降关节数据 + - expandState (rm_udp_expand_state_t): 扩展关节数据 + - handState (rm_udp_hand_state_t): 灵巧手数据 + - arm_current_status (int): 机械臂状态,对应rm_udp_arm_current_status_e枚举 + - aloha_state (rm_udp_aloha_state_t): aloha主臂状态 + - rm_plus_state (int): 末端设备状态,0-设备在线,1-表示协议未开启,2-表示协议开启但是设备不在线 + - plus_base_info (rm_plus_base_info_t): 末端设备基础信息 + - plus_state_info (rm_plus_state_info_t): 末端设备实时信息 + """ + _fields_ = [ + ('errCode', c_int), + ('arm_ip', c_char * int(16)), + ('joint_status', rm_joint_status_t), + ('force_sensor', rm_force_sensor_t), + ('err', rm_err_t), + ('waypoint', rm_pose_t), + ('liftState', rm_udp_lift_state_t), + ('expandState', rm_udp_expand_state_t), + ('handState', rm_udp_hand_state_t), + ('arm_current_status', c_int), + ('aloha_state', rm_udp_aloha_state_t), + ('rm_plus_state', c_int), + ('plus_base_info', rm_plus_base_info_t), + ('plus_state_info',rm_plus_state_info_t), + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_inverse_kinematics_params_t(Structure): + """ + 逆运动学参数结构体。 + + **Args:** + - q_in (List[float], optional): 上一时刻关节角度,单位°,默认为None。 + - q_pose (List[float], optional): 目标位姿,根据flag的值,可以是位置+四元数或位置+欧拉角,默认为None。 + - flag (int, optional): 标志位,0表示使用四元数,1表示使用欧拉角,默认为None。 + """ + _fields_ = [ + ('q_in', c_float * int(7)), + ('q_pose', rm_pose_t), + ('flag', uint8_t), + ] + + def __init__(self, q_in: list[float] = None, q_pose: list[float] = None, flag: int = None): + """逆运动学参数初始化 + + Args: + q_in (list[float], optional): 上一时刻关节角度,单位°. Defaults to None. + q_pose (list[float], optional): 目标位姿. Defaults to None. + flag (int, optional): 姿态参数类别:0-四元数;1-欧拉角. Defaults to None. + """ + if all(param is None for param in [q_in, q_pose, flag]): + return + else: + # 上一时刻关节角度,单位° + self.q_in = (c_float*7)(*q_in) + + po1 = rm_pose_t() + po1.position = rm_position_t(*q_pose[:3]) + # 四元数 + if flag == 0: + po1.quaternion = rm_quat_t(*q_pose[3:]) + # 欧拉角 + elif flag == 1: + po1.euler = rm_euler_t(*q_pose[3:]) + # 目标位姿。根据flag的值,可以是位置+四元数或位置+欧拉角。 + self.q_pose = po1 + # 姿态数据的类别:0表示使用四元数,1表示使用欧拉角。 + self.flag = flag + +class rm_inverse_kinematics_all_solve_t(ctypes.Structure): + """ + 逆运动学全解参数结构体。 + + **Args:** + - result: 逆解求解结果,0:成功,1:逆解失败,-1:上一时刻关节角度输入为空或超关节限位,-2:目标位姿四元数不合法 + - num ( optional): 目标位姿,根据flag的值,可以是位置+四元数或位置+欧拉角,默认为None。 + - q_ref (List[float]): 参考关节角度,通常是当前关节角度, 单位 ° + - q_solve(List[float]): 关节角全解, 8x8 数组, 单位 ° + """ + _fields_ = [ + ("result", ctypes.c_int), + ("num", ctypes.c_int), + ("q_ref", ctypes.c_float * 8), + ("q_solve", (ctypes.c_float * 8) * 8), + ] + + +class rm_matrix_t(Structure): + """ + 矩阵结构体 + + **Attributes:** + - irow (int): 矩阵的行数。 + - iline (int): 矩阵的列数。 + - data (List[float]): 矩阵的数据部分,大小为4x4的浮点数矩阵。 + """ + _fields_ = [ + ('irow', c_short), + ('iline', c_short), + ('data', (c_float * 16)), + ] + + + def __init__(self, irow=4, iline=4, data=None): + super().__init__() + self.irow = irow + self.iline = iline + + if data is None: + self.data = (c_float * 16)(*([0.0] * 16)) # 初始化所有元素为0.0 + else: + flattened_data = [float(val) for row in data for val in row] + if len(flattened_data) != 16: + raise ValueError("Data must contain exactly 16 elements for a 4x4 matrix") + self.data = (c_float * 16)(*flattened_data) + +# 定义机械臂事件回调函数类型,该回调函数接受一个类型为 rm_event_push_data_t 的参数 +rm_event_callback_ptr = CFUNCTYPE(None, rm_event_push_data_t) +# 定义机械臂实时状态回调函数类型,该回调函数接受一个类型为 rm_realtime_arm_joint_state_t 的参数 +rm_realtime_arm_state_callback_ptr = CFUNCTYPE( + None, rm_realtime_arm_joint_state_t) + + +class rm_robot_info_t(Structure): + """ + 机械臂基本信息结构体 + + **Args:** + 无直接构造参数,所有字段应通过访问属性进行设置。 + + **Attributes:** + arm_dof (int): 机械臂的自由度数量。 + arm_model (int): 机械臂型号。 + force_type (int): 机械臂末端力控类型。 + robot_controller_version (int): 机械臂控制器版本,4:四代控制器,3:三代控制器。 + """ + _fields_ = [ + ('arm_dof', uint8_t), + ('arm_model', c_int), + ('force_type', c_int), + ('robot_controller_version', uint8_t) + ] + + def to_dictionary(self): + """将int类型数据转化为字符串,并输出结果为字典 + @return dict: 包含机械臂自由度'arm_dof'、型号'arm_model'、末端力控版本'force_type'值的字典 + """ + arm_dof = self.arm_dof + model_to_string = { + rm_robot_arm_model_e.RM_MODEL_RM_65_E: "RM_65", + rm_robot_arm_model_e.RM_MODEL_RM_75_E: "RM_75", + rm_robot_arm_model_e.RM_MODEL_RM_63_I_E: "RML_63", + rm_robot_arm_model_e.RM_MODEL_RM_63_II_E: "RML_63", + rm_robot_arm_model_e.RM_MODEL_RM_63_III_E: "RML_63", + rm_robot_arm_model_e.RM_MODEL_ECO_65_E: "ECO_65", + rm_robot_arm_model_e.RM_MODEL_ECO_62_E: "ECO_62", + rm_robot_arm_model_e.RM_MODEL_GEN_72_E: "GEN_72", + rm_robot_arm_model_e.RM_MODEL_ECO_63_E: "ECO_63", + rm_robot_arm_model_e.RM_MODEL_UNIVERSAL_E: "RM_UNIVERSAL", + rm_robot_arm_model_e.RM_MODEL_ZM7L_E: "ZM7L", + rm_robot_arm_model_e.RM_MODEL_ZM7R_E: "ZM7R", + rm_robot_arm_model_e.RM_MODEL_RXL75_E: "RXL75", + rm_robot_arm_model_e.RM_MODEL_RXR75_E: "RXR75", + } + force_to_string = { + rm_force_type_e.RM_MODEL_RM_B_E: "B", + rm_force_type_e.RM_MODEL_RM_ZF_E: "ZF", + rm_force_type_e.RM_MODEL_RM_SF_E: "SF", + rm_force_type_e.RM_MODEL_RM_ISF_E: "ISF" + } + + # 使用字典来查找对应的字符串表示 + model_string = "Unknown" + force_type = "Unknown" + try: + model_string = model_to_string[self.arm_model] + force_type = force_to_string[self.force_type] + except KeyError: + print(f"Unknown model value: {self.arm_model}, {self.force_type}") + arm_model = model_string + + output_dict = { + "arm_dof": arm_dof, + "arm_model": model_string if arm_dof != 0 else None, + "force_type": force_type if arm_dof != 0 else None, + "robot_controller_version": self.robot_controller_version, + } + + return output_dict + + +class rm_robot_handle(Structure): + """ + 机械臂句柄结构体 + + **Attributes**: + - id (int): 机械臂的唯一标识符,通过rm_create_robot_arm接口可创建机械臂句柄,用于在程序中控制特定的机械臂。 + + """ + _fields_ = [ + ('id', c_int), + ] + +class rm_multi_drag_teach_t(Structure): + """复合拖动示教参数 + + **Attributes:** + free_axes (list[int]): 自由驱动方向[x,y,z,rx,ry,rz],0-在参考坐标系对应方向轴上不可拖动,1-在参考坐标系对应方向轴上可拖动 + frame (int): 参考坐标系,0-工作坐标系 1-工具坐标系。 + singular_wall (int): 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙,若无配置参数,默认启动拖动奇异墙 + """ + _fields_ = [ + ('free_axes', c_int * int(6)), + ('frame', c_int), + ('singular_wall', c_int), + ] + + +class rm_force_position_t(Structure): + """力位混合控制参数结构体 + """ + _fields_ = [ + ('sensor', c_int), # 传感器;0-一维力;1-六维力 + ('mode', c_int), # 0-工作坐标系力控;1-工具坐标系力控; + ('control_mode', c_int * int(6)), # 6个方向(Fx Fy Fz Mx My Mz)的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模 4-力跟踪模式 8-力跟踪+姿态自适应模式(新参数,模式8只对工具坐标系的Fz方向有效) + ('desired_force', c_float * int(6)), # 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,单位0.1N。 + ('limit_vel', c_float * int(6)), # 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。(x、y、z)轴的最大线速度,单位为0.001 m/s,(rx、ry、rz)轴的最大角速度单位为0001 °/s + ] + +class rm_force_position_move_t(Structure): + """透传力位混合补偿参数 + """ + _fields_ = [ + ('flag', c_int), # 0-下发目标角度,1-下发目标位姿 + ('pose', rm_pose_t), # 当前坐标系下的目标位姿,支持四元数/欧拉角表示姿态。位置精度:0.001mm,欧拉角表示姿态,姿态精度:0.001rad,四元数方式表示姿态,姿态精度:0.000001 + ('joint', c_float * int(7)), # 目标关节角度,单位:°,精度:0.001° + ('sensor', c_int), # 传感器,0-一维力;1-六维力 + ('mode', c_int), # 0-基坐标系力控;1-工具坐标系力控; + ('follow', c_bool), # 表示驱动器的运动跟随效果,true 为高跟随,false 为低跟随。 + ('control_mode', c_int * int(6)), # 6个力控方向的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模式 4-力跟踪模式 5-浮动+运动模式 6-弹簧+运动模式 7-力跟踪+运动模式 8-姿态自适应模式 + ('desired_force', c_float * int(6)), # 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。 + ('limit_vel', c_float * int(6)), # 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。 + ('trajectory_mode', c_int), # 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + ('radio', c_int), # 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),0~100 + ] + + def __init__(self, flag: int = None, pose: list[float] = None, joint: list[float] = None, sensor: int = None, mode:int = None, + follow:bool = None, control_mode:list[int] =None,desired_force:list[float] =None,limit_vel:list[float] =None, + trajectory_mode: int = None, radio: int = None): + """透传力位混合补偿参数初始化 + """ + if all(param is None for param in [flag,pose,joint,sensor,mode,follow,control_mode,desired_force,limit_vel]): + return + else: + if flag is not None: + self.flag = flag + if flag == 1: + # pose长度为6时认为使用欧拉角,长度为7时认为使用四元数 + if pose is not None and len(pose) == 6: + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.euler = rm_euler_t(*pose[3:]) + if pose is not None and len(pose) == 7: + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.quaternion = rm_quat_t(*pose[3:]) + self.pose = po1 + elif flag == 0: + self.joint = (c_float*7)(*joint) + if sensor is not None: + self.sensor = sensor + if mode is not None: + self.mode = mode + if follow is not None: + self.follow = follow + if control_mode is not None and len(control_mode) == 6: + self.control_mode = (c_int * 6)(*control_mode) + if desired_force is not None and len(desired_force) == 6: + self.desired_force = (c_float * 6)(*desired_force) + if limit_vel is not None and len(limit_vel) == 6: + self.limit_vel = (c_float * 6)(*limit_vel) + if trajectory_mode is not None: + self.trajectory_mode = trajectory_mode + if radio is not None: + self.radio = radio + +class rm_dh_t(Structure): + _fields_ = [ + ('d', c_float * int(8)), # unit: m + ('a', c_float * int(8)), # unit: m + ('alpha', c_float * int(8)), # unit: ° + ('offset', c_float * int(8)), # unit: ° + ] + def __init__(self, d: list[float] = None, a: list[float] = None, alpha: list[float] = None, offset: list[float] = None): + if all(param is None for param in [d, a, alpha, offset]): + return + else: + self.d = (c_float * 8)(*d) + self.a = (c_float * 8)(*a) + self.alpha = (c_float * 8)(*alpha) + self.offset = (c_float * 8)(*offset) + + def to_dict(self, dof, recurse=True): + output_dict = { + "d": list(self.d[:dof]), + "a": list(self.a[:dof]), + "alpha": list(self.alpha[:dof]), + "offset": list(self.offset[:dof]) + } + return output_dict + + +class rm_tool_sphere_t(Structure): + _fields_ = [ + ("radius", c_float), # 球体半径(单位:m) + ("centrePoint", c_float * int(3)), # 球体中心位置(单位:m,以法兰坐标系为参考坐标系) + ] + + +class rm_version_t(Structure): + _fields_ = [ + ('version', c_char * int(10)), + ] + +class rm_trajectory_info_t(Structure): + _fields_ = [ + ('point_num', c_int), # 轨迹点数量 + ('name', c_char * int(20)), # 轨迹名称 + ('create_time', c_char * int(20)), # 创建时间 + ] + + def to_dict(self, recurse=True): + output_dict = { + "point_num": self.point_num, + "name": self.name.decode('utf-8'), + "create_time": self.create_time.decode('utf-8') + } + return output_dict + +class rm_trajectory_list_t(Structure): + _fields_ = [ + ('page_num', c_int), # 页码 + ('page_size', c_int), # 每页大小 + ('total_size', c_int), # 列表长度 + ('vague_search', c_char * int(32)), # 模糊搜索 + ('list_len', c_int), # 返回符合的轨迹列表长度 + ('tra_list', rm_trajectory_info_t * int(100)), # 返回符合的轨迹列表 + ] + + def to_dict(self, recurse=True): + vague_search = self.vague_search.decode("utf-8") + non_empty_outputs = [] + for i in range(self.list_len): + output = self.tra_list[i].to_dict() + non_empty_outputs.append(output) + + output_dict = { + "page_num": self.page_num, + "page_size": self.page_size, + "total_size": self.total_size, + "vague_search": self.vague_search.decode('utf-8'), + "list_len": self.list_len, + "tra_list": non_empty_outputs + } + return output_dict + +class rm_modbus_tcp_master_info_t(Structure): + _fields_ = [ + ('master_name', c_char * int(20)), # Modbus 主站名称,最大长度15个字符,不超过15个字符 + ('ip', c_char * int(16)), # TCP主站 IP 地址 + ('port', c_int), # TCP主站端口号 + ] + + def __init__(self, master_name: str = None, ip: str = None, port: int = None): + if all(param is None for param in [master_name, ip, port]): + return + else: + self.master_name = master_name.encode('utf-8') + self.ip = ip.encode('utf-8') + self.port = port + + + def to_dict(self, recurse=True): + output_dict = { + "master_name": self.master_name.decode('utf-8'), + "ip": self.ip.decode('utf-8'), + "port": self.port + } + return output_dict + + +class rm_modbus_tcp_master_list_t(Structure): + _fields_ = [ + ('page_num', c_int), # 页码 + ('page_size', c_int), # 每页大小 + ('total_size', c_int), # 列表长度 + ('vague_search', c_char * int(32)), # 模糊搜索 + ('list_len', c_int), # 返回符合的TCP主站列表长度 + ('master_list', rm_modbus_tcp_master_info_t * int(100)), # 返回符合的TCP主站列表 + ] + def to_dict(self, recurse=True): + output_dict = { + "page_num": self.page_num, + "page_size": self.page_size, + "total_size": self.total_size, + "vague_search": self.vague_search.decode('utf-8'), + "list_len": self.list_len, + "master_list": [self.master_list[i].to_dict() for i in range(self.list_len)] + } + return output_dict + +class rm_modbus_rtu_read_params_t(Structure): + _fields_ = [ + ('address', c_int), # 数据起始地址 + ('device', c_int), # 外设设备地址 + ('type', c_int), # 0-控制器端modbus主机;1-工具端modbus主机。 + ('num', c_int), # 要读的数据的数量,数据长度不超过109 + ] + + def __init__(self, address: int = None, device: int = None, type: int = None, num: int = None): + if all(param is None for param in [address, device, type, num]): + return + else: + self.address = address + self.device = device + self.type = type + self.num = num + +class rm_modbus_rtu_write_params_t(Structure): + _fields_ = [ + ('address', c_int), # 数据起始地址 + ('device', c_int), # 外设设备地址 + ('type', c_int), # 0-控制器端modbus主机;1-工具端modbus主机。 + ('num', c_int), # 要写的数据的数量,最大不超过100 + ('data', c_int * int(120)), # 要写的数据,数据长度不超过100 + ] + def __init__(self, address: int = None, device: int = None, type: int = None, num: int = None, data: list[int] = None): + if all(param is None for param in [address, device, type, num, data]): + return + else: + self.address = address + self.device = device + self.type = type + self.num = num + self.data = (c_int * int(120))(*data) + + +class rm_modbus_tcp_read_params_t(Structure): + _fields_ = [ + ('address', c_int), # 数据起始地址 + ('master_name', c_char * int(20)), # Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + ('ip', c_char * int(16)), # 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + ('port', c_int), # 主机连接的端口号 + ('num', c_int), # 读取数据数量,最大不超过100 + ] + def __init__(self, address: int = None, master_name: str = '', ip: str = '', port: int = None, num: int = None): + if all(param is None for param in [address, num]): + return + else: + if(master_name == None): + master_name = "" + if(ip == None): + ip = "" + self.address = address + self.master_name = master_name.encode('utf-8') + self.ip = ip.encode('utf-8') + self.port = port + self.num = num + + +class rm_modbus_tcp_write_params_t(Structure): + _fields_ = [ + ('address', c_int), # 数据起始地址 + ('master_name', c_char * int(20)), # Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + ('ip', c_char * int(16)), # 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + ('port', c_int), # 主机连接的端口号 + ('num', c_int), # 写入数据数量,最大不超过100 + ('data', c_int * int(120)), # 写入的数据,数据长度不超过100 + ] + def __init__(self, address: int = None, master_name: str = '', ip: str = '', port: int = None, num: int = None, data: list[int] = None): + if all(param is None for param in [address, num, data]): + return + else: + if(master_name == None): + master_name = "" + if(ip == None): + ip = "" + self.address = address + self.master_name = master_name.encode('utf-8') + self.ip = ip.encode('utf-8') + self.port = port + self.num = num + self.data = (c_int * int(120))(*data) + + +class rm_tool_action_info_t(Structure): + _fields_ = [ + ('name', c_char * int(20)), #动作名称 + ('hand_pos', c_int * int(100)), #动作位置 + ('hand_angle', c_int * int(100)), #动作角度 + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + +class rm_tool_action_list_t(Structure): + _fields_ = [ + ('page_num', c_int), #页码 + ('page_size', c_int), #每页大小 + ('total_size', c_int), #列表长度 + ('vague_search', c_char * int(32)), #模糊搜索 + ('list_len', c_int), #返回符合的动作列表长度 + ('act_list', rm_tool_action_info_t * int(100)), #返回符合的动作列表 + ] + + def to_dict(self, recurse=True): + """将类的变量返回为字典,如果recurse为True,则递归处理ctypes结构字段""" + result = {} + for field, ctype in self._fields_: + value = getattr(self, field) + + if recurse and isinstance(ctype, type) and issubclass(ctype, Structure): + value = value.to_dict(recurse=recurse) + result[field] = value + + non_empty_outputs = [] + for i in range(self.total_size): + if self.act_list[i].name != b'': # 判断列表是否为空 + output = self.act_list[i].to_dict() + non_empty_outputs.append(output) + result["act_list"] = non_empty_outputs + + for key, value in result.items(): + if isinstance(value, bytes): + try: + # 尝试使用 UTF-8 解码 + result[key] = value.decode('utf-8') + except UnicodeDecodeError: + # 如果不是 UTF-8 编码,则可能需要根据实际情况处理 + # 这里简单地将字节转换为十六进制字符串作为替代方案 + result[key] = value.hex() + else: + # 值不是字节类型,直接保留 + result[key] = value + return result + + + +if _libs[libname].has("rm_api_version", "cdecl"): + rm_api_version = _libs[libname].get("rm_api_version", "cdecl") + rm_api_version.argtypes = [] + if sizeof(c_int) == sizeof(c_void_p): + rm_api_version.restype = ReturnString + else: + rm_api_version.restype = String + rm_api_version.errcheck = ReturnString + +if _libs[libname].has("rm_init", "cdecl"): + rm_init = _libs[libname].get("rm_init", "cdecl") + rm_init.argtypes = [c_int] + rm_init.restype = c_int + +if _libs[libname].has("rm_destroy", "cdecl"): + rm_destroy = _libs[libname].get("rm_destroy", "cdecl") + rm_destroy.argtypes = [] + rm_destroy.restype = c_int + +if _libs[libname].has("rm_set_log_call_back", "cdecl"): + rm_set_log_call_back = _libs[libname].get("rm_set_log_call_back", "cdecl") + # rm_set_log_call_back.argtypes = [CFUNCTYPE(UNCHECKED(None), String, c_void_p), c_int] + rm_set_log_call_back.restype = None + +if _libs[libname].has("rm_set_log_save", "cdecl"): + rm_set_log_save = _libs[libname].get("rm_set_log_save", "cdecl") + rm_set_log_save.argtypes = [String] + rm_set_log_save.restype = None + +if _libs[libname].has("rm_set_timeout", "cdecl"): + rm_set_timeout = _libs[libname].get("rm_set_timeout", "cdecl") + rm_set_timeout.argtypes = [c_int] + rm_set_timeout.restype = None + +if _libs[libname].has("rm_create_robot_arm", "cdecl"): + rm_create_robot_arm = _libs[libname].get("rm_create_robot_arm", "cdecl") + rm_create_robot_arm.argtypes = [String, c_int] + rm_create_robot_arm.restype = POINTER(rm_robot_handle) + +if _libs[libname].has("rm_delete_robot_arm", "cdecl"): + rm_delete_robot_arm = _libs[libname].get("rm_delete_robot_arm", "cdecl") + rm_delete_robot_arm.argtypes = [POINTER(rm_robot_handle)] + rm_delete_robot_arm.restype = c_int + +if _libs[libname].has("rm_set_arm_run_mode", "cdecl"): + rm_set_arm_run_mode = _libs[libname].get("rm_set_arm_run_mode", "cdecl") + rm_set_arm_run_mode.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_arm_run_mode.restype = c_int + +if _libs[libname].has("rm_get_arm_run_mode", "cdecl"): + rm_get_arm_run_mode = _libs[libname].get("rm_get_arm_run_mode", "cdecl") + rm_get_arm_run_mode.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_arm_run_mode.restype = c_int + +if _libs[libname].has("rm_get_robot_info", "cdecl"): + rm_get_robot_info = _libs[libname].get("rm_get_robot_info", "cdecl") + rm_get_robot_info.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_robot_info_t)] + rm_get_robot_info.restype = c_int + +if _libs[libname].has("rm_get_arm_event_call_back", "cdecl"): + rm_get_arm_event_call_back = _libs[libname].get( + "rm_get_arm_event_call_back", "cdecl") + rm_get_arm_event_call_back.argtypes = [rm_event_callback_ptr] + rm_get_arm_event_call_back.restype = None + +if _libs[libname].has("rm_realtime_arm_state_call_back", "cdecl"): + rm_realtime_arm_state_call_back = _libs[libname].get( + "rm_realtime_arm_state_call_back", "cdecl") + rm_realtime_arm_state_call_back.argtypes = [ + rm_realtime_arm_state_callback_ptr] + rm_realtime_arm_state_call_back.restype = None + +if _libs[libname].has("rm_set_joint_max_speed", "cdecl"): + rm_set_joint_max_speed = _libs[libname].get( + "rm_set_joint_max_speed", "cdecl") + rm_set_joint_max_speed.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_max_speed.restype = c_int + +if _libs[libname].has("rm_set_joint_max_acc", "cdecl"): + rm_set_joint_max_acc = _libs[libname].get("rm_set_joint_max_acc", "cdecl") + rm_set_joint_max_acc.argtypes = [POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_max_acc.restype = c_int + +if _libs[libname].has("rm_set_joint_min_pos", "cdecl"): + rm_set_joint_min_pos = _libs[libname].get("rm_set_joint_min_pos", "cdecl") + rm_set_joint_min_pos.argtypes = [POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_min_pos.restype = c_int + +if _libs[libname].has("rm_set_joint_max_pos", "cdecl"): + rm_set_joint_max_pos = _libs[libname].get("rm_set_joint_max_pos", "cdecl") + rm_set_joint_max_pos.argtypes = [POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_max_pos.restype = c_int + +if _libs[libname].has("rm_set_joint_drive_max_speed", "cdecl"): + rm_set_joint_drive_max_speed = _libs[libname].get( + "rm_set_joint_drive_max_speed", "cdecl") + rm_set_joint_drive_max_speed.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_drive_max_speed.restype = c_int + +if _libs[libname].has("rm_set_joint_drive_max_acc", "cdecl"): + rm_set_joint_drive_max_acc = _libs[libname].get( + "rm_set_joint_drive_max_acc", "cdecl") + rm_set_joint_drive_max_acc.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_drive_max_acc.restype = c_int + +if _libs[libname].has("rm_set_joint_drive_min_pos", "cdecl"): + rm_set_joint_drive_min_pos = _libs[libname].get( + "rm_set_joint_drive_min_pos", "cdecl") + rm_set_joint_drive_min_pos.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_drive_min_pos.restype = c_int + +if _libs[libname].has("rm_set_joint_drive_max_pos", "cdecl"): + rm_set_joint_drive_max_pos = _libs[libname].get( + "rm_set_joint_drive_max_pos", "cdecl") + rm_set_joint_drive_max_pos.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float] + rm_set_joint_drive_max_pos.restype = c_int + +if _libs[libname].has("rm_set_joint_en_state", "cdecl"): + rm_set_joint_en_state = _libs[libname].get( + "rm_set_joint_en_state", "cdecl") + rm_set_joint_en_state.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_joint_en_state.restype = c_int + +if _libs[libname].has("rm_set_joint_zero_pos", "cdecl"): + rm_set_joint_zero_pos = _libs[libname].get( + "rm_set_joint_zero_pos", "cdecl") + rm_set_joint_zero_pos.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_joint_zero_pos.restype = c_int + +if _libs[libname].has("rm_set_joint_clear_err", "cdecl"): + rm_set_joint_clear_err = _libs[libname].get( + "rm_set_joint_clear_err", "cdecl") + rm_set_joint_clear_err.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_joint_clear_err.restype = c_int + +if _libs[libname].has("rm_auto_set_joint_limit", "cdecl"): + rm_auto_set_joint_limit = _libs[libname].get( + "rm_auto_set_joint_limit", "cdecl") + rm_auto_set_joint_limit.argtypes = [POINTER(rm_robot_handle), c_int] + rm_auto_set_joint_limit.restype = c_int + +if _libs[libname].has("rm_get_joint_max_speed", "cdecl"): + rm_get_joint_max_speed = _libs[libname].get( + "rm_get_joint_max_speed", "cdecl") + rm_get_joint_max_speed.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_max_speed.restype = c_int + +if _libs[libname].has("rm_get_joint_max_acc", "cdecl"): + rm_get_joint_max_acc = _libs[libname].get("rm_get_joint_max_acc", "cdecl") + rm_get_joint_max_acc.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_max_acc.restype = c_int + +if _libs[libname].has("rm_get_joint_min_pos", "cdecl"): + rm_get_joint_min_pos = _libs[libname].get("rm_get_joint_min_pos", "cdecl") + rm_get_joint_min_pos.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_min_pos.restype = c_int + +if _libs[libname].has("rm_get_joint_max_pos", "cdecl"): + rm_get_joint_max_pos = _libs[libname].get("rm_get_joint_max_pos", "cdecl") + rm_get_joint_max_pos.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_max_pos.restype = c_int + +if _libs[libname].has("rm_get_joint_drive_max_speed", "cdecl"): + rm_get_joint_drive_max_speed = _libs[libname].get( + "rm_get_joint_drive_max_speed", "cdecl") + rm_get_joint_drive_max_speed.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_drive_max_speed.restype = c_int + +if _libs[libname].has("rm_get_joint_drive_max_acc", "cdecl"): + rm_get_joint_drive_max_acc = _libs[libname].get( + "rm_get_joint_drive_max_acc", "cdecl") + rm_get_joint_drive_max_acc.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_drive_max_acc.restype = c_int + +if _libs[libname].has("rm_get_joint_drive_min_pos", "cdecl"): + rm_get_joint_drive_min_pos = _libs[libname].get( + "rm_get_joint_drive_min_pos", "cdecl") + rm_get_joint_drive_min_pos.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_drive_min_pos.restype = c_int + +if _libs[libname].has("rm_get_joint_drive_max_pos", "cdecl"): + rm_get_joint_drive_max_pos = _libs[libname].get( + "rm_get_joint_drive_max_pos", "cdecl") + rm_get_joint_drive_max_pos.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_drive_max_pos.restype = c_int + +if _libs[libname].has("rm_get_joint_en_state", "cdecl"): + rm_get_joint_en_state = _libs[libname].get( + "rm_get_joint_en_state", "cdecl") + rm_get_joint_en_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(uint8_t)] + rm_get_joint_en_state.restype = c_int + +if _libs[libname].has("rm_get_joint_err_flag", "cdecl"): + rm_get_joint_err_flag = _libs[libname].get( + "rm_get_joint_err_flag", "cdecl") + rm_get_joint_err_flag.argtypes = [ + POINTER(rm_robot_handle), POINTER(uint16_t), POINTER(uint16_t)] + rm_get_joint_err_flag.restype = c_int + +if _libs[libname].has("rm_set_arm_max_line_speed", "cdecl"): + rm_set_arm_max_line_speed = _libs[libname].get( + "rm_set_arm_max_line_speed", "cdecl") + rm_set_arm_max_line_speed.argtypes = [POINTER(rm_robot_handle), c_float] + rm_set_arm_max_line_speed.restype = c_int + +if _libs[libname].has("rm_set_arm_max_line_acc", "cdecl"): + rm_set_arm_max_line_acc = _libs[libname].get( + "rm_set_arm_max_line_acc", "cdecl") + rm_set_arm_max_line_acc.argtypes = [POINTER(rm_robot_handle), c_float] + rm_set_arm_max_line_acc.restype = c_int + +if _libs[libname].has("rm_set_arm_max_angular_speed", "cdecl"): + rm_set_arm_max_angular_speed = _libs[libname].get( + "rm_set_arm_max_angular_speed", "cdecl") + rm_set_arm_max_angular_speed.argtypes = [POINTER(rm_robot_handle), c_float] + rm_set_arm_max_angular_speed.restype = c_int + +if _libs[libname].has("rm_set_arm_max_angular_acc", "cdecl"): + rm_set_arm_max_angular_acc = _libs[libname].get( + "rm_set_arm_max_angular_acc", "cdecl") + rm_set_arm_max_angular_acc.argtypes = [POINTER(rm_robot_handle), c_float] + rm_set_arm_max_angular_acc.restype = c_int + +if _libs[libname].has("rm_set_arm_tcp_init", "cdecl"): + rm_set_arm_tcp_init = _libs[libname].get("rm_set_arm_tcp_init", "cdecl") + rm_set_arm_tcp_init.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_tcp_init.restype = c_int + +if _libs[libname].has("rm_set_collision_state", "cdecl"): + rm_set_collision_state = _libs[libname].get( + "rm_set_collision_state", "cdecl") + rm_set_collision_state.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_collision_state.restype = c_int + +if _libs[libname].has("rm_get_collision_stage", "cdecl"): + rm_get_collision_stage = _libs[libname].get( + "rm_get_collision_stage", "cdecl") + rm_get_collision_stage.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_collision_stage.restype = c_int + +if _libs[libname].has("rm_get_arm_max_line_speed", "cdecl"): + rm_get_arm_max_line_speed = _libs[libname].get( + "rm_get_arm_max_line_speed", "cdecl") + rm_get_arm_max_line_speed.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_arm_max_line_speed.restype = c_int + +if _libs[libname].has("rm_get_arm_max_line_acc", "cdecl"): + rm_get_arm_max_line_acc = _libs[libname].get( + "rm_get_arm_max_line_acc", "cdecl") + rm_get_arm_max_line_acc.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_arm_max_line_acc.restype = c_int + +if _libs[libname].has("rm_get_arm_max_angular_speed", "cdecl"): + rm_get_arm_max_angular_speed = _libs[libname].get( + "rm_get_arm_max_angular_speed", "cdecl") + rm_get_arm_max_angular_speed.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_arm_max_angular_speed.restype = c_int + +if _libs[libname].has("rm_get_arm_max_angular_acc", "cdecl"): + rm_get_arm_max_angular_acc = _libs[libname].get( + "rm_get_arm_max_angular_acc", "cdecl") + rm_get_arm_max_angular_acc.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_arm_max_angular_acc.restype = c_int + +if _libs[libname].has("rm_set_DH_data", "cdecl"): + rm_set_DH_data = _libs[libname].get("rm_set_DH_data", "cdecl") + rm_set_DH_data.argtypes = [POINTER(rm_robot_handle), rm_dh_t] + rm_set_DH_data.restype = c_int + +if _libs[libname].has("rm_get_DH_data", "cdecl"): + rm_get_DH_data = _libs[libname].get("rm_get_DH_data", "cdecl") + rm_get_DH_data.argtypes = [POINTER(rm_robot_handle), POINTER(rm_dh_t)] + rm_get_DH_data.restype = c_int + +if _libs[libname].has("rm_set_DH_data_default", "cdecl"): + rm_set_DH_data_default = _libs[libname].get("rm_set_DH_data_default", "cdecl") + rm_set_DH_data_default.argtypes = [POINTER(rm_robot_handle)] + rm_set_DH_data_default.restype = c_int + +if _libs[libname].has("rm_set_auto_tool_frame", "cdecl"): + rm_set_auto_tool_frame = _libs[libname].get( + "rm_set_auto_tool_frame", "cdecl") + rm_set_auto_tool_frame.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_auto_tool_frame.restype = c_int + +if _libs[libname].has("rm_generate_auto_tool_frame", "cdecl"): + rm_generate_auto_tool_frame = _libs[libname].get( + "rm_generate_auto_tool_frame", "cdecl") + rm_generate_auto_tool_frame.argtypes = [ + POINTER(rm_robot_handle), String, c_float, c_float, c_float, c_float] + rm_generate_auto_tool_frame.restype = c_int + +if _libs[libname].has("rm_set_manual_tool_frame", "cdecl"): + rm_set_manual_tool_frame = _libs[libname].get( + "rm_set_manual_tool_frame", "cdecl") + rm_set_manual_tool_frame.argtypes = [POINTER(rm_robot_handle), rm_frame_t] + rm_set_manual_tool_frame.restype = c_int + +if _libs[libname].has("rm_change_tool_frame", "cdecl"): + rm_change_tool_frame = _libs[libname].get("rm_change_tool_frame", "cdecl") + rm_change_tool_frame.argtypes = [POINTER(rm_robot_handle), String] + rm_change_tool_frame.restype = c_int + +if _libs[libname].has("rm_delete_tool_frame", "cdecl"): + rm_delete_tool_frame = _libs[libname].get("rm_delete_tool_frame", "cdecl") + rm_delete_tool_frame.argtypes = [POINTER(rm_robot_handle), String] + rm_delete_tool_frame.restype = c_int + +if _libs[libname].has("rm_update_tool_frame", "cdecl"): + rm_update_tool_frame = _libs[libname].get("rm_update_tool_frame", "cdecl") + rm_update_tool_frame.argtypes = [POINTER(rm_robot_handle), rm_frame_t] + rm_update_tool_frame.restype = c_int + +if _libs[libname].has("rm_set_tool_envelope", "cdecl"): + rm_set_tool_envelope = _libs[libname].get("rm_set_tool_envelope", "cdecl") + rm_set_tool_envelope.argtypes = [ + POINTER(rm_robot_handle), rm_envelope_balls_list_t] + rm_set_tool_envelope.restype = c_int + +if _libs[libname].has("rm_get_tool_envelope", "cdecl"): + rm_get_tool_envelope = _libs[libname].get("rm_get_tool_envelope", "cdecl") + rm_get_tool_envelope.argtypes = [ + POINTER(rm_robot_handle), String, POINTER(rm_envelope_balls_list_t)] + rm_get_tool_envelope.restype = c_int + +if _libs[libname].has("rm_set_auto_work_frame", "cdecl"): + rm_set_auto_work_frame = _libs[libname].get( + "rm_set_auto_work_frame", "cdecl") + rm_set_auto_work_frame.argtypes = [POINTER(rm_robot_handle), String, c_int] + rm_set_auto_work_frame.restype = c_int + +if _libs[libname].has("rm_set_manual_work_frame", "cdecl"): + rm_set_manual_work_frame = _libs[libname].get( + "rm_set_manual_work_frame", "cdecl") + rm_set_manual_work_frame.argtypes = [ + POINTER(rm_robot_handle), String, rm_pose_t] + rm_set_manual_work_frame.restype = c_int + +if _libs[libname].has("rm_change_work_frame", "cdecl"): + rm_change_work_frame = _libs[libname].get("rm_change_work_frame", "cdecl") + rm_change_work_frame.argtypes = [POINTER(rm_robot_handle), String] + rm_change_work_frame.restype = c_int + +if _libs[libname].has("rm_delete_work_frame", "cdecl"): + rm_delete_work_frame = _libs[libname].get("rm_delete_work_frame", "cdecl") + rm_delete_work_frame.argtypes = [POINTER(rm_robot_handle), String] + rm_delete_work_frame.restype = c_int + +if _libs[libname].has("rm_update_work_frame", "cdecl"): + rm_update_work_frame = _libs[libname].get("rm_update_work_frame", "cdecl") + rm_update_work_frame.argtypes = [ + POINTER(rm_robot_handle), String, rm_pose_t] + rm_update_work_frame.restype = c_int + +if _libs[libname].has("rm_get_total_tool_frame", "cdecl"): + rm_get_total_tool_frame = _libs[libname].get( + "rm_get_total_tool_frame", "cdecl") + rm_get_total_tool_frame.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_frame_name_t), POINTER(c_int)] + rm_get_total_tool_frame.restype = c_int + +if _libs[libname].has("rm_get_given_tool_frame", "cdecl"): + rm_get_given_tool_frame = _libs[libname].get( + "rm_get_given_tool_frame", "cdecl") + rm_get_given_tool_frame.argtypes = [ + POINTER(rm_robot_handle), String, POINTER(rm_frame_t)] + rm_get_given_tool_frame.restype = c_int + +if _libs[libname].has("rm_get_current_tool_frame", "cdecl"): + rm_get_current_tool_frame = _libs[libname].get( + "rm_get_current_tool_frame", "cdecl") + rm_get_current_tool_frame.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_frame_t)] + rm_get_current_tool_frame.restype = c_int + +if _libs[libname].has("rm_get_total_work_frame", "cdecl"): + rm_get_total_work_frame = _libs[libname].get( + "rm_get_total_work_frame", "cdecl") + rm_get_total_work_frame.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_frame_name_t), POINTER(c_int)] + rm_get_total_work_frame.restype = c_int + +if _libs[libname].has("rm_get_given_work_frame", "cdecl"): + rm_get_given_work_frame = _libs[libname].get( + "rm_get_given_work_frame", "cdecl") + rm_get_given_work_frame.argtypes = [ + POINTER(rm_robot_handle), String, POINTER(rm_pose_t)] + rm_get_given_work_frame.restype = c_int + +if _libs[libname].has("rm_get_current_work_frame", "cdecl"): + rm_get_current_work_frame = _libs[libname].get( + "rm_get_current_work_frame", "cdecl") + rm_get_current_work_frame.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_frame_t)] + rm_get_current_work_frame.restype = c_int + +if _libs[libname].has("rm_get_current_arm_state", "cdecl"): + rm_get_current_arm_state = _libs[libname].get( + "rm_get_current_arm_state", "cdecl") + rm_get_current_arm_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_current_arm_state_t)] + rm_get_current_arm_state.restype = c_int + +if _libs[libname].has("rm_get_current_joint_temperature", "cdecl"): + rm_get_current_joint_temperature = _libs[libname].get( + "rm_get_current_joint_temperature", "cdecl") + rm_get_current_joint_temperature.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_current_joint_temperature.restype = c_int + +if _libs[libname].has("rm_get_current_joint_current", "cdecl"): + rm_get_current_joint_current = _libs[libname].get( + "rm_get_current_joint_current", "cdecl") + rm_get_current_joint_current.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_current_joint_current.restype = c_int + +if _libs[libname].has("rm_get_current_joint_voltage", "cdecl"): + rm_get_current_joint_voltage = _libs[libname].get( + "rm_get_current_joint_voltage", "cdecl") + rm_get_current_joint_voltage.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_current_joint_voltage.restype = c_int + +if _libs[libname].has("rm_set_init_pose", "cdecl"): + rm_set_init_pose = _libs[libname].get("rm_set_init_pose", "cdecl") + rm_set_init_pose.argtypes = [POINTER(rm_robot_handle), POINTER(c_float)] + rm_set_init_pose.restype = c_int + +if _libs[libname].has("rm_get_init_pose", "cdecl"): + rm_get_init_pose = _libs[libname].get("rm_get_init_pose", "cdecl") + rm_get_init_pose.argtypes = [POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_init_pose.restype = c_int + +if _libs[libname].has("rm_movej", "cdecl"): + rm_movej = _libs[libname].get("rm_movej", "cdecl") + rm_movej.argtypes = [POINTER(rm_robot_handle), POINTER( + c_float), c_int, c_int, c_int, c_int] + rm_movej.restype = c_int + +if _libs[libname].has("rm_movel", "cdecl"): + rm_movel = _libs[libname].get("rm_movel", "cdecl") + rm_movel.argtypes = [ + POINTER(rm_robot_handle), rm_pose_t, c_int, c_int, c_int, c_int] + rm_movel.restype = c_int + +if _libs[libname].has("rm_movel_offset", "cdecl"): + rm_movel_offset = _libs[libname].get("rm_movel_offset", "cdecl") + rm_movel_offset.argtypes = [ + POINTER(rm_robot_handle), rm_pose_t, c_int, c_int, c_int, c_int, c_int] + rm_movel_offset.restype = c_int + +if _libs[libname].has("rm_moves", "cdecl"): + rm_moves = _libs[libname].get("rm_moves", "cdecl") + rm_moves.argtypes = [ + POINTER(rm_robot_handle), rm_pose_t, c_int, c_int, c_int, c_int] + rm_moves.restype = c_int + +if _libs[libname].has("rm_movec", "cdecl"): + rm_movec = _libs[libname].get("rm_movec", "cdecl") + rm_movec.argtypes = [POINTER( + rm_robot_handle), rm_pose_t, rm_pose_t, c_int, c_int, c_int, c_int, c_int] + rm_movec.restype = c_int + +if _libs[libname].has("rm_movej_p", "cdecl"): + rm_movej_p = _libs[libname].get("rm_movej_p", "cdecl") + rm_movej_p.argtypes = [ + POINTER(rm_robot_handle), rm_pose_t, c_int, c_int, c_int, c_int] + rm_movej_p.restype = c_int + +if _libs[libname].has("rm_movej_canfd", "cdecl"): + rm_movej_canfd = _libs[libname].get("rm_movej_canfd", "cdecl") + rm_movej_canfd.argtypes = [ + POINTER(rm_robot_handle), rm_movej_canfd_mode_t] + rm_movej_canfd.restype = c_int + +if _libs[libname].has("rm_movep_canfd", "cdecl"): + rm_movep_canfd = _libs[libname].get("rm_movep_canfd", "cdecl") + rm_movep_canfd.argtypes = [POINTER(rm_robot_handle), rm_movep_canfd_mode_t] + rm_movep_canfd.restype = c_int + +if _libs[libname].has("rm_movej_follow", "cdecl"): + rm_movej_follow = _libs[libname].get("rm_movej_follow", "cdecl") + rm_movej_follow.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_movej_follow.restype = c_int + +if _libs[libname].has("rm_movep_follow", "cdecl"): + rm_movep_follow = _libs[libname].get("rm_movep_follow", "cdecl") + rm_movep_follow.argtypes = [POINTER(rm_robot_handle), rm_pose_t] + rm_movep_follow.restype = c_int + +if _libs[libname].has("rm_set_arm_slow_stop", "cdecl"): + rm_set_arm_slow_stop = _libs[libname].get("rm_set_arm_slow_stop", "cdecl") + rm_set_arm_slow_stop.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_slow_stop.restype = c_int + +if _libs[libname].has("rm_set_arm_stop", "cdecl"): + rm_set_arm_stop = _libs[libname].get("rm_set_arm_stop", "cdecl") + rm_set_arm_stop.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_stop.restype = c_int + +if _libs[libname].has("rm_set_arm_pause", "cdecl"): + rm_set_arm_pause = _libs[libname].get("rm_set_arm_pause", "cdecl") + rm_set_arm_pause.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_pause.restype = c_int + +if _libs[libname].has("rm_set_arm_continue", "cdecl"): + rm_set_arm_continue = _libs[libname].get("rm_set_arm_continue", "cdecl") + rm_set_arm_continue.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_continue.restype = c_int + +if _libs[libname].has("rm_set_delete_current_trajectory", "cdecl"): + rm_set_delete_current_trajectory = _libs[libname].get( + "rm_set_delete_current_trajectory", "cdecl") + rm_set_delete_current_trajectory.argtypes = [POINTER(rm_robot_handle)] + rm_set_delete_current_trajectory.restype = c_int + +if _libs[libname].has("rm_set_arm_delete_trajectory", "cdecl"): + rm_set_arm_delete_trajectory = _libs[libname].get( + "rm_set_arm_delete_trajectory", "cdecl") + rm_set_arm_delete_trajectory.argtypes = [POINTER(rm_robot_handle)] + rm_set_arm_delete_trajectory.restype = c_int + +if _libs[libname].has("rm_get_arm_current_trajectory", "cdecl"): + rm_get_arm_current_trajectory = _libs[libname].get( + "rm_get_arm_current_trajectory", "cdecl") + rm_get_arm_current_trajectory.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), + POINTER(c_float)] + rm_get_arm_current_trajectory.restype = c_int + +if _libs[libname].has("rm_set_joint_step", "cdecl"): + rm_set_joint_step = _libs[libname].get("rm_set_joint_step", "cdecl") + rm_set_joint_step.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float, c_int, c_int] + rm_set_joint_step.restype = c_int + +if _libs[libname].has("rm_set_pos_step", "cdecl"): + rm_set_pos_step = _libs[libname].get("rm_set_pos_step", "cdecl") + rm_set_pos_step.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float, c_int, c_int] + rm_set_pos_step.restype = c_int + +if _libs[libname].has("rm_set_ort_step", "cdecl"): + rm_set_ort_step = _libs[libname].get("rm_set_ort_step", "cdecl") + rm_set_ort_step.argtypes = [ + POINTER(rm_robot_handle), c_int, c_float, c_int, c_int] + rm_set_ort_step.restype = c_int + +if _libs[libname].has("rm_set_joint_teach", "cdecl"): + rm_set_joint_teach = _libs[libname].get("rm_set_joint_teach", "cdecl") + rm_set_joint_teach.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_joint_teach.restype = c_int + +if _libs[libname].has("rm_set_pos_teach", "cdecl"): + rm_set_pos_teach = _libs[libname].get("rm_set_pos_teach", "cdecl") + rm_set_pos_teach.argtypes = [POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_pos_teach.restype = c_int + +if _libs[libname].has("rm_set_ort_teach", "cdecl"): + rm_set_ort_teach = _libs[libname].get("rm_set_ort_teach", "cdecl") + rm_set_ort_teach.argtypes = [POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_ort_teach.restype = c_int + +if _libs[libname].has("rm_set_stop_teach", "cdecl"): + rm_set_stop_teach = _libs[libname].get("rm_set_stop_teach", "cdecl") + rm_set_stop_teach.argtypes = [POINTER(rm_robot_handle)] + rm_set_stop_teach.restype = c_int + +if _libs[libname].has("rm_set_teach_frame", "cdecl"): + rm_set_teach_frame = _libs[libname].get("rm_set_teach_frame", "cdecl") + rm_set_teach_frame.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_teach_frame.restype = c_int + +if _libs[libname].has("rm_get_teach_frame", "cdecl"): + rm_get_teach_frame = _libs[libname].get("rm_get_teach_frame", "cdecl") + rm_get_teach_frame.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_teach_frame.restype = c_int + +if _libs[libname].has("rm_get_controller_state", "cdecl"): + rm_get_controller_state = _libs[libname].get( + "rm_get_controller_state", "cdecl") + rm_get_controller_state.argtypes = [POINTER(rm_robot_handle), POINTER(c_float), POINTER(c_float), POINTER(c_float), + POINTER(c_int)] + rm_get_controller_state.restype = c_int + +if _libs[libname].has("rm_set_arm_power", "cdecl"): + rm_set_arm_power = _libs[libname].get("rm_set_arm_power", "cdecl") + rm_set_arm_power.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_arm_power.restype = c_int + +if _libs[libname].has("rm_get_arm_power_state", "cdecl"): + rm_get_arm_power_state = _libs[libname].get( + "rm_get_arm_power_state", "cdecl") + rm_get_arm_power_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_arm_power_state.restype = c_int + +if _libs[libname].has("rm_get_system_runtime", "cdecl"): + rm_get_system_runtime = _libs[libname].get( + "rm_get_system_runtime", "cdecl") + rm_get_system_runtime.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int), POINTER(c_int), + POINTER(c_int)] + rm_get_system_runtime.restype = c_int + +if _libs[libname].has("rm_clear_system_runtime", "cdecl"): + rm_clear_system_runtime = _libs[libname].get( + "rm_clear_system_runtime", "cdecl") + rm_clear_system_runtime.argtypes = [POINTER(rm_robot_handle)] + rm_clear_system_runtime.restype = c_int + +if _libs[libname].has("rm_get_joint_odom", "cdecl"): + rm_get_joint_odom = _libs[libname].get("rm_get_joint_odom", "cdecl") + rm_get_joint_odom.argtypes = [POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_odom.restype = c_int + +if _libs[libname].has("rm_clear_joint_odom", "cdecl"): + rm_clear_joint_odom = _libs[libname].get("rm_clear_joint_odom", "cdecl") + rm_clear_joint_odom.argtypes = [POINTER(rm_robot_handle)] + rm_clear_joint_odom.restype = c_int + +if _libs[libname].has("rm_set_NetIP", "cdecl"): + rm_set_NetIP = _libs[libname].get("rm_set_NetIP", "cdecl") + rm_set_NetIP.argtypes = [POINTER(rm_robot_handle), String, String, String] + rm_set_NetIP.restype = c_int + +if _libs[libname].has("rm_clear_system_err", "cdecl"): + rm_clear_system_err = _libs[libname].get("rm_clear_system_err", "cdecl") + rm_clear_system_err.argtypes = [POINTER(rm_robot_handle)] + rm_clear_system_err.restype = c_int + +if _libs[libname].has("rm_get_arm_software_info", "cdecl"): + rm_get_arm_software_info = _libs[libname].get( + "rm_get_arm_software_info", "cdecl") + rm_get_arm_software_info.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_arm_software_version_t)] + rm_get_arm_software_info.restype = c_int + +if _libs[libname].has("rm_set_wifi_ap", "cdecl"): + rm_set_wifi_ap = _libs[libname].get("rm_set_wifi_ap", "cdecl") + rm_set_wifi_ap.argtypes = [POINTER(rm_robot_handle), String, String] + rm_set_wifi_ap.restype = c_int + +if _libs[libname].has("rm_set_wifi_sta", "cdecl"): + rm_set_wifi_sta = _libs[libname].get("rm_set_wifi_sta", "cdecl") + rm_set_wifi_sta.argtypes = [POINTER(rm_robot_handle), String, String] + rm_set_wifi_sta.restype = c_int + +if _libs[libname].has("rm_set_RS485", "cdecl"): + rm_set_RS485 = _libs[libname].get("rm_set_RS485", "cdecl") + rm_set_RS485.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_RS485.restype = c_int + +if _libs[libname].has("rm_get_wired_net", "cdecl"): + rm_get_wired_net = _libs[libname].get("rm_get_wired_net", "cdecl") + rm_get_wired_net.argtypes = [ + POINTER(rm_robot_handle), String, String, String] + rm_get_wired_net.restype = c_int + +if _libs[libname].has("rm_get_wifi_net", "cdecl"): + rm_get_wifi_net = _libs[libname].get("rm_get_wifi_net", "cdecl") + rm_get_wifi_net.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_wifi_net_t)] + rm_get_wifi_net.restype = c_int + +if _libs[libname].has("rm_set_net_default", "cdecl"): + rm_set_net_default = _libs[libname].get("rm_set_net_default", "cdecl") + rm_set_net_default.argtypes = [POINTER(rm_robot_handle)] + rm_set_net_default.restype = c_int + +if _libs[libname].has("rm_set_wifi_close", "cdecl"): + rm_set_wifi_close = _libs[libname].get("rm_set_wifi_close", "cdecl") + rm_set_wifi_close.argtypes = [POINTER(rm_robot_handle)] + rm_set_wifi_close.restype = c_int + +if _libs[libname].has("rm_get_joint_degree", "cdecl"): + rm_get_joint_degree = _libs[libname].get("rm_get_joint_degree", "cdecl") + rm_get_joint_degree.argtypes = [POINTER(rm_robot_handle), POINTER(c_float)] + rm_get_joint_degree.restype = c_int + +if _libs[libname].has("rm_get_arm_all_state", "cdecl"): + rm_get_arm_all_state = _libs[libname].get("rm_get_arm_all_state", "cdecl") + rm_get_arm_all_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_arm_all_state_t)] + rm_get_arm_all_state.restype = c_int + +if _libs[libname].has("rm_get_controller_RS485_mode", "cdecl"): + rm_get_controller_RS485_mode = _libs[libname].get( + "rm_get_controller_RS485_mode", "cdecl") + rm_get_controller_RS485_mode.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int), POINTER(c_int)] + rm_get_controller_RS485_mode.restype = c_int + +if _libs[libname].has("rm_get_tool_RS485_mode", "cdecl"): + rm_get_tool_RS485_mode = _libs[libname].get( + "rm_get_tool_RS485_mode", "cdecl") + rm_get_tool_RS485_mode.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int), POINTER(c_int)] + rm_get_tool_RS485_mode.restype = c_int + +if _libs[libname].has("rm_set_IO_mode", "cdecl"): + rm_set_IO_mode = _libs[libname].get("rm_set_IO_mode", "cdecl") + rm_set_IO_mode.argtypes = [POINTER(rm_robot_handle), c_int, rm_io_config_t] + rm_set_IO_mode.restype = c_int + +if _libs[libname].has("rm_set_DO_state", "cdecl"): + rm_set_DO_state = _libs[libname].get("rm_set_DO_state", "cdecl") + rm_set_DO_state.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_DO_state.restype = c_int + +if _libs[libname].has("rm_get_IO_state", "cdecl"): + rm_get_IO_state = _libs[libname].get("rm_get_IO_state", "cdecl") + rm_get_IO_state.argtypes = [ + POINTER(rm_robot_handle), c_int, POINTER(rm_io_get_t)] + rm_get_IO_state.restype = c_int + +if _libs[libname].has("rm_get_IO_input", "cdecl"): + rm_get_IO_input = _libs[libname].get("rm_get_IO_input", "cdecl") + rm_get_IO_input.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_IO_input.restype = c_int + +if _libs[libname].has("rm_get_IO_output", "cdecl"): + rm_get_IO_output = _libs[libname].get("rm_get_IO_output", "cdecl") + rm_get_IO_output.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_IO_output.restype = c_int + +if _libs[libname].has("rm_set_voltage", "cdecl"): + rm_set_voltage = _libs[libname].get("rm_set_voltage", "cdecl") + rm_set_voltage.argtypes = [POINTER(rm_robot_handle), c_int, c_bool] + rm_set_voltage.restype = c_int + +if _libs[libname].has("rm_get_voltage", "cdecl"): + rm_get_voltage = _libs[libname].get("rm_get_voltage", "cdecl") + rm_get_voltage.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_voltage.restype = c_int + +if _libs[libname].has("rm_set_tool_DO_state", "cdecl"): + rm_set_tool_DO_state = _libs[libname].get("rm_set_tool_DO_state", "cdecl") + rm_set_tool_DO_state.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_tool_DO_state.restype = c_int + +if _libs[libname].has("rm_set_tool_IO_mode", "cdecl"): + rm_set_tool_IO_mode = _libs[libname].get("rm_set_tool_IO_mode", "cdecl") + rm_set_tool_IO_mode.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_tool_IO_mode.restype = c_int + +if _libs[libname].has("rm_get_tool_IO_state", "cdecl"): + rm_get_tool_IO_state = _libs[libname].get("rm_get_tool_IO_state", "cdecl") + rm_get_tool_IO_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int)] + rm_get_tool_IO_state.restype = c_int + +if _libs[libname].has("rm_set_tool_voltage", "cdecl"): + rm_set_tool_voltage = _libs[libname].get("rm_set_tool_voltage", "cdecl") + rm_set_tool_voltage.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_tool_voltage.restype = c_int + +if _libs[libname].has("rm_get_tool_voltage", "cdecl"): + rm_get_tool_voltage = _libs[libname].get("rm_get_tool_voltage", "cdecl") + rm_get_tool_voltage.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_tool_voltage.restype = c_int + +if _libs[libname].has("rm_set_gripper_route", "cdecl"): + rm_set_gripper_route = _libs[libname].get("rm_set_gripper_route", "cdecl") + rm_set_gripper_route.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_gripper_route.restype = c_int + +if _libs[libname].has("rm_set_gripper_release", "cdecl"): + rm_set_gripper_release = _libs[libname].get( + "rm_set_gripper_release", "cdecl") + rm_set_gripper_release.argtypes = [ + POINTER(rm_robot_handle), c_int, c_bool, c_int] + rm_set_gripper_release.restype = c_int + +if _libs[libname].has("rm_set_gripper_pick", "cdecl"): + rm_set_gripper_pick = _libs[libname].get("rm_set_gripper_pick", "cdecl") + rm_set_gripper_pick.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_bool, c_int] + rm_set_gripper_pick.restype = c_int + +if _libs[libname].has("rm_set_gripper_pick_on", "cdecl"): + rm_set_gripper_pick_on = _libs[libname].get( + "rm_set_gripper_pick_on", "cdecl") + rm_set_gripper_pick_on.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_bool, c_int] + rm_set_gripper_pick_on.restype = c_int + +if _libs[libname].has("rm_set_gripper_position", "cdecl"): + rm_set_gripper_position = _libs[libname].get( + "rm_set_gripper_position", "cdecl") + rm_set_gripper_position.argtypes = [ + POINTER(rm_robot_handle), c_int, c_bool, c_int] + rm_set_gripper_position.restype = c_int + +if _libs[libname].has("rm_get_gripper_state", "cdecl"): + rm_get_gripper_state = _libs[libname].get("rm_get_gripper_state", "cdecl") + rm_get_gripper_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_gripper_state_t)] + rm_get_gripper_state.restype = c_int + +if _libs[libname].has("rm_get_force_data", "cdecl"): + rm_get_force_data = _libs[libname].get("rm_get_force_data", "cdecl") + rm_get_force_data.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_force_data_t)] + rm_get_force_data.restype = c_int + +if _libs[libname].has("rm_clear_force_data", "cdecl"): + rm_clear_force_data = _libs[libname].get("rm_clear_force_data", "cdecl") + rm_clear_force_data.argtypes = [POINTER(rm_robot_handle)] + rm_clear_force_data.restype = c_int + +if _libs[libname].has("rm_set_force_sensor", "cdecl"): + rm_set_force_sensor = _libs[libname].get("rm_set_force_sensor", "cdecl") + rm_set_force_sensor.argtypes = [POINTER(rm_robot_handle), c_bool] + rm_set_force_sensor.restype = c_int + +if _libs[libname].has("rm_manual_set_force", "cdecl"): + rm_manual_set_force = _libs[libname].get("rm_manual_set_force", "cdecl") + rm_manual_set_force.argtypes = [ + POINTER(rm_robot_handle), c_int, POINTER(c_float), c_bool] + rm_manual_set_force.restype = c_int + +if _libs[libname].has("rm_stop_set_force_sensor", "cdecl"): + rm_stop_set_force_sensor = _libs[libname].get( + "rm_stop_set_force_sensor", "cdecl") + rm_stop_set_force_sensor.argtypes = [POINTER(rm_robot_handle)] + rm_stop_set_force_sensor.restype = c_int + +if _libs[libname].has("rm_get_Fz", "cdecl"): + rm_get_Fz = _libs[libname].get("rm_get_Fz", "cdecl") + rm_get_Fz.argtypes = [POINTER(rm_robot_handle), POINTER(rm_fz_data_t)] + rm_get_Fz.restype = c_int + +if _libs[libname].has("rm_clear_Fz", "cdecl"): + rm_clear_Fz = _libs[libname].get("rm_clear_Fz", "cdecl") + rm_clear_Fz.argtypes = [POINTER(rm_robot_handle)] + rm_clear_Fz.restype = c_int + +if _libs[libname].has("rm_auto_set_Fz", "cdecl"): + rm_auto_set_Fz = _libs[libname].get("rm_auto_set_Fz", "cdecl") + rm_auto_set_Fz.argtypes = [POINTER(rm_robot_handle), c_bool] + rm_auto_set_Fz.restype = c_int + +if _libs[libname].has("rm_manual_set_Fz", "cdecl"): + rm_manual_set_Fz = _libs[libname].get("rm_manual_set_Fz", "cdecl") + rm_manual_set_Fz.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float), POINTER(c_float), c_bool] + rm_manual_set_Fz.restype = c_int + +if _libs[libname].has("rm_start_drag_teach", "cdecl"): + rm_start_drag_teach = _libs[libname].get("rm_start_drag_teach", "cdecl") + rm_start_drag_teach.argtypes = [POINTER(rm_robot_handle), c_int] + rm_start_drag_teach.restype = c_int + +if _libs[libname].has("rm_stop_drag_teach", "cdecl"): + rm_stop_drag_teach = _libs[libname].get("rm_stop_drag_teach", "cdecl") + rm_stop_drag_teach.argtypes = [POINTER(rm_robot_handle)] + rm_stop_drag_teach.restype = c_int + +if _libs[libname].has("rm_start_multi_drag_teach", "cdecl"): + rm_start_multi_drag_teach = _libs[libname].get( + "rm_start_multi_drag_teach", "cdecl") + rm_start_multi_drag_teach.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int] + rm_start_multi_drag_teach.restype = c_int + +if _libs[libname].has("rm_start_multi_drag_teach_new", "cdecl"): + rm_start_multi_drag_teach_new = _libs[libname].get("rm_start_multi_drag_teach_new", "cdecl") + rm_start_multi_drag_teach_new.argtypes = [POINTER(rm_robot_handle), rm_multi_drag_teach_t] + rm_start_multi_drag_teach_new.restype = c_int + +if _libs[libname].has("rm_set_drag_teach_sensitivity", "cdecl"): + rm_set_drag_teach_sensitivity = _libs[libname].get("rm_set_drag_teach_sensitivity", "cdecl") + rm_set_drag_teach_sensitivity.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_drag_teach_sensitivity.restype = c_int + +if _libs[libname].has("rm_get_drag_teach_sensitivity", "cdecl"): + rm_get_drag_teach_sensitivity = _libs[libname].get("rm_get_drag_teach_sensitivity", "cdecl") + rm_get_drag_teach_sensitivity.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_drag_teach_sensitivity.restype = c_int + +if _libs[libname].has("rm_drag_trajectory_origin", "cdecl"): + rm_drag_trajectory_origin = _libs[libname].get( + "rm_drag_trajectory_origin", "cdecl") + rm_drag_trajectory_origin.argtypes = [POINTER(rm_robot_handle), c_int] + rm_drag_trajectory_origin.restype = c_int + +if _libs[libname].has("rm_run_drag_trajectory", "cdecl"): + rm_run_drag_trajectory = _libs[libname].get( + "rm_run_drag_trajectory", "cdecl") + rm_run_drag_trajectory.argtypes = [POINTER(rm_robot_handle), c_int] + rm_run_drag_trajectory.restype = c_int + +if _libs[libname].has("rm_pause_drag_trajectory", "cdecl"): + rm_pause_drag_trajectory = _libs[libname].get( + "rm_pause_drag_trajectory", "cdecl") + rm_pause_drag_trajectory.argtypes = [POINTER(rm_robot_handle)] + rm_pause_drag_trajectory.restype = c_int + +if _libs[libname].has("rm_continue_drag_trajectory", "cdecl"): + rm_continue_drag_trajectory = _libs[libname].get( + "rm_continue_drag_trajectory", "cdecl") + rm_continue_drag_trajectory.argtypes = [POINTER(rm_robot_handle)] + rm_continue_drag_trajectory.restype = c_int + +if _libs[libname].has("rm_stop_drag_trajectory", "cdecl"): + rm_stop_drag_trajectory = _libs[libname].get( + "rm_stop_drag_trajectory", "cdecl") + rm_stop_drag_trajectory.argtypes = [POINTER(rm_robot_handle)] + rm_stop_drag_trajectory.restype = c_int + +if _libs[libname].has("rm_set_force_position", "cdecl"): + rm_set_force_position = _libs[libname].get( + "rm_set_force_position", "cdecl") + rm_set_force_position.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int, c_float] + rm_set_force_position.restype = c_int + +if _libs[libname].has("rm_set_force_position_new", "cdecl"): + rm_set_force_position_new = _libs[libname].get("rm_set_force_position_new", "cdecl") + rm_set_force_position_new.argtypes = [POINTER(rm_robot_handle), rm_force_position_t] + rm_set_force_position_new.restype = c_int + +if _libs[libname].has("rm_stop_force_position", "cdecl"): + rm_stop_force_position = _libs[libname].get( + "rm_stop_force_position", "cdecl") + rm_stop_force_position.argtypes = [POINTER(rm_robot_handle)] + rm_stop_force_position.restype = c_int + +if _libs[libname].has("rm_set_force_drag_mode", "cdecl"): + rm_set_force_drag_mode = _libs[libname].get("rm_set_force_drag_mode", "cdecl") + rm_set_force_drag_mode.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_force_drag_mode.restype = c_int + +if _libs[libname].has("rm_get_force_drag_mode", "cdecl"): + rm_get_force_drag_mode = _libs[libname].get("rm_get_force_drag_mode", "cdecl") + rm_get_force_drag_mode.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_force_drag_mode.restype = c_int + +if _libs[libname].has("rm_set_hand_posture", "cdecl"): + rm_set_hand_posture = _libs[libname].get("rm_set_hand_posture", "cdecl") + rm_set_hand_posture.argtypes = [ + POINTER(rm_robot_handle), c_int, c_bool, c_int] + rm_set_hand_posture.restype = c_int + +if _libs[libname].has("rm_set_hand_seq", "cdecl"): + rm_set_hand_seq = _libs[libname].get("rm_set_hand_seq", "cdecl") + rm_set_hand_seq.argtypes = [POINTER(rm_robot_handle), c_int, c_bool, c_int] + rm_set_hand_seq.restype = c_int + +if _libs[libname].has("rm_set_hand_angle", "cdecl"): + rm_set_hand_angle = _libs[libname].get("rm_set_hand_angle", "cdecl") + rm_set_hand_angle.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), c_bool, c_int] + rm_set_hand_angle.restype = c_int + +if _libs[libname].has("rm_set_hand_follow_angle", "cdecl"): + rm_set_hand_follow_angle = _libs[libname].get("rm_set_hand_follow_angle", "cdecl") + rm_set_hand_follow_angle.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), c_bool] + rm_set_hand_follow_angle.restype = c_int + +if _libs[libname].has("rm_set_hand_follow_pos", "cdecl"): + rm_set_hand_follow_pos = _libs[libname].get("rm_set_hand_follow_pos", "cdecl") + rm_set_hand_follow_pos.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), c_bool] + rm_set_hand_follow_pos.restype = c_int + +if _libs[libname].has("rm_set_hand_speed", "cdecl"): + rm_set_hand_speed = _libs[libname].get("rm_set_hand_speed", "cdecl") + rm_set_hand_speed.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_hand_speed.restype = c_int + +if _libs[libname].has("rm_set_hand_force", "cdecl"): + rm_set_hand_force = _libs[libname].get("rm_set_hand_force", "cdecl") + rm_set_hand_force.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_hand_force.restype = c_int + +if _libs[libname].has("rm_set_modbus_mode", "cdecl"): + rm_set_modbus_mode = _libs[libname].get("rm_set_modbus_mode", "cdecl") + rm_set_modbus_mode.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_modbus_mode.restype = c_int + +if _libs[libname].has("rm_close_modbus_mode", "cdecl"): + rm_close_modbus_mode = _libs[libname].get("rm_close_modbus_mode", "cdecl") + rm_close_modbus_mode.argtypes = [POINTER(rm_robot_handle), c_int] + rm_close_modbus_mode.restype = c_int + +if _libs[libname].has("rm_set_modbustcp_mode", "cdecl"): + rm_set_modbustcp_mode = _libs[libname].get( + "rm_set_modbustcp_mode", "cdecl") + rm_set_modbustcp_mode.argtypes = [ + POINTER(rm_robot_handle), String, c_int, c_int] + rm_set_modbustcp_mode.restype = c_int + +if _libs[libname].has("rm_close_modbustcp_mode", "cdecl"): + rm_close_modbustcp_mode = _libs[libname].get( + "rm_close_modbustcp_mode", "cdecl") + rm_close_modbustcp_mode.argtypes = [POINTER(rm_robot_handle)] + rm_close_modbustcp_mode.restype = c_int + +if _libs[libname].has("rm_read_coils", "cdecl"): + rm_read_coils = _libs[libname].get("rm_read_coils", "cdecl") + rm_read_coils.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_read_coils.restype = c_int + +if _libs[libname].has("rm_read_input_status", "cdecl"): + rm_read_input_status = _libs[libname].get("rm_read_input_status", "cdecl") + rm_read_input_status.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_read_input_status.restype = c_int + +if _libs[libname].has("rm_read_holding_registers", "cdecl"): + rm_read_holding_registers = _libs[libname].get( + "rm_read_holding_registers", "cdecl") + rm_read_holding_registers.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_read_holding_registers.restype = c_int + +if _libs[libname].has("rm_read_input_registers", "cdecl"): + rm_read_input_registers = _libs[libname].get( + "rm_read_input_registers", "cdecl") + rm_read_input_registers.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_read_input_registers.restype = c_int + +if _libs[libname].has("rm_write_single_coil", "cdecl"): + rm_write_single_coil = _libs[libname].get("rm_write_single_coil", "cdecl") + rm_write_single_coil.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, c_int] + rm_write_single_coil.restype = c_int + +if _libs[libname].has("rm_write_single_register", "cdecl"): + rm_write_single_register = _libs[libname].get( + "rm_write_single_register", "cdecl") + rm_write_single_register.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, c_int] + rm_write_single_register.restype = c_int + +if _libs[libname].has("rm_write_registers", "cdecl"): + rm_write_registers = _libs[libname].get("rm_write_registers", "cdecl") + rm_write_registers.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_write_registers.restype = c_int + +if _libs[libname].has("rm_write_coils", "cdecl"): + rm_write_coils = _libs[libname].get("rm_write_coils", "cdecl") + rm_write_coils.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_write_coils.restype = c_int + +if _libs[libname].has("rm_read_multiple_coils", "cdecl"): + rm_read_multiple_coils = _libs[libname].get( + "rm_read_multiple_coils", "cdecl") + rm_read_multiple_coils.argtypes = [ + POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, POINTER(c_int)] + rm_read_multiple_coils.restype = c_int + +if _libs[libname].has("rm_read_multiple_holding_registers", "cdecl"): + rm_read_multiple_holding_registers = _libs[libname].get( + "rm_read_multiple_holding_registers", "cdecl") + rm_read_multiple_holding_registers.argtypes = [POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, + POINTER(c_int)] + rm_read_multiple_holding_registers.restype = c_int + +if _libs[libname].has("rm_read_multiple_input_registers", "cdecl"): + rm_read_multiple_input_registers = _libs[libname].get( + "rm_read_multiple_input_registers", "cdecl") + rm_read_multiple_input_registers.argtypes = [POINTER(rm_robot_handle), rm_peripheral_read_write_params_t, + POINTER(c_int)] + rm_read_multiple_input_registers.restype = c_int + +if _libs[libname].has("rm_set_install_pose", "cdecl"): + rm_set_install_pose = _libs[libname].get("rm_set_install_pose", "cdecl") + rm_set_install_pose.argtypes = [ + POINTER(rm_robot_handle), c_float, c_float, c_float] + rm_set_install_pose.restype = c_int + +if _libs[libname].has("rm_get_install_pose", "cdecl"): + rm_get_install_pose = _libs[libname].get("rm_get_install_pose", "cdecl") + rm_get_install_pose.argtypes = [POINTER(rm_robot_handle), POINTER( + c_float), POINTER(c_float), POINTER(c_float)] + rm_get_install_pose.restype = c_int + +if _libs[libname].has("rm_get_joint_software_version", "cdecl"): + rm_get_joint_software_version = _libs[libname].get("rm_get_joint_software_version", "cdecl") + rm_get_joint_software_version.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), POINTER(rm_version_t)] + rm_get_joint_software_version.restype = c_int + +if _libs[libname].has("rm_get_tool_software_version", "cdecl"): + rm_get_tool_software_version = _libs[libname].get( + "rm_get_tool_software_version", "cdecl") + rm_get_tool_software_version.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), POINTER(rm_version_t)] + rm_get_tool_software_version.restype = c_int + +if _libs[libname].has("rm_start_force_position_move", "cdecl"): + rm_start_force_position_move = _libs[libname].get( + "rm_start_force_position_move", "cdecl") + rm_start_force_position_move.argtypes = [POINTER(rm_robot_handle)] + rm_start_force_position_move.restype = c_int + +if _libs[libname].has("rm_stop_force_position_move", "cdecl"): + rm_stop_force_position_move = _libs[libname].get( + "rm_stop_force_position_move", "cdecl") + rm_stop_force_position_move.argtypes = [POINTER(rm_robot_handle)] + rm_stop_force_position_move.restype = c_int + +if _libs[libname].has("rm_force_position_move_joint", "cdecl"): + rm_force_position_move_joint = _libs[libname].get( + "rm_force_position_move_joint", "cdecl") + rm_force_position_move_joint.argtypes = [POINTER(rm_robot_handle), POINTER(c_float), c_int, c_int, c_int, c_float, + c_bool] + rm_force_position_move_joint.restype = c_int + +if _libs[libname].has("rm_force_position_move_pose", "cdecl"): + rm_force_position_move_pose = _libs[libname].get( + "rm_force_position_move_pose", "cdecl") + rm_force_position_move_pose.argtypes = [ + POINTER(rm_robot_handle), rm_pose_t, c_int, c_int, c_int, c_float, c_bool] + rm_force_position_move_pose.restype = c_int + +if _libs[libname].has("rm_force_position_move", "cdecl"): + rm_force_position_move = _libs[libname].get("rm_force_position_move", "cdecl") + rm_force_position_move.argtypes = [POINTER(rm_robot_handle), rm_force_position_move_t] + rm_force_position_move.restype = c_int + +if _libs[libname].has("rm_set_lift_speed", "cdecl"): + rm_set_lift_speed = _libs[libname].get("rm_set_lift_speed", "cdecl") + rm_set_lift_speed.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_lift_speed.restype = c_int + +if _libs[libname].has("rm_set_lift_height", "cdecl"): + rm_set_lift_height = _libs[libname].get("rm_set_lift_height", "cdecl") + rm_set_lift_height.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_lift_height.restype = c_int + +if _libs[libname].has("rm_get_lift_state", "cdecl"): + rm_get_lift_state = _libs[libname].get("rm_get_lift_state", "cdecl") + rm_get_lift_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_expand_state_t)] + rm_get_lift_state.restype = c_int + +if _libs[libname].has("rm_get_expand_state", "cdecl"): + rm_get_expand_state = _libs[libname].get("rm_get_expand_state", "cdecl") + rm_get_expand_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_expand_state_t)] + rm_get_expand_state.restype = c_int + +if _libs[libname].has("rm_set_expand_speed", "cdecl"): + rm_set_expand_speed = _libs[libname].get("rm_set_expand_speed", "cdecl") + rm_set_expand_speed.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_expand_speed.restype = c_int + +if _libs[libname].has("rm_set_expand_pos", "cdecl"): + rm_set_expand_pos = _libs[libname].get("rm_set_expand_pos", "cdecl") + rm_set_expand_pos.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_expand_pos.restype = c_int + +if _libs[libname].has("rm_send_project", "cdecl"): + rm_send_project = _libs[libname].get("rm_send_project", "cdecl") + rm_send_project.argtypes = [ + POINTER(rm_robot_handle), rm_send_project_t, POINTER(c_int)] + rm_send_project.restype = c_int + +if _libs[libname].has("rm_set_plan_speed", "cdecl"): + rm_set_plan_speed = _libs[libname].get("rm_set_plan_speed", "cdecl") + rm_set_plan_speed.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_plan_speed.restype = c_int + +if _libs[libname].has("rm_save_trajectory", "cdecl"): + rm_save_trajectory = _libs[libname].get("rm_save_trajectory", "cdecl") + rm_save_trajectory.argtypes = [ + POINTER(rm_robot_handle), String, POINTER(c_int)] + rm_save_trajectory.restype = c_int + +if _libs[libname].has("rm_get_program_trajectory_list", "cdecl"): + rm_get_program_trajectory_list = _libs[libname].get( + "rm_get_program_trajectory_list", "cdecl") + rm_get_program_trajectory_list.argtypes = [POINTER(rm_robot_handle), c_int, c_int, String, + POINTER(rm_program_trajectorys_t)] + rm_get_program_trajectory_list.restype = c_int + +if _libs[libname].has("rm_set_program_id_run", "cdecl"): + rm_set_program_id_run = _libs[libname].get( + "rm_set_program_id_run", "cdecl") + rm_set_program_id_run.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_program_id_run.restype = c_int + +if _libs[libname].has("rm_get_program_run_state", "cdecl"): + rm_get_program_run_state = _libs[libname].get( + "rm_get_program_run_state", "cdecl") + rm_get_program_run_state.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_program_run_state_t)] + rm_get_program_run_state.restype = c_int + +if _libs[libname].has("rm_delete_program_trajectory", "cdecl"): + rm_delete_program_trajectory = _libs[libname].get( + "rm_delete_program_trajectory", "cdecl") + rm_delete_program_trajectory.argtypes = [POINTER(rm_robot_handle), c_int] + rm_delete_program_trajectory.restype = c_int + +if _libs[libname].has("rm_update_program_trajectory", "cdecl"): + rm_update_program_trajectory = _libs[libname].get( + "rm_update_program_trajectory", "cdecl") + rm_update_program_trajectory.argtypes = [ + POINTER(rm_robot_handle), c_int, c_int, String] + rm_update_program_trajectory.restype = c_int + +if _libs[libname].has("rm_set_default_run_program", "cdecl"): + rm_set_default_run_program = _libs[libname].get( + "rm_set_default_run_program", "cdecl") + rm_set_default_run_program.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_default_run_program.restype = c_int + +if _libs[libname].has("rm_get_default_run_program", "cdecl"): + rm_get_default_run_program = _libs[libname].get( + "rm_get_default_run_program", "cdecl") + rm_get_default_run_program.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_default_run_program.restype = c_int + +if _libs[libname].has("rm_set_realtime_push", "cdecl"): + rm_set_realtime_push = _libs[libname].get("rm_set_realtime_push", "cdecl") + rm_set_realtime_push.argtypes = [ + POINTER(rm_robot_handle), rm_realtime_push_config_t] + rm_set_realtime_push.restype = c_int + +if _libs[libname].has("rm_get_realtime_push", "cdecl"): + rm_get_realtime_push = _libs[libname].get("rm_get_realtime_push", "cdecl") + rm_get_realtime_push.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_realtime_push_config_t)] + rm_get_realtime_push.restype = c_int + +if _libs[libname].has("rm_add_global_waypoint", "cdecl"): + rm_add_global_waypoint = _libs[libname].get( + "rm_add_global_waypoint", "cdecl") + rm_add_global_waypoint.argtypes = [POINTER(rm_robot_handle), rm_waypoint_t] + rm_add_global_waypoint.restype = c_int + +if _libs[libname].has("rm_update_global_waypoint", "cdecl"): + rm_update_global_waypoint = _libs[libname].get( + "rm_update_global_waypoint", "cdecl") + rm_update_global_waypoint.argtypes = [ + POINTER(rm_robot_handle), rm_waypoint_t] + rm_update_global_waypoint.restype = c_int + +if _libs[libname].has("rm_delete_global_waypoint", "cdecl"): + rm_delete_global_waypoint = _libs[libname].get( + "rm_delete_global_waypoint", "cdecl") + rm_delete_global_waypoint.argtypes = [POINTER(rm_robot_handle), GBKString] + rm_delete_global_waypoint.restype = c_int + +if _libs[libname].has("rm_get_given_global_waypoint", "cdecl"): + rm_get_given_global_waypoint = _libs[libname].get( + "rm_get_given_global_waypoint", "cdecl") + rm_get_given_global_waypoint.argtypes = [ + POINTER(rm_robot_handle), GBKString, POINTER(rm_waypoint_t)] + rm_get_given_global_waypoint.restype = c_int + +if _libs[libname].has("rm_get_global_waypoints_list", "cdecl"): + rm_get_global_waypoints_list = _libs[libname].get( + "rm_get_global_waypoints_list", "cdecl") + rm_get_global_waypoints_list.argtypes = [POINTER(rm_robot_handle), c_int, c_int, GBKString, + POINTER(rm_waypoint_list_t)] + rm_get_global_waypoints_list.restype = c_int + +if _libs[libname].has("rm_add_electronic_fence_config", "cdecl"): + rm_add_electronic_fence_config = _libs[libname].get( + "rm_add_electronic_fence_config", "cdecl") + rm_add_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), rm_fence_config_t] + rm_add_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_update_electronic_fence_config", "cdecl"): + rm_update_electronic_fence_config = _libs[libname].get( + "rm_update_electronic_fence_config", "cdecl") + rm_update_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), rm_fence_config_t] + rm_update_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_delete_electronic_fence_config", "cdecl"): + rm_delete_electronic_fence_config = _libs[libname].get( + "rm_delete_electronic_fence_config", "cdecl") + rm_delete_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), String] + rm_delete_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_get_electronic_fence_list_names", "cdecl"): + rm_get_electronic_fence_list_names = _libs[libname].get( + "rm_get_electronic_fence_list_names", "cdecl") + rm_get_electronic_fence_list_names.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_fence_names_t), POINTER(c_int)] + rm_get_electronic_fence_list_names.restype = c_int + +if _libs[libname].has("rm_get_given_electronic_fence_config", "cdecl"): + rm_get_given_electronic_fence_config = _libs[libname].get( + "rm_get_given_electronic_fence_config", "cdecl") + rm_get_given_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), String, POINTER(rm_fence_config_t)] + rm_get_given_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_get_electronic_fence_list_infos", "cdecl"): + rm_get_electronic_fence_list_infos = _libs[libname].get( + "rm_get_electronic_fence_list_infos", "cdecl") + rm_get_electronic_fence_list_infos.argtypes = [POINTER(rm_robot_handle), POINTER(rm_fence_config_list_t), + POINTER(c_int)] + rm_get_electronic_fence_list_infos.restype = c_int + +if _libs[libname].has("rm_set_electronic_fence_enable", "cdecl"): + rm_set_electronic_fence_enable = _libs[libname].get( + "rm_set_electronic_fence_enable", "cdecl") + rm_set_electronic_fence_enable.argtypes = [ + POINTER(rm_robot_handle), rm_electronic_fence_enable_t] + rm_set_electronic_fence_enable.restype = c_int + +if _libs[libname].has("rm_get_electronic_fence_enable", "cdecl"): + rm_get_electronic_fence_enable = _libs[libname].get( + "rm_get_electronic_fence_enable", "cdecl") + rm_get_electronic_fence_enable.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_electronic_fence_enable_t)] + rm_get_electronic_fence_enable.restype = c_int + +if _libs[libname].has("rm_set_electronic_fence_config", "cdecl"): + rm_set_electronic_fence_config = _libs[libname].get( + "rm_set_electronic_fence_config", "cdecl") + rm_set_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), rm_fence_config_t] + rm_set_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_get_electronic_fence_config", "cdecl"): + rm_get_electronic_fence_config = _libs[libname].get( + "rm_get_electronic_fence_config", "cdecl") + rm_get_electronic_fence_config.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_fence_config_t)] + rm_get_electronic_fence_config.restype = c_int + +if _libs[libname].has("rm_set_virtual_wall_enable", "cdecl"): + rm_set_virtual_wall_enable = _libs[libname].get( + "rm_set_virtual_wall_enable", "cdecl") + rm_set_virtual_wall_enable.argtypes = [ + POINTER(rm_robot_handle), rm_electronic_fence_enable_t] + rm_set_virtual_wall_enable.restype = c_int + +if _libs[libname].has("rm_get_virtual_wall_enable", "cdecl"): + rm_get_virtual_wall_enable = _libs[libname].get( + "rm_get_virtual_wall_enable", "cdecl") + rm_get_virtual_wall_enable.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_electronic_fence_enable_t)] + rm_get_virtual_wall_enable.restype = c_int + +if _libs[libname].has("rm_set_virtual_wall_config", "cdecl"): + rm_set_virtual_wall_config = _libs[libname].get( + "rm_set_virtual_wall_config", "cdecl") + rm_set_virtual_wall_config.argtypes = [ + POINTER(rm_robot_handle), rm_fence_config_t] + rm_set_virtual_wall_config.restype = c_int + +if _libs[libname].has("rm_get_virtual_wall_config", "cdecl"): + rm_get_virtual_wall_config = _libs[libname].get( + "rm_get_virtual_wall_config", "cdecl") + rm_get_virtual_wall_config.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_fence_config_t)] + rm_get_virtual_wall_config.restype = c_int + +if _libs[libname].has("rm_set_self_collision_enable", "cdecl"): + rm_set_self_collision_enable = _libs[libname].get( + "rm_set_self_collision_enable", "cdecl") + rm_set_self_collision_enable.argtypes = [POINTER(rm_robot_handle), c_bool] + rm_set_self_collision_enable.restype = c_int + +if _libs[libname].has("rm_get_self_collision_enable", "cdecl"): + rm_get_self_collision_enable = _libs[libname].get( + "rm_get_self_collision_enable", "cdecl") + rm_get_self_collision_enable.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_bool)] + rm_get_self_collision_enable.restype = c_int + +if _libs[libname].has("rm_algo_version", "cdecl"): + rm_algo_version = _libs[libname].get("rm_algo_version", "cdecl") + rm_algo_version.argtypes = [] + if sizeof(c_int) == sizeof(c_void_p): + rm_algo_version.restype = ReturnString + else: + rm_algo_version.restype = String + rm_algo_version.errcheck = ReturnString + +if _libs[libname].has("rm_algo_init_sys_data", "cdecl"): + rm_algo_init_sys_data = _libs[libname].get( + "rm_algo_init_sys_data", "cdecl") + rm_algo_init_sys_data.argtypes = [c_int, c_int] + rm_algo_init_sys_data.restype = None + +if _libs[libname].has("rm_algo_init_sys_data_by_dh", "cdecl"): + rm_algo_init_sys_data_by_dh = _libs[libname].get("rm_algo_init_sys_data_by_dh", "cdecl") + rm_algo_init_sys_data_by_dh.argtypes = [c_int, rm_dh_t, c_int] + rm_algo_init_sys_data_by_dh.restype = None + +if _libs[libname].has("rm_algo_set_robot_dof", "cdecl"): + rm_algo_set_robot_dof = _libs[libname].get( + "rm_algo_set_robot_dof", "cdecl") + rm_algo_set_robot_dof.argtypes = [c_int] + rm_algo_set_robot_dof.restype = None + +if _libs[libname].has("rm_algo_set_angle", "cdecl"): + rm_algo_set_angle = _libs[libname].get("rm_algo_set_angle", "cdecl") + rm_algo_set_angle.argtypes = [c_float, c_float, c_float] + rm_algo_set_angle.restype = None + +if _libs[libname].has("rm_algo_get_angle", "cdecl"): + rm_algo_get_angle = _libs[libname].get("rm_algo_get_angle", "cdecl") + rm_algo_get_angle.argtypes = [ + POINTER(c_float), POINTER(c_float), POINTER(c_float)] + rm_algo_get_angle.restype = None + +if _libs[libname].has("rm_algo_set_redundant_parameter_traversal_mode", "cdecl"): + rm_algo_set_redundant_parameter_traversal_mode = _libs[libname].get("rm_algo_set_redundant_parameter_traversal_mode", "cdecl") + rm_algo_set_redundant_parameter_traversal_mode.argtypes = [c_bool] + rm_algo_set_redundant_parameter_traversal_mode.restype = None + +if _libs[libname].has("rm_algo_set_workframe", "cdecl"): + rm_algo_set_workframe = _libs[libname].get( + "rm_algo_set_workframe", "cdecl") + rm_algo_set_workframe.argtypes = [POINTER(rm_frame_t)] + rm_algo_set_workframe.restype = None + +if _libs[libname].has("rm_algo_get_curr_workframe", "cdecl"): + rm_algo_get_curr_workframe = _libs[libname].get( + "rm_algo_get_curr_workframe", "cdecl") + rm_algo_get_curr_workframe.argtypes = [POINTER(rm_frame_t)] + rm_algo_get_curr_workframe.restype = None + +if _libs[libname].has("rm_algo_set_toolframe", "cdecl"): + rm_algo_set_toolframe = _libs[libname].get( + "rm_algo_set_toolframe", "cdecl") + rm_algo_set_toolframe.argtypes = [POINTER(rm_frame_t)] + rm_algo_set_toolframe.restype = None + +if _libs[libname].has("rm_algo_get_curr_toolframe", "cdecl"): + rm_algo_get_curr_toolframe = _libs[libname].get( + "rm_algo_get_curr_toolframe", "cdecl") + rm_algo_get_curr_toolframe.argtypes = [POINTER(rm_frame_t)] + rm_algo_get_curr_toolframe.restype = None + +if _libs[libname].has("rm_algo_set_joint_max_limit", "cdecl"): + rm_algo_set_joint_max_limit = _libs[libname].get( + "rm_algo_set_joint_max_limit", "cdecl") + rm_algo_set_joint_max_limit.argtypes = [POINTER(c_float)] + rm_algo_set_joint_max_limit.restype = None + +if _libs[libname].has("rm_algo_get_joint_max_limit", "cdecl"): + rm_algo_get_joint_max_limit = _libs[libname].get( + "rm_algo_get_joint_max_limit", "cdecl") + rm_algo_get_joint_max_limit.argtypes = [POINTER(c_float)] + rm_algo_get_joint_max_limit.restype = None + +if _libs[libname].has("rm_algo_set_joint_min_limit", "cdecl"): + rm_algo_set_joint_min_limit = _libs[libname].get( + "rm_algo_set_joint_min_limit", "cdecl") + rm_algo_set_joint_min_limit.argtypes = [POINTER(c_float)] + rm_algo_set_joint_min_limit.restype = None + +if _libs[libname].has("rm_algo_get_joint_min_limit", "cdecl"): + rm_algo_get_joint_min_limit = _libs[libname].get( + "rm_algo_get_joint_min_limit", "cdecl") + rm_algo_get_joint_min_limit.argtypes = [POINTER(c_float)] + rm_algo_get_joint_min_limit.restype = None + +if _libs[libname].has("rm_algo_set_joint_max_speed", "cdecl"): + rm_algo_set_joint_max_speed = _libs[libname].get( + "rm_algo_set_joint_max_speed", "cdecl") + rm_algo_set_joint_max_speed.argtypes = [POINTER(c_float)] + rm_algo_set_joint_max_speed.restype = None + +if _libs[libname].has("rm_algo_get_joint_max_speed", "cdecl"): + rm_algo_get_joint_max_speed = _libs[libname].get( + "rm_algo_get_joint_max_speed", "cdecl") + rm_algo_get_joint_max_speed.argtypes = [POINTER(c_float)] + rm_algo_get_joint_max_speed.restype = None + +if _libs[libname].has("rm_algo_set_joint_max_acc", "cdecl"): + rm_algo_set_joint_max_acc = _libs[libname].get( + "rm_algo_set_joint_max_acc", "cdecl") + rm_algo_set_joint_max_acc.argtypes = [POINTER(c_float)] + rm_algo_set_joint_max_acc.restype = None + +if _libs[libname].has("rm_algo_get_joint_max_acc", "cdecl"): + rm_algo_get_joint_max_acc = _libs[libname].get( + "rm_algo_get_joint_max_acc", "cdecl") + rm_algo_get_joint_max_acc.argtypes = [POINTER(c_float)] + rm_algo_get_joint_max_acc.restype = None + +if _libs[libname].has("rm_algo_inverse_kinematics", "cdecl"): + rm_algo_inverse_kinematics = _libs[libname].get( + "rm_algo_inverse_kinematics", "cdecl") + rm_algo_inverse_kinematics.argtypes = [POINTER(rm_robot_handle), rm_inverse_kinematics_params_t, + POINTER(c_float)] + rm_algo_inverse_kinematics.restype = c_int + +if _libs[libname].has("rm_algo_inverse_kinematics_all", "cdecl"): + rm_algo_inverse_kinematics_all = _libs[libname].get( + "rm_algo_inverse_kinematics_all", "cdecl") + rm_algo_inverse_kinematics_all.argtypes = [POINTER(rm_robot_handle), rm_inverse_kinematics_params_t] + rm_algo_inverse_kinematics_all.restype = rm_inverse_kinematics_all_solve_t + +if _libs[libname].has("rm_algo_ikine_select_ik_solve", "cdecl"): + rm_algo_ikine_select_ik_solve = _libs[libname].get( + "rm_algo_ikine_select_ik_solve", "cdecl") + rm_algo_ikine_select_ik_solve.argtypes = [POINTER(c_float), rm_inverse_kinematics_all_solve_t] + rm_algo_ikine_select_ik_solve.restype = c_int + +if _libs[libname].has("rm_algo_ikine_check_joint_position_limit", "cdecl"): + rm_algo_ikine_check_joint_position_limit = _libs[libname].get( + "rm_algo_ikine_check_joint_position_limit", "cdecl") + rm_algo_ikine_check_joint_position_limit.argtypes = [POINTER(c_float)] + rm_algo_ikine_check_joint_position_limit.restype = c_int + +if _libs[libname].has("rm_algo_ikine_check_joint_velocity_limit", "cdecl"): + rm_algo_ikine_check_joint_velocity_limit = _libs[libname].get( + "rm_algo_ikine_check_joint_velocity_limit", "cdecl") + rm_algo_ikine_check_joint_velocity_limit.argtypes = [c_float, POINTER(c_float),POINTER(c_float)] + rm_algo_ikine_check_joint_velocity_limit.restype = c_int + +if _libs[libname].has("rm_algo_calculate_arm_angle_from_config_rm75", "cdecl"): + rm_algo_calculate_arm_angle_from_config_rm75 = _libs[libname].get( + "rm_algo_calculate_arm_angle_from_config_rm75", "cdecl") + rm_algo_calculate_arm_angle_from_config_rm75.argtypes = [POINTER(c_float),POINTER(c_float)] + rm_algo_calculate_arm_angle_from_config_rm75.restype = c_int + +if _libs[libname].has("rm_algo_inverse_kinematics_rm75_for_arm_angle", "cdecl"): + rm_algo_inverse_kinematics_rm75_for_arm_angle = _libs[libname].get( + "rm_algo_inverse_kinematics_rm75_for_arm_angle", "cdecl") + rm_algo_inverse_kinematics_rm75_for_arm_angle.argtypes = [rm_inverse_kinematics_params_t, c_float,POINTER(c_float)] + rm_algo_inverse_kinematics_rm75_for_arm_angle.restype = c_int + +if _libs[libname].has("rm_algo_forward_kinematics", "cdecl"): + rm_algo_forward_kinematics = _libs[libname].get( + "rm_algo_forward_kinematics", "cdecl") + rm_algo_forward_kinematics.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float)] + rm_algo_forward_kinematics.restype = rm_pose_t + +if _libs[libname].has("rm_algo_euler2quaternion", "cdecl"): + rm_algo_euler2quaternion = _libs[libname].get( + "rm_algo_euler2quaternion", "cdecl") + rm_algo_euler2quaternion.argtypes = [rm_euler_t] + rm_algo_euler2quaternion.restype = rm_quat_t + +if _libs[libname].has("rm_algo_quaternion2euler", "cdecl"): + rm_algo_quaternion2euler = _libs[libname].get( + "rm_algo_quaternion2euler", "cdecl") + rm_algo_quaternion2euler.argtypes = [rm_quat_t] + rm_algo_quaternion2euler.restype = rm_euler_t + +if _libs[libname].has("rm_algo_euler2matrix", "cdecl"): + rm_algo_euler2matrix = _libs[libname].get("rm_algo_euler2matrix", "cdecl") + rm_algo_euler2matrix.argtypes = [rm_euler_t] + rm_algo_euler2matrix.restype = rm_matrix_t + +if _libs[libname].has("rm_algo_pos2matrix", "cdecl"): + rm_algo_pos2matrix = _libs[libname].get("rm_algo_pos2matrix", "cdecl") + rm_algo_pos2matrix.argtypes = [rm_pose_t] + rm_algo_pos2matrix.restype = rm_matrix_t + +if _libs[libname].has("rm_algo_matrix2pos", "cdecl"): + rm_algo_matrix2pos = _libs[libname].get("rm_algo_matrix2pos", "cdecl") + rm_algo_matrix2pos.argtypes = [rm_matrix_t] + rm_algo_matrix2pos.restype = rm_pose_t + +if _libs[libname].has("rm_algo_base2workframe", "cdecl"): + rm_algo_base2workframe = _libs[libname].get( + "rm_algo_base2workframe", "cdecl") + rm_algo_base2workframe.argtypes = [rm_matrix_t, rm_pose_t] + rm_algo_base2workframe.restype = rm_pose_t + +if _libs[libname].has("rm_algo_workframe2base", "cdecl"): + rm_algo_workframe2base = _libs[libname].get( + "rm_algo_workframe2base", "cdecl") + rm_algo_workframe2base.argtypes = [rm_matrix_t, rm_pose_t] + rm_algo_workframe2base.restype = rm_pose_t + +if _libs[libname].has("rm_algo_rotate_move", "cdecl"): + rm_algo_rotate_move = _libs[libname].get("rm_algo_rotate_move", "cdecl") + rm_algo_rotate_move.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float), c_int, c_float, rm_pose_t] + rm_algo_rotate_move.restype = rm_pose_t + +if _libs[libname].has("rm_algo_cartesian_tool", "cdecl"): + rm_algo_cartesian_tool = _libs[libname].get( + "rm_algo_cartesian_tool", "cdecl") + rm_algo_cartesian_tool.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_float), c_float, c_float, c_float] + rm_algo_cartesian_tool.restype = rm_pose_t + +if _libs[libname].has("rm_algo_pose_move", "cdecl"): + rm_algo_pose_move = _libs[libname].get("rm_algo_pose_move", "cdecl") + rm_algo_pose_move.argtypes = [POINTER(rm_robot_handle), rm_pose_t, POINTER(c_float), c_int] + rm_algo_pose_move.restype = rm_pose_t + +if _libs[libname].has("rm_algo_end2tool", "cdecl"): + rm_algo_end2tool = _libs[libname].get("rm_algo_end2tool", "cdecl") + rm_algo_end2tool.argtypes = [POINTER(rm_robot_handle), rm_pose_t] + rm_algo_end2tool.restype = rm_pose_t + +if _libs[libname].has("rm_algo_tool2end", "cdecl"): + rm_algo_tool2end = _libs[libname].get("rm_algo_tool2end", "cdecl") + rm_algo_tool2end.argtypes = [POINTER(rm_robot_handle), rm_pose_t] + rm_algo_tool2end.restype = rm_pose_t + +if _libs[libname].has("rm_algo_get_dh", "cdecl"): + rm_algo_get_dh = _libs[libname].get("rm_algo_get_dh", "cdecl") + rm_algo_get_dh.argtypes = [] + rm_algo_get_dh.restype = rm_dh_t + +if _libs[libname].has("rm_algo_set_dh", "cdecl"): + rm_algo_set_dh = _libs[libname].get("rm_algo_set_dh", "cdecl") + rm_algo_set_dh.argtypes = [rm_dh_t] + rm_algo_set_dh.restype = None + +if _libs[libname].has("rm_set_rm_plus_mode", "cdecl"): + rm_set_rm_plus_mode = _libs[libname].get( + "rm_set_rm_plus_mode", "cdecl") + rm_set_rm_plus_mode.argtypes = [ + POINTER(rm_robot_handle), c_int] + rm_set_rm_plus_mode.restype = c_int + +if _libs[libname].has("rm_get_rm_plus_mode", "cdecl"): + rm_get_rm_plus_mode = _libs[libname].get( + "rm_get_rm_plus_mode", "cdecl") + rm_get_rm_plus_mode.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_rm_plus_mode.restype = c_int + +if _libs[libname].has("rm_set_rm_plus_touch", "cdecl"): + rm_set_rm_plus_touch = _libs[libname].get( + "rm_set_rm_plus_touch", "cdecl") + rm_set_rm_plus_touch.argtypes = [ + POINTER(rm_robot_handle), c_int] + rm_set_rm_plus_touch.restype = c_int + +if _libs[libname].has("rm_get_rm_plus_touch", "cdecl"): + rm_get_rm_plus_touch = _libs[libname].get( + "rm_get_rm_plus_touch", "cdecl") + rm_get_rm_plus_touch.argtypes = [ + POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_rm_plus_touch.restype = c_int + +if _libs[libname].has("rm_get_rm_plus_base_info", "cdecl"): + rm_get_rm_plus_base_info = _libs[libname].get( + "rm_get_rm_plus_base_info", "cdecl") + rm_get_rm_plus_base_info.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_plus_base_info_t)] + rm_get_rm_plus_base_info.restype = c_int + +if _libs[libname].has("rm_get_rm_plus_state_info", "cdecl"): + rm_get_rm_plus_state_info = _libs[libname].get( + "rm_get_rm_plus_state_info", "cdecl") + rm_get_rm_plus_state_info.argtypes = [ + POINTER(rm_robot_handle), POINTER(rm_plus_state_info_t)] + rm_get_rm_plus_state_info.restype = c_int + + +if _libs[libname].has("rm_algo_universal_singularity_analyse", "cdecl"): + rm_algo_universal_singularity_analyse = _libs[libname].get( + "rm_algo_universal_singularity_analyse", "cdecl") + rm_algo_universal_singularity_analyse.argtypes = [ + POINTER(c_float), c_float] + rm_algo_universal_singularity_analyse.restype = c_int + +if _libs[libname].has("rm_algo_kin_set_singularity_thresholds", "cdecl"): + rm_algo_kin_set_singularity_thresholds = _libs[libname].get( + "rm_algo_kin_set_singularity_thresholds", "cdecl") + rm_algo_kin_set_singularity_thresholds.argtypes = [ + c_float, c_float, c_float] + rm_algo_kin_set_singularity_thresholds.restype = None + +if _libs[libname].has("rm_algo_kin_get_singularity_thresholds", "cdecl"): + rm_algo_kin_get_singularity_thresholds = _libs[libname].get( + "rm_algo_kin_get_singularity_thresholds", "cdecl") + rm_algo_kin_get_singularity_thresholds.argtypes = [ + POINTER(c_float), POINTER(c_float), POINTER(c_float)] + rm_algo_kin_get_singularity_thresholds.restype = None + + +if _libs[libname].has("rm_algo_kin_singularity_thresholds_init", "cdecl"): + rm_algo_kin_singularity_thresholds_init = _libs[libname].get( + "rm_algo_kin_singularity_thresholds_init", "cdecl") + rm_algo_kin_singularity_thresholds_init.argtypes = [] + rm_algo_kin_singularity_thresholds_init.restype = None + +if _libs[libname].has("rm_algo_kin_robot_singularity_analyse", "cdecl"): + rm_algo_kin_robot_singularity_analyse = _libs[libname].get( + "rm_algo_kin_robot_singularity_analyse", "cdecl") + rm_algo_kin_robot_singularity_analyse.argtypes = [ + POINTER(c_float), POINTER(c_float)] + rm_algo_kin_robot_singularity_analyse.restype = c_int + + +if _libs[libname].has("rm_algo_set_tool_envelope", "cdecl"): + rm_algo_set_tool_envelope = _libs[libname].get( + "rm_algo_set_tool_envelope", "cdecl") + rm_algo_set_tool_envelope.argtypes = [ + c_int, rm_tool_sphere_t] + rm_algo_set_tool_envelope.restype = None + +if _libs[libname].has("rm_algo_get_tool_envelope", "cdecl"): + rm_algo_get_tool_envelope = _libs[libname].get( + "rm_algo_get_tool_envelope", "cdecl") + rm_algo_get_tool_envelope.argtypes = [ + c_int, POINTER(rm_tool_sphere_t)] + rm_algo_get_tool_envelope.restype = None + +if _libs[libname].has("rm_algo_safety_robot_self_collision_detection", "cdecl"): + rm_algo_safety_robot_self_collision_detection = _libs[libname].get( + "rm_algo_safety_robot_self_collision_detection", "cdecl") + rm_algo_safety_robot_self_collision_detection.argtypes = [ + POINTER(c_float)] + rm_algo_safety_robot_self_collision_detection.restype = c_int + +if _libs[libname].has("rm_get_flowchart_program_run_state", "cdecl"): + rm_get_flowchart_program_run_state = _libs[libname].get("rm_get_flowchart_program_run_state", "cdecl") + rm_get_flowchart_program_run_state.argtypes = [POINTER(rm_robot_handle), POINTER(rm_flowchart_run_state_t)] + rm_get_flowchart_program_run_state.restype = c_int + +if _libs[libname].has("rm_get_trajectory_file_list", "cdecl"): + rm_get_trajectory_file_list = _libs[libname].get("rm_get_trajectory_file_list", "cdecl") + rm_get_trajectory_file_list.argtypes = [POINTER(rm_robot_handle), c_int, c_int, String, + POINTER(rm_trajectory_list_t)] + rm_get_trajectory_file_list.restype = c_int + +if _libs[libname].has("rm_set_run_trajectory", "cdecl"): + rm_set_run_trajectory = _libs[libname].get("rm_set_run_trajectory", "cdecl") + rm_set_run_trajectory.argtypes = [POINTER(rm_robot_handle), String] + rm_set_run_trajectory.restype = c_int + +if _libs[libname].has("rm_delete_trajectory_file", "cdecl"): + rm_delete_trajectory_file = _libs[libname].get("rm_delete_trajectory_file", "cdecl") + rm_delete_trajectory_file.argtypes = [POINTER(rm_robot_handle), String] + rm_delete_trajectory_file.restype = c_int + +if _libs[libname].has("rm_save_trajectory_file", "cdecl"): + rm_save_trajectory_file = _libs[libname].get("rm_save_trajectory_file", "cdecl") + rm_save_trajectory_file.argtypes = [POINTER(rm_robot_handle), String] + rm_save_trajectory_file.restype = c_int + +if _libs[libname].has("rm_set_arm_emergency_stop", "cdecl"): + rm_set_arm_emergency_stop = _libs[libname].get("rm_set_arm_emergency_stop", "cdecl") + rm_set_arm_emergency_stop.argtypes = [POINTER(rm_robot_handle), c_bool] + rm_set_arm_emergency_stop.restype = c_int + +if _libs[libname].has("rm_add_modbus_tcp_master", "cdecl"): + rm_add_modbus_tcp_master = _libs[libname].get("rm_add_modbus_tcp_master", "cdecl") + rm_add_modbus_tcp_master.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_master_info_t] + rm_add_modbus_tcp_master.restype = c_int + +if _libs[libname].has("rm_update_modbus_tcp_master", "cdecl"): + rm_update_modbus_tcp_master = _libs[libname].get("rm_update_modbus_tcp_master", "cdecl") + rm_update_modbus_tcp_master.argtypes = [POINTER(rm_robot_handle), String, rm_modbus_tcp_master_info_t] + rm_update_modbus_tcp_master.restype = c_int + +if _libs[libname].has("rm_delete_modbus_tcp_master", "cdecl"): + rm_delete_modbus_tcp_master = _libs[libname].get("rm_delete_modbus_tcp_master", "cdecl") + rm_delete_modbus_tcp_master.argtypes = [POINTER(rm_robot_handle), String] + rm_delete_modbus_tcp_master.restype = c_int + +if _libs[libname].has("rm_get_modbus_tcp_master", "cdecl"): + rm_get_modbus_tcp_master = _libs[libname].get("rm_get_modbus_tcp_master", "cdecl") + rm_get_modbus_tcp_master.argtypes = [POINTER(rm_robot_handle), String, POINTER(rm_modbus_tcp_master_info_t)] + rm_get_modbus_tcp_master.restype = c_int + +if _libs[libname].has("rm_get_modbus_tcp_master_list", "cdecl"): + rm_get_modbus_tcp_master_list = _libs[libname].get("rm_get_modbus_tcp_master_list", "cdecl") + rm_get_modbus_tcp_master_list.argtypes = [POINTER(rm_robot_handle), c_int, c_int, String, POINTER(rm_modbus_tcp_master_list_t)] + rm_get_modbus_tcp_master_list.restype = c_int + +if _libs[libname].has("rm_set_controller_rs485_mode", "cdecl"): + rm_set_controller_rs485_mode = _libs[libname].get("rm_set_controller_rs485_mode", "cdecl") + rm_set_controller_rs485_mode.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_controller_rs485_mode.restype = c_int + +if _libs[libname].has("rm_get_controller_rs485_mode_v4", "cdecl"): + rm_get_controller_rs485_mode_v4 = _libs[libname].get("rm_get_controller_rs485_mode_v4", "cdecl") + rm_get_controller_rs485_mode_v4.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int)] + rm_get_controller_rs485_mode_v4.restype = c_int + +if _libs[libname].has("rm_set_tool_rs485_mode", "cdecl"): + rm_set_tool_rs485_mode = _libs[libname].get("rm_set_tool_rs485_mode", "cdecl") + rm_set_tool_rs485_mode.argtypes = [POINTER(rm_robot_handle), c_int, c_int] + rm_set_tool_rs485_mode.restype = c_int + +if _libs[libname].has("rm_get_tool_rs485_mode_v4", "cdecl"): + rm_get_tool_rs485_mode_v4 = _libs[libname].get("rm_get_tool_rs485_mode_v4", "cdecl") + rm_get_tool_rs485_mode_v4.argtypes = [POINTER(rm_robot_handle), POINTER(c_int), POINTER(c_int)] + rm_get_tool_rs485_mode_v4.restype = c_int + +if _libs[libname].has("rm_read_modbus_rtu_coils", "cdecl"): + rm_read_modbus_rtu_coils = _libs[libname].get("rm_read_modbus_rtu_coils", "cdecl") + rm_read_modbus_rtu_coils.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_read_params_t, POINTER(c_int)] + rm_read_modbus_rtu_coils.restype = c_int + +if _libs[libname].has("rm_write_modbus_rtu_coils", "cdecl"): + rm_write_modbus_rtu_coils = _libs[libname].get("rm_write_modbus_rtu_coils", "cdecl") + rm_write_modbus_rtu_coils.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_write_params_t] + rm_write_modbus_rtu_coils.restype = c_int + +if _libs[libname].has("rm_read_modbus_rtu_input_status", "cdecl"): + rm_read_modbus_rtu_input_status = _libs[libname].get("rm_read_modbus_rtu_input_status", "cdecl") + rm_read_modbus_rtu_input_status.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_read_params_t, POINTER(c_int)] + rm_read_modbus_rtu_input_status.restype = c_int + +if _libs[libname].has("rm_read_modbus_rtu_holding_registers", "cdecl"): + rm_read_modbus_rtu_holding_registers = _libs[libname].get("rm_read_modbus_rtu_holding_registers", "cdecl") + rm_read_modbus_rtu_holding_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_read_params_t, POINTER(c_int)] + rm_read_modbus_rtu_holding_registers.restype = c_int + +if _libs[libname].has("rm_write_modbus_rtu_registers", "cdecl"): + rm_write_modbus_rtu_registers = _libs[libname].get("rm_write_modbus_rtu_registers", "cdecl") + rm_write_modbus_rtu_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_write_params_t] + rm_write_modbus_rtu_registers.restype = c_int + +if _libs[libname].has("rm_read_modbus_rtu_input_registers", "cdecl"): + rm_read_modbus_rtu_input_registers = _libs[libname].get("rm_read_modbus_rtu_input_registers", "cdecl") + rm_read_modbus_rtu_input_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_rtu_read_params_t, POINTER(c_int)] + rm_read_modbus_rtu_input_registers.restype = c_int + +if _libs[libname].has("rm_read_modbus_tcp_coils", "cdecl"): + rm_read_modbus_tcp_coils = _libs[libname].get("rm_read_modbus_tcp_coils", "cdecl") + rm_read_modbus_tcp_coils.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_read_params_t, POINTER(c_int)] + rm_read_modbus_tcp_coils.restype = c_int + +if _libs[libname].has("rm_write_modbus_tcp_coils", "cdecl"): + rm_write_modbus_tcp_coils = _libs[libname].get("rm_write_modbus_tcp_coils", "cdecl") + rm_write_modbus_tcp_coils.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_write_params_t] + rm_write_modbus_tcp_coils.restype = c_int + +if _libs[libname].has("rm_read_modbus_tcp_input_status", "cdecl"): + rm_read_modbus_tcp_input_status = _libs[libname].get("rm_read_modbus_tcp_input_status", "cdecl") + rm_read_modbus_tcp_input_status.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_read_params_t, POINTER(c_int)] + rm_read_modbus_tcp_input_status.restype = c_int + +if _libs[libname].has("rm_read_modbus_tcp_holding_registers", "cdecl"): + rm_read_modbus_tcp_holding_registers = _libs[libname].get("rm_read_modbus_tcp_holding_registers", "cdecl") + rm_read_modbus_tcp_holding_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_read_params_t, POINTER(c_int)] + rm_read_modbus_tcp_holding_registers.restype = c_int + +if _libs[libname].has("rm_write_modbus_tcp_registers", "cdecl"): + rm_write_modbus_tcp_registers = _libs[libname].get("rm_write_modbus_tcp_registers", "cdecl") + rm_write_modbus_tcp_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_write_params_t] + rm_write_modbus_tcp_registers.restype = c_int + +if _libs[libname].has("rm_read_modbus_tcp_input_registers", "cdecl"): + rm_read_modbus_tcp_input_registers = _libs[libname].get("rm_read_modbus_tcp_input_registers", "cdecl") + rm_read_modbus_tcp_input_registers.argtypes = [POINTER(rm_robot_handle), rm_modbus_tcp_read_params_t, POINTER(c_int)] + rm_read_modbus_tcp_input_registers.restype = c_int + +if _libs[libname].has("rm_get_tool_action_list", "cdecl"): + rm_get_tool_action_list = _libs[libname].get( + "rm_get_tool_action_list", "cdecl") + rm_get_tool_action_list.argtypes = [POINTER(rm_robot_handle), c_int, c_int, String, + POINTER(rm_tool_action_list_t)] + rm_get_tool_action_list.restype = c_int + +if _libs[libname].has("rm_run_tool_action", "cdecl"): + rm_run_tool_action = _libs[libname].get("rm_run_tool_action", "cdecl") + rm_run_tool_action.argtypes = [POINTER(rm_robot_handle), String] + rm_run_tool_action.restype = c_int + +if _libs[libname].has("rm_delete_tool_action", "cdecl"): + rm_delete_tool_action = _libs[libname].get("rm_delete_tool_action", "cdecl") + rm_delete_tool_action.argtypes = [POINTER(rm_robot_handle), String] + rm_delete_tool_action.restype = c_int + +if _libs[libname].has("rm_save_tool_action", "cdecl"): + rm_save_tool_action = _libs[libname].get("rm_save_tool_action", "cdecl") + rm_save_tool_action.argtypes = [POINTER(rm_robot_handle), String, POINTER(c_int), c_int, c_int] + rm_save_tool_action.restype = c_int + +if _libs[libname].has("rm_update_tool_action", "cdecl"): + rm_update_tool_action = _libs[libname].get("rm_update_tool_action", "cdecl") + rm_update_tool_action.argtypes = [POINTER(rm_robot_handle), String, String, POINTER(c_int), c_int, c_int] + rm_update_tool_action.restype = c_int + +if _libs[libname].has("rm_set_avoid_singularity_mode", "cdecl"): + rm_set_avoid_singularity_mode = _libs[libname].get("rm_set_avoid_singularity_mode", "cdecl") + rm_set_avoid_singularity_mode.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_avoid_singularity_mode.restype = c_int + +if _libs[libname].has("rm_get_avoid_singularity_mode", "cdecl"): + rm_get_avoid_singularity_mode = _libs[libname].get("rm_get_avoid_singularity_mode", "cdecl") + rm_get_avoid_singularity_mode.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_avoid_singularity_mode.restype = c_int + +if _libs[libname].has("rm_set_collision_detection", "cdecl"): + rm_set_collision_detection = _libs[libname].get("rm_set_collision_detection", "cdecl") + rm_set_collision_detection.argtypes = [POINTER(rm_robot_handle), c_int] + rm_set_collision_detection.restype = c_int + +if _libs[libname].has("rm_get_collision_detection", "cdecl"): + rm_get_collision_detection = _libs[libname].get("rm_get_collision_detection", "cdecl") + rm_get_collision_detection.argtypes = [POINTER(rm_robot_handle), POINTER(c_int)] + rm_get_collision_detection.restype = c_int + +if _libs[libname].has("rm_movev_canfd", "cdecl"): + rm_movev_canfd = _libs[libname].get("rm_movev_canfd", "cdecl") + rm_movev_canfd.argtypes = [POINTER(rm_robot_handle), rm_movev_canfd_mode_t] + rm_movev_canfd.restype = c_int + +if _libs[libname].has("rm_set_movev_canfd_init", "cdecl"): + rm_set_movev_canfd_init = _libs[libname].get("rm_set_movev_canfd_init", "cdecl") + rm_set_movev_canfd_init.argtypes = [POINTER(rm_robot_handle), c_int, c_int, c_int] + rm_set_movev_canfd_init.restype = c_int + +if _libs[libname].has("rm_get_rm_plus_reg", "cdecl"): + rm_get_rm_plus_reg = _libs[libname].get("rm_get_rm_plus_reg", "cdecl") + rm_get_rm_plus_reg.argtypes = [POINTER(rm_robot_handle), c_int, c_int, POINTER(c_int)] + rm_get_rm_plus_reg.restype = c_int + +if _libs[libname].has("rm_set_rm_plus_reg", "cdecl"): + rm_set_rm_plus_reg = _libs[libname].get("rm_set_rm_plus_reg", "cdecl") + rm_set_rm_plus_reg.argtypes = [POINTER(rm_robot_handle), c_int, c_int, POINTER(c_int)] + rm_set_rm_plus_reg.restype = c_int + +try: + ARM_DOF = 7 +except: + pass + +try: + M_PI = 3.14159265358979323846 +except: + pass +# @endcond +# No inserted files + +# No prefix-stripping diff --git a/Robotic_Arm/rm_robot_interface.py b/Robotic_Arm/rm_robot_interface.py new file mode 100644 index 00000000..34025d54 --- /dev/null +++ b/Robotic_Arm/rm_robot_interface.py @@ -0,0 +1,6726 @@ +""" +@brief 机械臂Python接口 +@author Realman-Aisha +@date 2024-04-28 + +@details +此模块为机械臂提供了一个高易用性的Python接口,通过封装rm_ctypes_wrap模块中导入的C库接口实现。 +关键类:RoboticArm类,所有对机械臂的操作均通过此类进行。 + +**注意** +- 在使用前,请确保已经根据环境正确配置了c版本的API库。 +- 对于可能发生的异常,建议进行适当的错误处理。 +- 本模块依赖于rm_ctypes_wrap.py模块,该模块提供了对C语言API的封装。 + +**更新日志**: +- +""" + +from .rm_ctypes_wrap import * +import ctypes +from typing import Callable + + +class JointConfigSettings: + """ + 关节配置 + """ + + def rm_set_joint_max_speed(self, joint_num: int, speed: float) -> int: + """ + 设置指定关节的最大速度。 + + Args: + joint_num (int): 关节的序号,取值范围为1到7,表示机械臂上不同关节的编号。 + speed (float): 关节的最大转速,单位为度每秒(°/s),定义了关节在运动时所能达到的最大速度。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_max_speed(self.handle, joint_num, speed) + return tag + + def rm_set_joint_max_acc(self, joint_num: int, acc: float) -> int: + """ + 设置关节最大加速度 + + Args: + joint_num (int): 关节序号,1~7 + acc (float): 关节最大加速度,单位:°/s² + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + + tag = rm_set_joint_max_acc(self.handle, joint_num, acc) + return tag + + def rm_set_joint_min_pos(self, joint_num: int, min_pos: float) -> int: + """ + 设置关节最小限位 + + Args: + joint_num (int): 关节序号,1~7 + min_pos (float): 关节最小位置,单位:° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_min_pos(self.handle, joint_num, min_pos) + return tag + + def rm_set_joint_max_pos(self, joint_num: int, max_pos: float) -> int: + """ + 设置关节最大限位 + + Args: + joint_num (int): 关节序号,1~7 + max_pos (float): 关节最大位置,单位:° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_max_pos(self.handle, joint_num, max_pos) + return tag + + def rm_set_joint_drive_max_speed(self, joint_num: int, speed: float) -> int: + """ + 设置指定关节(驱动器)的最大速度。 + + Args: + joint_num (int): 关节的序号,取值范围为1到7,表示机械臂上不同关节的编号。 + speed (float): 关节的最大转速,单位为度每秒(°/s),定义了关节在运动时所能达到的最大速度。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_drive_max_speed(self.handle, joint_num, speed) + return tag + + def rm_set_joint_drive_max_acc(self, joint_num: int, acc: float) -> int: + """ + 设置关节(驱动器)最大加速度 + + Args: + joint_num (int): 关节序号,1~7 + acc (float): 关节最大加速度,单位:°/s² + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + + tag = rm_set_joint_drive_max_acc(self.handle, joint_num, acc) + return tag + + def rm_set_joint_drive_min_pos(self, joint_num: int, min_pos: float) -> int: + """ + 设置关节(驱动器)最小限位 + + Args: + joint_num (int): 关节序号,1~7 + min_pos (float): 关节最小位置,单位:° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_drive_min_pos(self.handle, joint_num, min_pos) + return tag + + def rm_set_joint_drive_max_pos(self, joint_num: int, max_pos: float) -> int: + """ + 设置关节(驱动器)最大限位 + + Args: + joint_num (int): 关节序号,1~7 + max_pos (float): 关节最大位置,单位:° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_joint_drive_max_pos(self.handle, joint_num, max_pos) + return tag + + def rm_set_joint_en_state(self, joint_num: int, en_state: int) -> int: + """ + 设置关节使能状态 + + Args: + joint_num (int): 关节序号 + en_state (int): 1:上使能 0:掉使能 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_joint_en_state(self.handle, joint_num, en_state) + return tag + + def rm_set_joint_zero_pos(self, joint_num: int) -> int: + """ + 设置关节零位 + + Args: + joint_num (int): 关节序号 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_joint_zero_pos(self.handle, joint_num) + return tag + + def rm_set_joint_clear_err(self, joint_num: int) -> int: + """ + 清除关节错误代码 + + Args: + joint_num (int): 关节序号 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_joint_clear_err(self.handle, joint_num) + return tag + + def rm_auto_set_joint_limit(self, mode: int) -> int: + """ + 一键设置关节限位 + + Args: + mode (int): 1-正式模式,各关节限位为规格参数中的软限位和硬件限位 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_auto_set_joint_limit(self.handle, mode) + return tag + + +class JointConfigReader: + """ + 关节配置查询 + """ + + def rm_get_joint_max_speed(self) -> tuple[int, list]: + """ + 查询关节最大速度 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最大速度值。 + """ + if self.arm_dof != 0: + speed = (c_float * self.arm_dof)() + else: + speed = (c_float * ARM_DOF)() + + ret = rm_get_joint_max_speed(self.handle, speed) + return ret, list(speed) + + def rm_get_joint_max_acc(self) -> tuple[int, list]: + """ + 查询关节最大加速度 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 各关节最大加速度值。 + """ + if self.arm_dof != 0: + acc = (c_float * self.arm_dof)() + else: + acc = (c_float * ARM_DOF)() + + ret = rm_get_joint_max_acc(self.handle, acc) + return ret, list(acc) + + def rm_get_joint_min_pos(self) -> tuple[int, list]: + """ + 查询关节最小限位 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最小位置数组,长度与机械臂的关节数,单位:°。 + """ + if self.arm_dof != 0: + min_pos = (c_float * self.arm_dof)() + else: + min_pos = (c_float * ARM_DOF)() + + ret = rm_get_joint_min_pos(self.handle, min_pos) + return ret, list(min_pos) + + def rm_get_joint_max_pos(self) -> tuple[int, list]: + """ + 查询关节最大限位 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最大位置数组,长度机械臂的关节数,单位:°。 + """ + if (self.arm_dof != 0): + max_pos = (c_float * self.arm_dof)() + else: + max_pos = (c_float * ARM_DOF)() + + ret = rm_get_joint_max_pos(self.handle, max_pos) + return ret, list(max_pos) + + def rm_get_joint_drive_max_speed(self) -> tuple[int, list]: + """ + 查询关节(驱动器)最大速度 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最大速度值。 + """ + if (self.arm_dof != 0): + speed = (c_float * self.arm_dof)() + else: + speed = (c_float * ARM_DOF)() + + ret = rm_get_joint_drive_max_speed(self.handle, speed) + return ret, list(speed) + + def rm_get_joint_drive_max_acc(self) -> tuple[int, list]: + """ + 查询关节(驱动器)最大加速度 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 各关节最大加速度值。 + """ + if (self.arm_dof != 0): + acc = (c_float * self.arm_dof)() + else: + acc = (c_float * ARM_DOF)() + + ret = rm_get_joint_drive_max_acc(self.handle, acc) + return ret, list(acc) + + def rm_get_joint_drive_min_pos(self) -> tuple[int, list]: + """ + 查询关节(驱动器)最小限位 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最小位置数组,长度与机械臂的关节数,单位:°。 + """ + if (self.arm_dof != 0): + min_pos = (c_float * self.arm_dof)() + else: + min_pos = (c_float * ARM_DOF)() + + ret = rm_get_joint_drive_min_pos(self.handle, min_pos) + return ret, list(min_pos) + + def rm_get_joint_drive_max_pos(self) -> tuple[int, list]: + """ + 查询关节(驱动器)最大限位 + Args: + 无。 + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节最大位置数组,长度机械臂的关节数,单位:°。 + """ + if (self.arm_dof != 0): + max_pos = (c_float * self.arm_dof)() + else: + max_pos = (c_float * ARM_DOF)() + + ret = rm_get_joint_drive_max_pos(self.handle, max_pos) + return ret, list(max_pos) + + def rm_get_joint_en_state(self) -> tuple[int, list]: + """ + 获取关节使能状态 + + Returns: + tuple[int, list]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 每个关节的使能状态数组,长度为机械臂的关节数,单位:°。 + """ + if (self.arm_dof != 0): + en_state = (uint8_t * self.arm_dof)() + else: + en_state = (uint8_t * ARM_DOF)() + + ret = rm_get_joint_en_state(self.handle, en_state) + return ret, list(en_state) + + def rm_get_joint_err_flag(self) -> dict[str, any]: + """ + 获取关节错误代码 + + Returns: + dict: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - 'err_flag' (list[int]): 整数列表,表示每个关节的错误标志。 + 如果arm_dof不为0,则列表长度为arm_dof;否则,使用默认的ARM_DOF长度。 + - 'brake_state' (list[int]): 整数列表,表示每个关节的抱闸状态。 + 如果arm_dof不为0,则列表长度为arm_dof;否则,使用默认的ARM_DOF长度。 + """ + if (self.arm_dof != 0): + err_flag = (uint16_t * self.arm_dof)() + brake_state = (uint16_t * self.arm_dof)() + else: + err_flag = (uint16_t * ARM_DOF)() + brake_state = (uint16_t * ARM_DOF)() + + ret = rm_get_joint_err_flag(self.handle, err_flag, brake_state) + + result_dict = { + 'return_code': ret, + 'err_flag': list(err_flag), + 'brake_state': list(brake_state), + } + + return result_dict + + +class ArmTipVelocityParameters: + """ + 机械臂运动参数 + """ + + def rm_set_arm_max_line_speed(self, speed: float) -> int: + """ + 设置机械臂末端最大线速度 + + Args: + speed (float): 末端最大线速度,单位m/s + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_arm_max_line_speed(self.handle, speed) + return tag + + def rm_set_arm_max_line_acc(self, acc: float) -> int: + """ + 设置机械臂末端最大线加速度 + + Args: + acc (float): 末端最大线加速度,单位m/s^2 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_arm_max_line_acc(self.handle, acc) + return tag + + def rm_set_arm_max_angular_speed(self, speed: float) -> int: + """ + 设置机械臂末端最大角速度 + + Args: + speed (float): 末端最大角速度,单位rad/s + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_arm_max_angular_speed(self.handle, speed) + return tag + + def rm_set_arm_max_angular_acc(self, acc: float) -> int: + """ + 设置机械臂末端最大角加速度 + + Args: + acc (float): 末端最大角加速度,单位rad/s^2 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据格式不正确或无法识别。 + """ + tag = rm_set_arm_max_angular_acc(self.handle, acc) + return tag + + def rm_set_arm_tcp_init(self) -> int: + """ + 设置机械臂末端参数为默认值 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_tcp_init(self.handle) + return tag + + def rm_set_collision_state(self, stage: int) -> int: + """ + 设置机械臂动力学碰撞检测等级 + + Args: + stage (int): 等级:0~8,0-无碰撞,8-碰撞最灵敏 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_collision_state(self.handle, stage) + return tag + + def rm_get_collision_stage(self) -> tuple[int, int]: + """ + 查询碰撞防护等级 + + Returns: + tuple[int,int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 等级,范围:0~8. + """ + stage = c_int() + ret = rm_get_collision_stage(self.handle, byref(stage)) + return ret, stage.value + + def rm_get_arm_max_line_speed(self) -> tuple[int, float]: + """ + 获取机械臂末端最大线速度 + + Returns: + tuple[int,float]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - float: 末端最大线速度,单位m/s. + """ + speed = c_float() + ret = rm_get_arm_max_line_speed(self.handle, byref(speed)) + return ret, speed.value + + def rm_get_arm_max_line_acc(self) -> tuple[int, float]: + """ + 获取机械臂末端最大线加速度 + + Returns: + tuple[int,float]: 包含两个元素的元组。 + + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - float: 末端最大线加速度,单位m/s^2. + """ + acc = c_float() + ret = rm_get_arm_max_line_acc(self.handle, byref(acc)) + return ret, acc.value + + def rm_get_arm_max_angular_speed(self) -> tuple[int, float]: + """ + 获取机械臂末端最大角速度 + + Returns: + tuple[int,float]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - float: 末端最大角速度,单位rad/s. + """ + speed = c_float() + ret = rm_get_arm_max_angular_speed(self.handle, byref(speed)) + return ret, speed.value + + def rm_get_arm_max_angular_acc(self) -> tuple[int, float]: + """ + 获取机械臂末端最大角加速度 + + Returns: + tuple[int,float]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - float: 末端最大角加速度,单位rad/s^2. + """ + acc = c_float() + ret = rm_get_arm_max_angular_acc(self.handle, byref(acc)) + return ret, acc.value + + def rm_set_DH_data_default(self) -> int: + """ + 恢复机械臂默认 DH 参数 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_DH_data_default(self.handle) + return tag + + def rm_set_DH_data(self, DH_data: rm_dh_t) -> int: + """ + 设置DH参数 + + Args: + DH_data (rm_dh_t): DH参数 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_DH_data(self.handle, DH_data) + return tag + + def rm_get_DH_data(self) -> tuple[int, rm_dh_t]: + """ + 获取DH参数 + Returns: + tuple[int,rm_dh_t]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - rm_dh_t: DH参数。 + """ + DH_data = rm_dh_t() + ret = rm_get_DH_data(self.handle, DH_data) + return ret, DH_data.to_dict(self.dh_dof) + +class ToolCoordinateConfig: + """ + 工具坐标系 + """ + + def rm_set_auto_tool_frame(self, point_num: int) -> int: + """ + 六点法自动设置工具坐标系 标记点位 + + Args: + point_num (int): 1~6代表6个标定点 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_auto_tool_frame(self.handle, point_num) + return tag + + def rm_generate_auto_tool_frame(self, tool_name: str, payload: float, x: float, y: float, z: float) -> int: + """ + 六点法自动设置工具坐标系 提交 + + Args: + tool_name (str): 工具坐标系名称,不能超过十个字节。 + payload (float):新工具执行末端负载重量 单位kg + x (float): 新工具执行末端负载位置 位置x 单位m + y (float): 新工具执行末端负载位置 位置y 单位m + z (float): 新工具执行末端负载位置 位置z 单位m + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_generate_auto_tool_frame( + self.handle, tool_name, payload, x, y, z) + return tag + + def rm_set_manual_tool_frame(self, frame: rm_frame_t) -> int: + """ + 手动设置工具坐标系 + + Args: + frame (rm_frame_t): 新工具坐标系参数结构体 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_manual_tool_frame(self.handle, frame) + return tag + + def rm_change_tool_frame(self, tool_name: str) -> int: + """ + 切换当前工具坐标系 + + Args: + tool_name (str): 目标工具坐标系名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_change_tool_frame(self.handle, tool_name) + return tag + + def rm_delete_tool_frame(self, tool_name: str) -> int: + """ + 删除指定工具坐标系 + + Args: + tool_name (str): 要删除的工具坐标系名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_delete_tool_frame(self.handle, tool_name) + return tag + + def rm_update_tool_frame(self, frame: rm_frame_t) -> int: + """ + 修改指定工具坐标系 + + Args: + frame (rm_frame_t): 要修改的工具坐标系名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_update_tool_frame(self.handle, frame) + return tag + + def rm_get_total_tool_frame(self) -> dict[str, any]: + """ + 获取所有工具坐标系名称 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'tool_names' (list[str]): 字符串列表,表示所有工具坐标系名称。 + - 'len' (int): 工具坐标系名称数量。 + """ + names = (rm_frame_name_t*10)() + len_ = c_int() + ret = rm_get_total_tool_frame(self.handle, names, byref(len_)) + tool_names = [names[i].name.decode('utf-8') for i in range(len_.value)] + + result_dict = { + 'return_code': ret, + 'tool_names': tool_names, + 'len': len_.value, + } + + return result_dict + + def rm_get_given_tool_frame(self, tool_name: str) -> tuple[int, dict[str, any]]: + """ + 获取指定工具坐标系 + + Args: + tool_name (str): 工具坐标系名称。 + + Returns: + tuple: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict: 工具坐标系字典,键为rm_frame_t的参数名。 + """ + tool_frame = rm_frame_t() + ret = rm_get_given_tool_frame( + self.handle, tool_name, byref(tool_frame)) + + return ret, tool_frame.to_dictionary() + + def rm_get_current_tool_frame(self) -> tuple[int, dict[str, any]]: + """ + 获取当前工具坐标系。 + + Args: + 无。 + + Returns: + tuple: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict: 工具坐标系字典,键为rm_frame_t的参数名。 + """ + tool_frame = rm_frame_t() + ret = rm_get_current_tool_frame(self.handle, byref(tool_frame)) + + return ret, tool_frame.to_dictionary() + + def rm_set_tool_envelope(self, envelope: rm_envelope_balls_list_t) -> int: + """ + 设置工具坐标系的包络参数 + + Args: + envelope (rm_envelope_balls_list_t): 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + ret = rm_set_tool_envelope(self.handle, envelope) + return ret + + def rm_get_tool_envelope(self, tool_name: str) -> tuple[int, dict[str, any]]: + """ + 获取工具坐标系的包络参数 + + Args: + tool_name (string): 工具坐标系名称 + + Returns: + tuple: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回设置失败,可能是参数错误或控制器发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等。 + - dict: 包络参数字典,包含了工具坐标系的包络参数信息。 + """ + envelope_balls = rm_envelope_balls_list_t() + ret = rm_get_tool_envelope( + self.handle, tool_name, byref(envelope_balls)) + + return ret, envelope_balls.to_dictionary() + + +class WorkCoordinateConfig: + """ + 工作坐标系 + """ + + def rm_set_auto_work_frame(self, name: str, point_num: int) -> int: + """ + 三点法自动设置工作坐标系 + + Args: + name (str): 工作坐标系名称,不能超过十个字节。 + point_num (int): 1~3代表3个标定点,依次为原点、X轴一点、Y轴一点,4代表生成坐标系。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_auto_work_frame(self.handle, name, point_num) + return tag + + def rm_set_manual_work_frame(self, name: str, pose: list) -> int: + """ + 手动设置工作坐标系 + + Args: + name (str): 工作坐标系名称,不能超过十个字节。 + pose (list): 新工作坐标系相对于基坐标系的位姿 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + frame_pose = rm_pose_t() + frame_pose.position = rm_position_t(*pose[:3]) + frame_pose.euler = rm_euler_t(*pose[3:]) + tag = rm_set_manual_work_frame(self.handle, name, frame_pose) + return tag + + def rm_change_work_frame(self, tool_name: str) -> int: + """ + 切换当前工作坐标系 + + Args: + tool_name (str): 目标工作坐标系名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_change_work_frame(self.handle, tool_name) + return tag + + def rm_delete_work_frame(self, tool_name: str) -> int: + """ + 删除指定工作坐标系 + + Args: + tool_name (str): 要删除的工作坐标系名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_delete_work_frame(self.handle, tool_name) + return tag + + def rm_update_work_frame(self, name: str, pose: list) -> int: + """ + 修改指定工作坐标系 + + Args: + name (str): 指定工具坐标系名称 + pose (list): 更新工作坐标系相对于基坐标系的位姿 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + frame_pose = rm_pose_t() + frame_pose.position = rm_position_t(*pose[:3]) + frame_pose.euler = rm_euler_t(*pose[3:]) + tag = rm_update_work_frame(self.handle, name, frame_pose) + return tag + + def rm_get_total_work_frame(self) -> dict[str, any]: + """ + 获取所有工作坐标系名称 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'tool_names' (list[str]): 字符串列表,表示所有工作坐标系名称。 + - 'len' (int): 工作坐标系名称数量。 + """ + len_ = c_int() + names = (rm_frame_name_t*10)() + ret = rm_get_total_work_frame(self.handle, names, byref(len_)) + work_names = [names[i].name.decode('utf-8') for i in range(len_.value)] + result_dict = { + 'return_code': ret, + 'work_names': work_names, + 'len': len_.value, + } + + return result_dict + + def rm_get_given_work_frame(self, name: str) -> tuple[int, list[float]]: + """ + 获取指定工作坐标系 + + Args: + name (str): 指定的工作坐标系名称 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - list: 工作坐标系位姿列表。 + """ + work_frame = rm_pose_t() + ret = rm_get_given_work_frame(self.handle, name, byref(work_frame)) + position = work_frame.position + euler = work_frame.euler + return ret, [position.x, position.y, position.z, euler.rx, euler.ry, euler.rz] + + def rm_get_current_work_frame(self) -> tuple[int, dict[str, any]]: + """ + 获取当前工作坐标系 + + Returns: + tuple[int, dict[str, any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict: 工作坐标系字典,键为rm_frame_t的参数名。 + """ + frame = rm_frame_t() + ret = rm_get_current_work_frame(self.handle, byref(frame)) + + return ret, frame.to_dictionary() + + +class ArmState: + """ + 机械臂状态获取 + """ + + def rm_get_current_arm_state(self) -> tuple[int, dict[str, any]]: + """ + 获取机械臂当前状态 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict: 机械臂当前状态字典,键为rm_current_arm_state_t的参数名。 + """ + state = rm_current_arm_state_t() + ret = rm_get_current_arm_state(self.handle, byref(state)) + + return ret, state.to_dictionary(self.arm_dof if self.arm_dof != 0 else ARM_DOF) + + def rm_get_current_joint_temperature(self) -> tuple[int, list[float]]: + """ + 获取关节当前温度 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节1~7温度数组,单位:℃ + """ + if self.arm_dof != 0: + temperature = (c_float * self.arm_dof)() + else: + temperature = (c_float * ARM_DOF)() + + ret = rm_get_current_joint_temperature(self.handle, temperature) + return ret, list(temperature) + + def rm_get_current_joint_current(self) -> tuple[int, list[float]]: + """ + 获取关节当前电流 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节1~7电流数组,单位:mA + """ + if self.arm_dof != 0: + current = (c_float * self.arm_dof)() + else: + current = (c_float * ARM_DOF)() + + ret = rm_get_current_joint_current(self.handle, current) + return ret, list(current) + + def rm_get_current_joint_voltage(self) -> tuple[int, list[float]]: + """ + 获取关节当前电压 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 关节1~7电压数组,单位:V + """ + if self.arm_dof != 0: + voltage = (c_float * self.arm_dof)() + else: + voltage = (c_float * ARM_DOF)() + + ret = rm_get_current_joint_voltage(self.handle, voltage) + return ret, list(voltage) + + def rm_set_init_pose(self, joint: list[float]) -> int: + """ + 设置机械臂的初始位置角度 + + Args: + joint (list[float]): 机械臂初始位置关节角度数组 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + if self.arm_dof != 0: + joint_position = (c_float * self.arm_dof)(*joint) + else: + joint_position = (c_float * ARM_DOF)(*joint) + + tag = rm_set_init_pose(self.handle, joint_position) + + return tag + + def rm_get_init_pose(self) -> tuple[int, list[float]]: + """ + 获取机械臂初始位置角度 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 机械臂初始位置关节角度数组,单位:° + """ + if self.arm_dof != 0: + joint_position = (c_float * self.arm_dof)() + else: + joint_position = (c_float * ARM_DOF)() + + ret = rm_get_init_pose(self.handle, joint_position) + return ret, list(joint_position) + + def rm_get_joint_degree(self) -> tuple[int, list[float]]: + """ + 获取当前关节角度 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list: 当前7个关节的角度数组,单位:° + """ + if self.arm_dof != 0: + joint_degree = (c_float * self.arm_dof)() + else: + joint_degree = (c_float * ARM_DOF)() + + ret = rm_get_joint_degree(self.handle, joint_degree) + return ret, list(joint_degree) + + def rm_get_arm_all_state(self) -> tuple[int, dict[str, any]]: + """ + 获取机械臂所有状态信息 + + Returns: + tuple[int, dict[str, any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict: 机械臂所有状态信息字典,键为rm_arm_all_state_t的参数名。 + """ + joint_status = rm_arm_all_state_t() + + tag = rm_get_arm_all_state(self.handle, joint_status) + + return tag, joint_status.to_dictionary() + + def rm_get_controller_rs485_mode(self) -> dict[str, any]: + """ + 查询控制器RS485模式 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + - 'mode' (int): 0-代表默认 RS485 串行通讯,1-代表 modbus-RTU 主站模式,2-代表 modbus-RTU 从站模式; + - 'baudrate' (int): 波特率 + - 'timeout' (int): modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + """ + mode = c_int() + baudrate = c_int() + timeout = c_int() + + ret = rm_get_controller_RS485_mode( + self.handle, byref(mode), byref(baudrate), byref(timeout)) + + # 创建一个字典来存储返回值 + result_dict = { + 'return_code': ret, + 'mode': mode.value, + 'baudrate': baudrate.value, + 'timeout': timeout.value, + } + + return result_dict + + def rm_get_tool_rs485_mode(self) -> dict[str, any]: + """ + 查询工具端 RS485 模式 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + - 'mode' (int): 0-代表默认 RS485 串行通讯 1-代表 modbus-RTU 主站模式 + - 'baudrate' (int): 波特率 + - 'timeout' (int): modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + """ + mode = c_int() + baudrate = c_int() + timeout = c_int() + + ret = rm_get_tool_RS485_mode(self.handle, byref( + mode), byref(baudrate), byref(timeout)) + + # 创建一个字典来存储返回值 + result_dict = { + 'return_code': ret, + 'mode': mode.value, + 'baudrate': baudrate.value, + 'timeout': timeout.value, + } + + return result_dict + + def rm_set_avoid_singularity_mode(self, mode: int) -> int: + """ + 设置避奇异模式 + + Args: + mode: 模式 0-不规避奇异点,1-规避奇异点 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + + tag = rm_set_avoid_singularity_mode(self.handle, mode) + + return tag + + def rm_get_avoid_singularity_mode(self) -> tuple[int, int]: + """ + 获取避奇异模式 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 当前避奇异模式 0-不规避奇异点,1-规避奇异点 + """ + mode = c_int() + ret = rm_get_avoid_singularity_mode(self.handle, byref(mode)) + return ret, mode.value + + def rm_set_collision_detection(self, mode: int) -> int: + """ + 设置静止状态碰撞检测开关(三代控制器) + + Args: + mode: 碰撞检测模式,0-关闭,1-开启 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_collision_detection(self.handle, mode) + return tag + + def rm_get_collision_detection(self) -> tuple[int, int]: + """ + 查询碰撞防护等级 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码(含义同set方法)。 + - int: 碰撞检测模式,0-关闭,1-开启。 + """ + mode = c_int() + ret = rm_get_collision_detection(self.handle, byref(mode)) + return ret, mode.value + + +class MovePlan: + """ + 机械臂轨迹规划指令 + """ + + def rm_movej(self, joint: list[float], v: int, r: int, connect: int, block: int) -> int: + """ + 关节空间运动 + + Args: + joint (list): 各关节目标角度数组,单位:° + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)(*joint) + else: + joint_positions = (c_float * ARM_DOF)(*joint) + + tag = rm_movej(self.handle, joint_positions, v, r, connect, block) + + return tag + + def rm_movel(self, pose: list[float], v: int, r: int, connect: int, block: int) -> int: + """ + 笛卡尔空间直线运动 + + Args: + pose (list[float]): 目标位姿,位置单位:米,姿态单位:弧度 + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.euler = rm_euler_t(*pose[3:]) + + tag = rm_movel(self.handle, po1, v, r, connect, block) + + return tag + + def rm_movel_offset(self, offset: list[float], v: int, r: int, connect: int, frame_type: int, block: int) -> int: + """ + 笛卡尔空间直线偏移运动 (四代控制器支持) + + 该函数用于机械臂末端在当前位姿的基础上沿某坐标系(工具或工作)进行位移或旋转运动。 + + Args: + offset (list[float]): 位置姿态偏移,位置单位:米,姿态单位:弧度 + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + frame_type (int): 坐标系类型 + - 0:工作坐标系 + - 1:工具坐标系 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + - -7: 三代控制器不支持该接口。 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*offset[:3]) + po1.euler = rm_euler_t(*offset[3:]) + + tag = rm_movel_offset(self.handle, po1, v, r, connect, frame_type, block) + + return tag + + def rm_moves(self, pose: list[float], v: int, r: int, connect: int, block: int) -> int: + """ + 样条曲线运动 + + Args: + pose (list[float]): 目标位姿,位置单位:米,姿态单位:弧度 + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + **注意** + 样条曲线运动需至少连续下发三个点位(trajectory_connect设置为1),否则运动轨迹为直线。 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.euler = rm_euler_t(*pose[3:]) + + tag = rm_moves(self.handle, po1, v, r, connect, block) + + return tag + + def rm_movec(self, pose_via: list[float], pose_to: list[float], v: int, r: int, loop: int, connect: int, block: int) -> int: + """ + 笛卡尔空间圆弧运动 + + Args: + pose_via (list[float]): 中间点位姿,位置单位:米,姿态单位:弧度 + pose_to (list[float]): 终点位姿,位置单位:米,姿态单位:弧度 + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + loop (int): 规划圈数. + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*pose_via[:3]) + po1.euler = rm_euler_t(*pose_via[3:]) + + po2 = rm_pose_t() + po2.position = rm_position_t(*pose_to[:3]) + po2.euler = rm_euler_t(*pose_to[3:]) + tag = rm_movec(self.handle, po1, po2, v, r, loop, connect, block) + + return tag + + def rm_movej_p(self, pose: list[float], v: int, r: int, connect: int, block: int) -> int: + """ + 该函数用于关节空间运动到目标位姿 + + Args: + pose (list[float]): 目标位姿,位置单位:米,姿态单位:弧度。 + v (int): 速度百分比系数,1~100 + r (int, optional): 交融半径百分比系数,0~100。 + connect (int): 轨迹连接标志 + - 0:立即规划并执行轨迹,不与后续轨迹连接。 + - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.euler = rm_euler_t(*pose[3:]) + + tag = rm_movej_p(self.handle, po1, v, r, connect, block) + + return tag + + def rm_set_movev_canfd_init(self, avoid_singularity_flag: int, frame_type: int, dt: int) -> int: + """ + 笛卡尔速度透传初始化 + + Args: + avoid_singularity_flag: 是否避奇异,1-开启,0-关闭。 + frame_type: 参考坐标系,1-工作坐标系,0-工具坐标系。 + dt: 周期(单位:ms)。 + + Returns: + int: 函数执行的状态码(含义同前)。 + """ + tag = rm_set_movev_canfd_init(self.handle, avoid_singularity_flag, frame_type, dt) + return tag + + def rm_movev_canfd(self, cartesian_velocity: list[float], follow: bool, trajectory_mode: int = 0, radio: int = 0) -> int: + """ + 角度透传(CANFD 模式)- 严格匹配 ctypes 接口定义 + + Args: + cartesian_velocity (POINTER(c_float * 6)):(6个元素,对应x、y、z、rx、ry、rz),单位:m/s(平移)、rad/s(旋转),线速度最大值:0.250m/s,角速度最大值:0.6rad/s) + follow: 驱动器跟随效果,True-高跟随,False-低跟随。 + trajectory_mode: 高跟随模式类型,0-完全透传,1-曲线拟合,2-滤波。 + radio: 模式参数(平滑系数/滤波参数,需参考模式类型)。 + + Returns: + int: 函数执行的状态码(含义同前)。 + """ + config = rm_movev_canfd_mode_t() + cartesian_velocity_array = (c_float * 6)(*cartesian_velocity) + config.cartesian_velocity = ctypes.pointer(cartesian_velocity_array) + config.follow = follow + config.trajectory_mode = trajectory_mode + config.radio = radio + + tag = rm_movev_canfd(self.handle, config) + + return tag + + def rm_movej_canfd(self, joint: list[float], follow: bool, expand: float = 0, trajectory_mode: int = 0, radio: int = 0) -> int: + """ + 角度不经规划,直接通过CANFD透传给机械臂 + @details 角度透传到 CANFD,若指令正确,机械臂立即执行 + 备注: + 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + I系列有线网口周期最快可达2ms,提供了更高的实时性。 + Args: + joint (list[float]): 关节1~7目标角度数组,单位:° + follow (bool): true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + expand (float, optional): 如果存在通用扩展轴,并需要进行透传,可使用该参数进行透传发送。Defaults to 0. + trajectory_mode (int): 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + radio (int): 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),曲线拟合模式下取值范围0~100,滤波模式下取值范围0~999 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + """ + config = rm_movej_canfd_mode_t() + joint_array = (c_float * 7)(*joint) + config.joint = ctypes.pointer(joint_array) + config.follow = follow + config.expand = expand + config.trajectory_mode = trajectory_mode + config.radio = radio + + tag = rm_movej_canfd(self.handle, config) + + return tag + + def rm_movep_canfd(self, pose: list[float], follow: bool, trajectory_mode: int = 0, radio: int = 0) -> int: + """ + 位姿不经规划,直接通过CANFD透传给机械臂 + @details 当目标位姿被透传到机械臂控制器时,控制器首先尝试进行逆解计算。 + 若逆解成功且计算出的各关节角度与当前角度差异不大,则直接下发至关节执行,跳过额外的轨迹规划步骤。 + 这一特性适用于需要周期性调整位姿的场景,如视觉伺服等应用。 + 备注: + 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + I系列有线网口周期最快可达2ms,提供了更高的实时性。 + Args: + pose (list[float]): 位姿 (若位姿列表长度为7则认为使用四元数表达位姿,长度为6则认为使用欧拉角表达位姿) + follow (bool): true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + trajectory_mode (int): 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + radio (int): 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),曲线拟合模式下取值范围0~100,滤波模式下取值范围0~999 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + """ + config = rm_movep_canfd_mode_t() + config.pose.position = rm_position_t(*pose[:3]) + # 四元数 + if len(pose) == 7: + config.pose.quaternion = rm_quat_t(*pose[3:]) + # 欧拉角 + elif len(pose) == 6: + config.pose.euler = rm_euler_t(*pose[3:]) + else: + print("Error: pose length is error.") + config.follow = follow + config.trajectory_mode = trajectory_mode + config.radio = radio + + tag = rm_movep_canfd(self.handle, config) + + return tag + + def rm_movej_follow(self, joint: list[float]) -> int: + """ + 关节空间跟随运动 + + Args: + joint (list[float]): 关节1~7目标角度数组,单位:° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + """ + if self.arm_dof != 0 and self.arm_dof == len(joint): + joint_positions = (c_float * self.arm_dof)(*joint) + else: + joint_positions = (c_float * ARM_DOF)(*joint) + + tag = rm_movej_follow(self.handle, joint_positions) + + return tag + + def rm_movep_follow(self, pose: list[float]) -> int: + """ + 笛卡尔空间跟随运动 + + Args: + pose (list[float]): 位姿 (若位姿列表长度为7则认为使用四元数表达位姿,长度为6则认为使用欧拉角表达位姿) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + """ + po1 = rm_pose_t() + + po1.position = rm_position_t(*pose[:3]) + # 四元数 + if len(pose) == 7: + po1.quaternion = rm_quat_t(*pose[3:]) + # 欧拉角 + elif len(pose) == 6: + po1.euler = rm_euler_t(*pose[3:]) + else: + print("Error: pose length is error.") + + tag = rm_movep_follow(self.handle, po1) + + return tag + + +class ArmTeachMove: + """ + 机械臂示教及步进运动 + """ + + def rm_set_joint_step(self, num: int, step: float, v: int, block: int) -> int: + """ + 关节步进 + + Args: + num (int): 关节序号,1~7 + step (float): 步进的角度, + v (int): 速度百分比系数,1~100 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + tag = rm_set_joint_step(self.handle, num, step, v, block) + return tag + + def rm_set_pos_step(self, teach_type: rm_pos_teach_type_e, step: float, v: int, block: int) -> int: + """ + 当前工作坐标系下,位置步进 + + Args: + teach_type (rm_pos_teach_type_e): 示教类型 + step (float): 步进的距离,单位m,精确到0.001mm + v (int): 速度百分比系数,1~100 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + tag = rm_set_pos_step(self.handle, teach_type, step, v, block) + return tag + + def rm_set_ort_step(self, teach_type: rm_ort_teach_type_e, step: float, v: int, block: int) -> int: + """ + 当前工作坐标系下,姿态步进 + + Args: + teach_type (rm_ort_teach_type_e): 示教类型 + step (float): 步进的弧度,单位rad,精确到0.001rad + v (int): 速度百分比系数,1~100 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + """ + tag = rm_set_ort_step(self.handle, teach_type, step, v, block) + return tag + + def rm_set_joint_teach(self, num: int, direction: int, v: int) -> int: + """ + 关节示教 + + Args: + num (int): 示教关节的序号,1~7 + direction (int): 示教方向,0-负方向,1-正方向 + v (int): 速度百分比系数,1~100 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_joint_teach(self.handle, num, direction, v) + return tag + + def rm_set_pos_teach(self, teach_type: rm_pos_teach_type_e, direction: int, v: int) -> int: + """ + 当前工作坐标系下,笛卡尔空间位置示教 + + Args: + teach_type (rm_pos_teach_type_e): 示教类型 + direction (int): 示教方向,0-负方向,1-正方向 + v (int): 即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_pos_teach(self.handle, teach_type, direction, v) + return tag + + def rm_set_ort_teach(self, teach_type: rm_ort_teach_type_e, direction: int, v: int) -> int: + """ + 当前工作坐标系下,笛卡尔空间姿态示教 + + Args: + teach_type (rm_ort_teach_type_e): 示教类型 + direction (int): 示教方向,0-负方向,1-正方向 + v (int): 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_ort_teach(self.handle, teach_type, direction, v) + return tag + + def rm_set_stop_teach(self) -> int: + """ + 示教停止 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_stop_teach(self.handle) + return tag + + def rm_set_teach_frame(self, frame_type: int) -> int: + """ + 切换示教运动坐标系 + + Args: + frame_type (int): 0: 工作坐标系运动, 1: 工具坐标系运动 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_teach_frame(self.handle, frame_type) + return tag + + def rm_get_teach_frame(self) -> tuple[int, int]: + """ + 获取示教参考坐标系 + + Returns: + tuple[int,int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 0: 工作坐标系运动, 1: 工具坐标系运动 + """ + frame_type = c_int() + tag = rm_get_teach_frame(self.handle, byref(frame_type)) + return tag, frame_type.value + + +class ArmMotionControl: + """ + 机械臂运动的急停、暂停、继续等控制 + """ + + def rm_set_arm_slow_stop(self) -> int: + """ + 轨迹缓停,在当前正在运行的轨迹上停止 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_slow_stop(self.handle) + return tag + + def rm_set_arm_stop(self) -> int: + """ + 轨迹急停,关节最快速度停止,轨迹不可恢复 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_stop(self.handle) + return tag + + def rm_set_arm_pause(self) -> int: + """ + 轨迹暂停,暂停在规划轨迹上,轨迹可恢复 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_pause(self.handle) + return tag + + def rm_set_arm_continue(self) -> int: + """ + 轨迹暂停后,继续当前轨迹运动 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_continue(self.handle) + return tag + + def rm_set_delete_current_trajectory(self) -> int: + """ + 清除当前轨迹 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_delete_current_trajectory(self.handle) + return tag + + def rm_set_arm_delete_trajectory(self) -> int: + """ + 清除所有轨迹 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_delete_trajectory(self.handle) + return tag + + def rm_get_arm_current_trajectory(self) -> dict[str, any]: + """ + 获取当前正在规划的轨迹信息 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'trajectory_type' (rm_arm_current_trajectory_e): 返回的规划类型 + - 'data' (list[float]): 无规划和关节空间规划为当前关节1~7角度数组;笛卡尔空间规划则为当前末端位姿 + """ + plan_type = c_int() + + if self.arm_dof != 0: + data = (c_float * self.arm_dof)() + else: + data = (c_float * ARM_DOF)() + tag = rm_get_arm_current_trajectory( + self.handle, byref(plan_type), data) + + # 创建一个字典来存储返回值 + result_dict = { + 'return_code': tag, + 'trajectory_type': plan_type.value, + 'data': list(data), + } + + return result_dict + + +class ControllerConfig: + """ + 系统配置 + """ + + def rm_get_controller_state(self) -> dict[str, any]: + """ + 获取控制器状态 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'voltage' (float): 返回的电压 + - 'current' (float): 返回的电流 + - 'temperature' (float): 返回的温度 + - 'sys_err' (int): 控制器运行错误代码 + """ + voltage = c_float() + current = c_float() + temperature = c_float() + sys_err = c_int() + ret = rm_get_controller_state(self.handle, byref(voltage), byref(current), + byref(temperature), byref(sys_err)) + + # 创建一个字典来存储返回值 + result_dict = { + 'return_code': ret, + 'voltage': voltage.value, + 'current': current.value, + 'temperature': temperature.value, + 'system_error': sys_err.value, + } + + return result_dict + + def rm_set_arm_power(self, power: int) -> int: + """ + 设置机械臂电源 + + Args: + power (int): 1-上电状态,0 断电状态 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_arm_power(self.handle, power) + return tag + + def rm_get_arm_power_state(self) -> tuple[int, int]: + """ + 读取机械臂电源状态 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 获取到的机械臂电源状态,1-上电状态,0 断电状态 + """ + power = c_int() + tag = rm_get_arm_power_state(self.handle, byref(power)) + return tag, power.value + + def rm_get_system_runtime(self) -> dict[str, any]: + """ + 读取控制器的累计运行时间 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'day' (int): 读取到的时间 + - 'hour' (int): 读取到的时间 + - 'min' (int): 读取到的时间 + - 'sec' (int): 读取到的时间 + """ + day = c_int() + hour = c_int() + min = c_int() + sec = c_int() + + ret = rm_get_system_runtime(self.handle, byref( + day), byref(hour), byref(min), byref(sec)) + result_dict = { + 'return_code': ret, + 'day': day.value, + 'hour': hour.value, + 'min': min.value, + 'sec': sec.value, + } + + return result_dict + + def rm_clear_system_runtime(self) -> int: + """ + 清零控制器的累计运行时间 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_clear_system_runtime(self.handle) + return tag + + def rm_get_joint_odom(self) -> tuple[int, list[float]]: + """ + 读取关节的累计转动角度 + + Returns: + tuple[int, list[float]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list[float]: 各关节累计的转动角度,单位:度 + """ + if self.arm_dof != 0: + joint_odom = (c_float * self.arm_dof)() + else: + joint_odom = (c_float * ARM_DOF)() + + ret = rm_get_joint_odom(self.handle, joint_odom) + return ret, list(joint_odom) + + def rm_clear_joint_odom(self) -> int: + """ + 清零关节累计转动的角度 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_clear_joint_odom(self.handle) + return tag + + def rm_get_arm_software_info(self) -> tuple[int, dict[str, any]]: + """ + 读取机械臂软件信息 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str,any]: 机械臂软件版本信息字典,键为rm_arm_software_version_t结构体的字段名称 + """ + version = rm_arm_software_version_t() + ret = rm_get_arm_software_info(self.handle, byref(version)) + + return ret, version.to_dict(self.robot_controller_version) + + def rm_set_NetIP(self, ip: str, netmask: str, gw: str) -> int: + """ + 配置有线网口 IP 地址 + + Args: + ip (str): 有线网口 IP 地址 + netmask(str): 有线网口子网掩码 + gw(str): 有线网口网关地址 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_NetIP(self.handle, ip, netmask, gw) + return tag + + def rm_clear_system_err(self) -> int: + """ + 清除系统错误 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_clear_system_err(self.handle) + return tag + + +class CommunicationConfig: + """ + 配置通讯内容 + + @details 机械臂控制器可通过网口、WIFI、RS232-USB 接口和 RS485 接口与用户通信,用户使用时无需切换,可使用上述任一接口, + 控制器收到指令后,若指令格式正确,则会通过相同的接口反馈数据。 + """ + + def rm_set_wifi_ap(self, wifi_name: str, password: str) -> int: + """ + 配置 wifiAP 模式 + + Args: + wifi_name (str): wifi名称 + password (str): wifi密码 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_wifi_ap(self.handle, wifi_name, password) + return tag + + def rm_set_wifi_sta(self, router_name: str, password: str) -> int: + """ + 配置WiFi STA模式 + + Args: + router_name (str): 路由器名称 + password (str): 路由器Wifi密码 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_wifi_sta(self.handle, router_name, password) + return tag + + def rm_set_RS485(self, baudrate: int) -> int: + """ + 控制器RS485接口波特率设置,设置成功后蜂鸣器响 + + Args: + baudrate (int): 波特率:9600,19200,38400,115200和460800,若用户设置其他数据,控制器会默认按照460800处理。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 四代不支持该接口 + """ + tag = rm_set_RS485(self.handle, baudrate) + return tag + + def rm_get_wired_net(self) -> dict[str, any]: + """ + 获取有线网卡信息,未连接有线网卡则会返回无效数据 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'ip' (str): 网络地址 + - 'mask' (str): 子网掩码 + - 'mac' (str): MAC地址 + """ + ip = ctypes.create_string_buffer(255) + mask = ctypes.create_string_buffer(255) + mac = ctypes.create_string_buffer(255) + ret = rm_get_wired_net(self.handle, ip, mask, mac) + result_dict = { + 'return_code': ret, + 'ip': ip.value.decode(), + 'mask': mask.value.decode(), + 'mac': mac.value.decode(), + } + + return result_dict + + def rm_get_wifi_net(self) -> tuple[int, dict[str, any]]: + """ + 查询无线网卡网络信息 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str,any]: 无线网络信息字典,键为rm_wifi_net_t结构体的字段 + """ + net = rm_wifi_net_t() + ret = rm_get_wifi_net(self.handle, byref(net)) + + return ret, net.to_dict() + + def rm_set_net_default(self) -> int: + """ + 恢复网络出厂设置 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_net_default(self.handle) + return tag + + def rm_set_wifi_close(self) -> int: + """ + 配置关闭 wifi 功能,需要重启后生效 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_wifi_close(self.handle) + return tag + + +class ControllerIOConfig: + """ + 控制器端IO + 机械臂控制器提供IO端口,用于与外部设备交互。可查阅文档了解其数量分类等。 + """ + + def rm_set_io_mode(self, io_num: int, io_mode: int, io_speed: int=0, io_speed_mode: int=0) -> int: + """ + Args: + io_num (int): IO 端口号,范围:1~4 + io_mode (int): 模式,0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、12-输入初始位姿功能复用模式、 + 13-输出碰撞功能复用模式。 + io_speed (int): 速度取值范围0-100 + io_speed_mode (int): 模式取值范围1或2, + 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值 + 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + config = rm_io_config_t(io_mode=io_mode, io_real_time_config_t=rm_io_real_time_config_t(io_speed, io_speed_mode)) + tag = rm_set_IO_mode(self.handle, io_num, config) + return tag + + def rm_set_do_state(self, io_num: int, state: int) -> int: + """ + 设置数字IO输出 + + Args: + io_num (int): IO 端口号,范围:1~4 + state (int): IO 状态,1-输出高,0-输出低 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_DO_state(self.handle, io_num, state) + return tag + + def rm_get_io_state(self, io_num: int) -> tuple[int, dict[str, any]]: + """ + 获取数字 IO 状态 + + Args: + io_num (int): IO 端口号,范围:1~4 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'io_state' (int): io 状态 + - 'io_config' (dict): 配置字典 + - 'io_mode' (int):模式 + 0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、 + 12-输入初始位姿功能复用模式、13-输出碰撞功能复用模式、14-实时调速功能复用模式 + - 'io_real_time_config_t' (dict):实时调速功能复用模式配置 + - speed (int):速度取值范围0-100(当io_mode不为14时,默认值为-1) + - mode (int) :模式取值范围1或2 (当io_mode不为14时,默认值为-1) + 1-单次触发模式,当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值 + 2-连续触发模式,IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + """ + config = rm_io_get_t() + ret = rm_get_IO_state(self.handle, io_num, byref(config)) + + return ret, config.to_dict() + + def rm_get_io_input(self) -> tuple[int, list[int]]: + """ + 获取所有 IO 输入状态 + + Returns: + tuple[int, list[int]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list[int]: 4路数字输入状态列表,1:高,0:低,-1:该端口不是输入模式 + """ + DI = (c_int * 4)() + + ret = rm_get_IO_input(self.handle, DI) + + return ret, list(DI) + + def rm_get_io_output(self) -> tuple[int, list[int]]: + """ + 获取所有 IO 输出状态 + + Returns: + tuple[int, list[int]]: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - list[int]: 4路数字输出状态列表,1:高,0:低,-1:该端口不是输出模式 + """ + DO = (c_int * 4)() + + ret = rm_get_IO_output(self.handle, DO) + + return ret, list(DO) + + def rm_set_voltage(self, voltage_type: int, start_enable: bool) -> int: + """ + 设置控制器电源输出 + + Args: + voltage_type (int): 电源输出类型,0:0V,2:12V,3:24V + start_enable (bool): true:开机启动时输出此配置电压,false:取消开机启动即配置电压 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_voltage(self.handle, voltage_type, start_enable) + return tag + + def rm_get_voltage(self) -> tuple[int, int]: + """ + 获取控制器电源输出类 + + Returns: + tuple[int, int]: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 电源输出类型,0:0V,2:12V,3:24V + """ + voltage_type = c_int() + tag = rm_get_voltage(self.handle, byref(voltage_type)) + return tag, voltage_type.value + +class EffectorIOConfig: + """ + 末端工具IO + 机械臂末端工具端提供多种IO端口,用于与外部设备交互。可查阅文档了解其数量分类等。 + """ + def rm_set_tool_do_state(self, io_num: int, state: int) -> int: + """ + 设置工具端数字 IO 输出 + + Args: + io_num (int): IO 端口号,范围:1~2 + state (int): IO 状态,1-输出高,0-输出低 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_tool_DO_state(self.handle, io_num, state) + return tag + + def rm_set_tool_IO_mode(self, io_num: int, state: int) -> int: + """ + 设置工具端数字 IO 模式 + + Args: + io_num (int): IO 端口号,范围:1~2 + state (int): 模式,0-输入状态,1-输出状态 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_tool_IO_mode(self.handle, io_num, state) + return tag + + def rm_get_tool_io_state(self) -> dict[str, any]: + """ + 获取数字 IO 状态 + + Returns: + dict[str, any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'IO_Mode' (list[int]): 0-输入模式,1-输出模式 + - 'IO_state' (list[int]): 0-低,1-高 + + """ + mode = (c_int * 2)() + state = (c_int * 2)() + + ret = rm_get_tool_IO_state(self.handle, mode, state) + + result_dict = { + 'return_code': ret, + 'IO_Mode': list(mode), + 'IO_state': list(state), + } + return result_dict + + def rm_set_tool_voltage(self, voltage_type: int) -> int: + """ + 设置工具端电源输出 + + Args: + voltage_type (int): 电源输出类型,0:0V,1:5V,2:12V,3:24V, + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_tool_voltage(self.handle, voltage_type) + return tag + + def rm_get_tool_voltage(self) -> tuple[int, int]: + """ + 获取工具端电源输出 + + Returns: + tuple[int, int]: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 电源输出类型,0:0V,1:5V,2:12V,3:24V, + """ + voltage_type = c_int() + tag = rm_get_tool_voltage(self.handle, byref(voltage_type)) + return tag, voltage_type.value + + +class GripperControl: + """ + 夹爪控制及状态获取 + @details 睿尔曼机械臂末端配备了因时机器人公司的 EG2-4C2 手爪,为了便于用户操作手爪,机械臂控制器 + 对用户开放了手爪的控制协议(手爪控制协议与末端modbus 功能互斥) + """ + def rm_set_rm_plus_mode(self, mode: int) -> int: + """ + 设置末端生态协议模式 + Args: + mode 末端生态协议模式 + 0:禁用协议 + 9600:开启协议(波特率9600) + 115200:开启协议(波特率115200) + 256000:开启协议(波特率256000) + 460800:开启协议(波特率460800) + + Returns: + int 设置末端生态协议模式结果 0成功 + """ + + tag = rm_set_rm_plus_mode(self.handle, mode) + return tag + + def rm_get_rm_plus_mode(self) -> tuple[int, int]: + """ + 查询末端生态协议模式 + Returns: + tag 函数执行的状态码 + - 0: 成功 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误 + - -1: 数据发送失败,通信过程中出现问题 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整 + mode 末端生态协议模式 + - 0:禁用协议 + - 9600:开启协议(波特率9600) + - 115200:开启协议(波特率115200) + - 256000:开启协议(波特率256000) + - 460800:开启协议(波特率460800) + """ + plus_mode_type = c_int() + tag = rm_get_rm_plus_mode(self.handle, byref(plus_mode_type)) + return tag, plus_mode_type.value + + def rm_set_rm_plus_touch(self,mode: int) -> int: + """ + 设置触觉传感器模式(末端生态协议支持) + Args: + mode 触觉传感器开关状态 + 0:关闭触觉传感器 + 1:打开触觉传感器(返回处理后数据) + 2:打开触觉传感器(返回原始数据) + Returns: + int 设置触觉传感器模式结果 0成功 + """ + tag = rm_set_rm_plus_touch(self.handle, mode) + return tag + + def rm_get_rm_plus_touch(self) -> tuple[int,int]: + """ + 查询触觉传感器模式(末端生态协议支持) + Returns: + -触觉传感器模式查询状态 + -mode 触觉传感器开关状态 + 0:关闭触觉传感器 + 1:打开触觉传感器(返回处理后数据) + 2:打开触觉传感器(返回原始数据) + """ + plus_touch_type = c_int() + tag = rm_get_rm_plus_touch(self.handle, byref(plus_touch_type)) + return tag, plus_touch_type.value + + def rm_get_rm_plus_base_info(self) -> tuple[int,dict[str, any]]: + """ + 读取末端设备基础信息(末端生态协议支持) + Returns: + -函数执行的状态码 + -rm_plus_base_info_t 末端设备基础信息 + """ + base_info_type = rm_plus_base_info_t() + tag = rm_get_rm_plus_base_info(self.handle, byref(base_info_type)) + return tag, base_info_type.to_dict() + + def rm_get_rm_plus_state_info(self) -> tuple[int, dict[str, any]]: + """ + 读取末端设备实时信息(末端生态协议支持) + Returns: + -函数执行的状态码 + -rm_plus_state_info_t 末端设备实时信息 + """ + state_info_type = rm_plus_state_info_t() + tag = rm_get_rm_plus_state_info(self.handle, byref(state_info_type)) + return tag, state_info_type.to_dict() + + def rm_get_rm_plus_reg(self, addr: int, length: int) -> tuple[int, list[int]]: + """ + 读末端生态设备寄存器 + + Args: + addr: 寄存器起始地址(1000~1653)。 + length: 寄存器长度。 + + Returns: + tuple[int, list[int]]: 包含两个元素的元组。 + - int: 函数执行的状态码(含义同前)。 + - list[int]: 读取的寄存器数据列表。 + """ + + regarr = (c_int * length)() + ret = rm_get_rm_plus_reg(self.handle, addr, length, regarr) + return ret, list(regarr) + + def rm_set_rm_plus_reg(self, addr: int, length: int, data: list[int]) -> int: + """ + 写末端生态设备寄存器(修正参数传递方式) + + Args: + addr: 寄存器起始地址(1000~1653)。 + length: 寄存器长度。 + data: 要写入的寄存器数据列表。 + + Returns: + int: 函数执行的状态码。 + """ + data_arr = (c_int * length)(*data) + ret = rm_set_rm_plus_reg(self.handle, addr, length, data_arr) + return ret + + def rm_set_gripper_route(self, min_route: int, max_route: int) -> int: + """ + 设置手爪行程,即手爪开口的最大值和最小值,设置成功后会自动保存,手爪断电不丢失 + + Args: + min_route (int): 手爪开口最小值,范围:0~1000,无单位量纲 + max_route (int): 手爪开口最大值,范围:0~1000,无单位量纲 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + """ + tag = rm_set_gripper_route(self.handle, min_route, max_route) + return tag + + def rm_set_gripper_release(self, speed: int, block: bool, timeout: int) -> int: + """ + 松开手爪,即手爪以指定的速度运动到开口最大处 + + Args: + speed (int): 手爪松开速度,范围 1~1000,无单位量纲 + block (bool): true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + timeout (int): 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + """ + tag = rm_set_gripper_release(self.handle, speed, block, timeout) + return tag + + def rm_set_gripper_pick(self, speed: int, force: int, block: bool, timeout: int) -> int: + """ + 手爪力控夹取,手爪以设定的速度和力夹取,当夹持力超过设定的力阈值后,停止夹取 + + Args: + speed (int): 手爪夹取速度,范围 1~1000,无单位量纲 + force (int): 力控阈值,范围:50~1000,无单位量纲 + block (bool): true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + timeout (int): 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + """ + tag = rm_set_gripper_pick(self.handle, speed, force, block, timeout) + return tag + + def rm_set_gripper_pick_on(self, speed: int, force: int, block: bool, timeout: int) -> int: + """ + 手爪持续力控夹取 + + Args: + speed (int): 手爪夹取速度,范围 1~1000,无单位量纲 + force (int): 力控阈值,范围:50~1000,无单位量纲 + block (bool): true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + timeout (int): 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + """ + tag = rm_set_gripper_pick_on(self.handle, speed, force, block, timeout) + return tag + + def rm_set_gripper_position(self, position: int, block: bool, timeout: int) -> int: + """ + 设置手爪达到指定位置 + + Args: + position (int): 手爪开口位置,范围:1~1000,无单位量纲 + block (bool): true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + timeout (int): 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + """ + tag = rm_set_gripper_position(self.handle, position, block, timeout) + return tag + + def rm_get_gripper_state(self) -> tuple[int, dict[str, any]]: + """ + 查询夹爪状态 + + Returns: + tuple[int,dict[str, any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str, any]: 夹爪状态信息字典,键为rm_gripper_state_t结构体的字段名称 + """ + state = rm_gripper_state_t() + tag = rm_get_gripper_state(self.handle, byref(state)) + return tag, state.to_dict() + + +class Force: + """ + 末端力传感器 + @details + **六维力** + 睿尔曼机械臂六维力版末端配备集成式六维力传感器,无需外部走线,用户可直接通过协议对六维力进行操作, + 获取六维力数据。如下图所示,正上方为六维力的 Z 轴,航插反方向为六维力的 Y 轴,坐标系符合右手定则。 + 机械臂位于零位姿态时,工具坐标系与六维力的坐标系方向一致。 + 另外,六维力额定力 200N,额定力矩 8Nm,过载水平 300%FS,工作温度 5~80℃,准度 0.5%FS。使用过程中 + 注意使用要求,防止损坏六维力传感器。 + @image html force.png "六维力坐标系" + **一维力** + 睿尔曼机械臂一维力版末端接口板集成了一维力传感器,可获取 Z 方向的力,量程200N,准度 0.5%FS。 + @image html oneforce.png "一维力坐标系" + """ + + def rm_get_force_data(self) -> tuple[int, dict[str, any]]: + """ + 查询当前六维力传感器得到的力和力矩信息:Fx,Fy,Fz,Mx,My,Mz + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str, any]: 六维力数据字典,键为rm_force_data_t结构体的字段名称 + """ + data = rm_force_data_t() + tag = rm_get_force_data(self.handle, byref(data)) + return tag, data.to_dict() + + def rm_clear_force_data(self) -> int: + """ + 将六维力数据清零,标定当前状态下的零位 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_clear_force_data(self.handle) + return tag + + def rm_set_force_sensor(self, block: bool) -> int: + """ + 自动设置六维力重心参数 + @details 设置六维力重心参数,六维力重新安装后,必须重新计算六维力所受到的初始力和重心。分别在不同姿态下,获取六维力的数据, + 用于计算重心位置。该指令下发后,机械臂以固定的速度运动到各标定点。 + 以RM65机械臂为例,四个标定点的关节角度分别为: + 位置1关节角度:{0,0,-60,0,60,0} + 位置2关节角度:{0,0,-60,0,-30,0} + 位置3关节角度:{0,0,-60,0,-30,180} + 位置4关节角度:{0,0,-60,0,-120,0} + Args: + block (bool): true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_force_sensor(self.handle, block) + return tag + + def rm_manual_set_force(self, point_num: int, joint: list[float], block: bool) -> int: + """ + 手动标定六维力数据 + + @details 六维力重新安装后,必须重新计算六维力所受到的初始力和重心。该手动标定流程,适用于空间狭窄工作区域,以防自动标定过程中 + 机械臂发生碰撞,用户可以手动选取四个位置下发,当下发完四个点后,机械臂开始自动沿用户设置的目标运动,并在此过程中计算六维力重心。 + @attention 上述4个位置必须按照顺序依次下发,当下发完位置4后,机械臂开始自动运行计算重心。 + + Args: + point_num (int): 点位;1~4 + joint (list[float]): 关节角度,单位:° + block (bool): true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)(*joint) + else: + joint_positions = (c_float * ARM_DOF)(*joint) + tag = rm_manual_set_force( + self.handle, point_num, joint_positions, block) + return tag + + def rm_stop_set_force_sensor(self) -> int: + """ + 停止标定力传感器重心 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_stop_set_force_sensor(self.handle) + return tag + + def rm_get_fz(self) -> tuple[int, dict[str, any]]: + """ + 查询末端一维力数据 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str, any]: 一维力数据字典,键为rm_fz_data_t结构体的字段名称 + """ + data = rm_fz_data_t() + tag = rm_get_Fz(self.handle, byref(data)) + return tag, data.to_dict() + + def rm_clear_fz(self) -> int: + """ + 清零末端一维力数据,清空一维力数据后,后续所有获取到的数据都是基于当前的偏置。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_clear_Fz(self.handle) + return tag + + def rm_auto_set_fz(self, block: bool) -> int: + """ + 自动标定一维力数据 + @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。 + 分别在不同姿态下,获取一维力的数据,用于计算重心位置,该步骤对于基于一维力的力位混合控制操作具有重要意义。 + Args: + block (bool): true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_auto_set_Fz(self.handle, block) + return tag + + def rm_manual_set_fz(self, joint1: list[float], joint2: list[float], block: bool) -> int: + """ + 手动标定一维力数据 + @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。该手动标定流程, + 适用于空间狭窄工作区域,以防自动标定过程中机械臂发生碰撞,用户可以手动选取2个位置下发,当下发完后, + 机械臂开始自动沿用户设置的目标运动,并在此过程中计算一维力重心。 + + Args: + joint1 (list[float]): 位置1关节角度数组,单位:度 + joint2 (list[float]): 位置2关节角度数组,单位:度 + block (bool): true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + if self.arm_dof != 0: + joint_positions1 = (c_float * self.arm_dof)(*joint1) + joint_positions2 = (c_float * self.arm_dof)(*joint2) + else: + joint_positions1 = (c_float * ARM_DOF)(*joint1) + joint_positions2 = (c_float * ARM_DOF)(*joint2) + tag = rm_manual_set_Fz( + self.handle, joint_positions1, joint_positions2, block) + return tag + + +class DragTeach: + """ + 拖动示教 + + @details 睿尔曼机械臂在拖动示教过程中,可记录拖动的轨迹点,并根据用户的指令对轨迹进行复现。 + """ + + def rm_start_drag_teach(self, trajectory_record: int) -> int: + """ + 拖动示教开始 + + Args: + trajectory_record (int): 拖动示教时记录轨迹,0-不记录,1-记录轨迹 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_start_drag_teach(self.handle, trajectory_record) + return tag + + def rm_stop_drag_teach(self) -> int: + """ + 拖动示教结束 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_stop_drag_teach(self.handle) + return tag + + def rm_start_multi_drag_teach(self, mode: int, singular_wall: int) -> int: + """ + 开始复合模式拖动示教 + 仅支持三代控制器 + + Args: + mode (int): 拖动示教模式 0-电流环模式,1-使用末端六维力,只动位置,2-使用末端六维力,只动姿态,3-使用末端六维力,位置和姿态同时动 + singular_wall (int): 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + @attention 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + """ + tag = rm_start_multi_drag_teach(self.handle, mode, singular_wall) + return tag + + def rm_start_multi_drag_teach_new(self, param: rm_multi_drag_teach_t) -> int: + """ + 开始复合模式拖动示教-新参数 + + Args: + param (rm_multi_drag_teach_t): 复合拖动示教参数 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + @attention 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + """ + tag = rm_start_multi_drag_teach_new(self.handle, param) + return tag + + def rm_set_drag_teach_sensitivity(self, grade: int) -> int: + """ + 设置电流环拖动示教灵敏度 + + Args: + grade (int): 灵敏度等级,取值范围0~100%,数值越小越沉,当设置为100时保持原本拖动灵敏度 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_drag_teach_sensitivity(self.handle, grade) + return tag + + def rm_get_drag_teach_sensitivity(self) -> tuple[int, int]: + """ + 获取电流环拖动示教灵敏度 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 灵敏度等级,取值范围0~100%,数值越小越沉,当设置为100时保持原本拖动灵敏度 + """ + grade = c_int() + tag = rm_get_drag_teach_sensitivity(self.handle, byref(grade)) + return tag, grade.value + + def rm_drag_trajectory_origin(self, block: int) -> int: + """ + 运动到轨迹起点 + @details 轨迹复现前,必须控制机械臂运动到轨迹起点,如果设置正确,机械臂将以20%的速度运动到轨迹起点 + + Args: + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_drag_trajectory_origin(self.handle, block) + return tag + + def rm_run_drag_trajectory(self, timeout: int) -> int: + """ + 轨迹复现开始 + @attention 必须在拖动示教结束后才能使用,同时保证机械臂位于拖动示教的起点位置,可调用rm_drag_trajectory_origin接口运动至起点位置 + Args: + timeout (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_run_drag_trajectory(self.handle, timeout) + return tag + + def rm_pause_drag_trajectory(self) -> int: + """ + 控制机械臂在轨迹复现过程中的暂停 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_pause_drag_trajectory(self.handle) + return tag + + def rm_continue_drag_trajectory(self) -> int: + """ + 控制机械臂在轨迹复现过程中暂停之后的继续, + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_continue_drag_trajectory(self.handle) + return tag + + def rm_stop_drag_trajectory(self) -> int: + """ + 控制机械臂在轨迹复现过程中的停止 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_stop_drag_trajectory(self.handle) + return tag + + def rm_set_force_position(self, sensor: int, mode: int, direction: int, force: float) -> int: + """ + 力位混合控制 + @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + Args: + sensor (int): 0-一维力;1-六维力 + mode (int): 0-基坐标系力控;1-工具坐标系力控; + direction (int): 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向 + force (float): 力的大小,单位N + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_force_position( + self.handle, sensor, mode, direction, force) + return tag + + def rm_set_force_position_new(self, param: rm_force_position_t) -> int: + """ + 力位混合控制-新参数 + @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + Args: + param (rm_force_position_t): 力位混合控制参数 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_force_position_new(self.handle, param) + return tag + + def rm_stop_force_position(self) -> int: + """ + 结束力位混合控制 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_stop_force_position(self.handle) + return tag + + def rm_save_trajectory(self, file_path: str) -> tuple[int, int]: + """ + 保存拖动示教轨迹 + + Args: + file_path (str): 轨迹要保存的文件路径及名称,例: c:/rm_test.txt + + Returns: + tuple[int,int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - int: 轨迹点总数 + """ + num = c_int() + tag = rm_save_trajectory(self.handle, file_path, byref(num)) + return tag, num.value + + def rm_set_force_drag_mode(self, mode: int) -> int: + """ + 设置六维力拖动示教模式 + + Args: + mode (int): 0表示快速拖动模式 1表示精准拖动模式 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + """ + tag = rm_set_force_drag_mode(self.handle, mode) + return tag + + def rm_get_force_drag_mode(self) -> tuple[int, int]: + """ + 查询六维力拖动示教模式 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 非六维力版本机械臂,不支持此功能。 + - int: 0表示快速拖动模式 1表示精准拖动模式 + """ + mode = c_int() + tag = rm_get_force_drag_mode(self.handle, byref(mode)) + return tag, mode.value + + +class HandControl: + """ + 五指灵巧手控制 + """ + + def rm_set_hand_posture(self, posture_num: int, block: bool, timeout: int) -> int: + """ + 设置灵巧手目标手势序列号 + + Args: + posture_num (int): 预先保存在灵巧手内的手势序号,范围:1~40 + block (bool): true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + timeout (int): 阻塞模式下超时时间设置,单位:秒 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + """ + tag = rm_set_hand_posture(self.handle, posture_num, block, timeout) + return tag + + def rm_set_hand_seq(self, seq_num: int, block: bool, timeout: int) -> int: + """ + 设置灵巧手目标手势序列号 + + Args: + seq_num (int): 预先保存在灵巧手内的手势序号,范围:1~40 + block (bool): true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + timeout (int): 阻塞模式下超时时间设置,单位:秒 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + """ + tag = rm_set_hand_seq(self.handle, seq_num, block, timeout) + return tag + + def rm_set_hand_angle(self, hand_angle: list[int], block:bool, timeout: int) -> int: + """ + 设置灵巧手各自由度角度 + @details 设置灵巧手角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + Args: + hand_angle (list[int]): 手指角度数组,范围:0~1000. 另外,-1代表该自由度不执行任何操作,保持当前状态 + block (bool): true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + timeout (int): 阻塞模式下超时时间设置,单位:秒 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + """ + angle = (c_int * 6)(*hand_angle) + tag = rm_set_hand_angle(self.handle, angle, block, timeout) + return tag + + def rm_set_hand_follow_angle(self, hand_angle: list[int], block:bool) -> int: + """ + 设置灵巧手角度跟随控制 + @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + Args: + hand_angle (list[int]): 手指角度数组,最大表示范围为-32768到+32767,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-2000 + block (bool): false:表示非阻塞模式,发送成功后返回,true:表示阻塞模式,接收设置成功指令后返回。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + angle = (c_int * 6)(*hand_angle) + tag = rm_set_hand_follow_angle(self.handle, angle, block) + return tag + + def rm_set_hand_follow_pos(self, hand_pos: list[int], block:bool) -> int: + """ + 设置灵巧手位置跟随控制 + @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + Args: + hand_pos (list[int]): 手指位置数组,最大范围为0-65535,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-1000 + block (bool): false:表示非阻塞模式,发送成功后返回,true:表示阻塞模式,接收设置成功指令后返回。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + pos = (c_int * 6)(*hand_pos) + tag = rm_set_hand_follow_pos(self.handle, pos, block) + return tag + + def rm_set_hand_speed(self, speed: int) -> int: + """ + 设置灵巧手速度 + + Args: + speed (int): 手指速度,范围:1~1000 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_hand_speed(self.handle, speed) + return tag + + def rm_set_hand_force(self, force: int) -> int: + """ + 设置灵巧手力阈值 + + Args: + force (int): 手指力,范围:1~1000 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_hand_force(self.handle, force) + return tag + + +class ModbusConfig: + """ + Modbus 配置 + + @details 睿尔曼机械臂在控制器和末端接口板上各提供一个RS485通讯接口,这些接口可通过接口配置为标准的Modbus RTU模式。 + 在Modbus RTU模式下,用户可通过提供的接口对连接在端口上的外设进行读写操作。 + + @attention + - 控制器的RS485接口在未配置为Modbus RTU模式时,可用于直接控制机械臂。 + - Modbus RTU模式与机械臂控制模式不兼容。若需恢复机械臂控制模式,必须关闭该端口的Modbus RTU模式。 + - 关闭Modbus RTU模式后,系统将自动切换回机械臂控制模式,使用波特率460800BPS,停止位1,数据位8,无校验。 + + 此外,I系列控制器还支持modbus-TCP主站配置,允许用户配置使用modbus-TCP主站,以连接外部设备的modbus-TCP从站。 + """ + + def rm_set_modbus_mode(self, port: int, baudrate: int, timeout: int) -> int: + """ + 配置通讯端口ModbusRTU模式 + + Args: + port (int): 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + baudrate (int): 波特率,支持 9600,115200,460800 三种常见波特率 + timeout (int): 超时时间,单位百毫秒。。对Modbus设备所有的读写指令,在规定的超时时间内未返回响应数据,则返回超时报错提醒。超时时间不能为0,若设置为0,则机械臂按1进行配置。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_set_modbus_mode(self.handle, port, baudrate, timeout) + return tag + + def rm_close_modbus_mode(self, port: int) -> int: + """ + 关闭通讯端口 Modbus RTU 模式 + + Args: + port (int): 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_close_modbus_mode(self.handle, port) + return tag + + def rm_set_modbustcp_mode(self, ip: str, port: int, timeout: int) -> int: + """ + 配置连接 + Args: + ip (str): 从机IP地址 + port (int): 端口号 + timeout (int): 超时时间,单位毫秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_set_modbustcp_mode(self.handle, ip, port, timeout) + return tag + + def rm_close_modbustcp_mode(self) -> int: + """ + 关闭通讯端口ModbusRTU模式 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_close_modbustcp_mode(self.handle) + return tag + + def rm_read_coils(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, int]: + """ + 读线圈 + + Args: + read_params (rm_peripheral_read_write_params_t): 线圈读取参数结构体,该指令最多一次性支持读 8 个线圈数据,即返回的数据不会超过一个字节 + + Returns: + tuple[int,int]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - int: 返回线圈状态,数据类型:int8 + """ + data = c_int() + tag = rm_read_coils(self.handle, read_params, byref(data)) + return tag, data.value + + def rm_read_input_status(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, int]: + """ + 读离散量输入 + + Args: + read_params (rm_peripheral_read_write_params_t): 离散量输入读取参数结构体,该指令最多一次性支持读 8 个离散量数据,即返回的数据不会超过一个字节 + + Returns: + tuple[int,int]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - int: 返回离散量,数据类型:int8 + """ + data = c_int() + tag = rm_read_input_status(self.handle, read_params, byref(data)) + return tag, data.value + + def rm_read_holding_registers(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, int]: + """ + 读保持寄存器 + + Args: + read_params (rm_peripheral_read_write_params_t): 保持寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + + Returns: + tuple[int,int]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - int: 返回寄存器数据,数据类型:int16 + """ + data = c_int() + tag = rm_read_holding_registers(self.handle, read_params, byref(data)) + return tag, data.value + + def rm_read_input_registers(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, int]: + """ + 读输入寄存器 + + Args: + read_params (rm_peripheral_read_write_params_t): 输入寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + + Returns: + tuple[int,int]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - int: 返回寄存器数据,数据类型:int16 + """ + data = c_int() + tag = rm_read_input_registers(self.handle, read_params, byref(data)) + return tag, data.value + + def rm_write_single_coil(self, write_params: rm_peripheral_read_write_params_t, data: int) -> int: + """ + 写单圈数据 + + Args: + write_params (rm_peripheral_read_write_params_t): 单圈数据写入参数结构体,该结构体成员num无需设置 + data (int): 要写入线圈的数据,数据类型:int16 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_write_single_coil(self.handle, write_params, data) + return tag + + def rm_write_single_register(self, write_params: rm_peripheral_read_write_params_t, data: int) -> int: + """ + 写单个寄存器 + + Args: + write_params (rm_peripheral_read_write_params_t): 单个寄存器数据写入参数结构体,该结构体成员num无需设置 + data (int): 要写入寄存器的数据,类型:int16 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + tag = rm_write_single_register(self.handle, write_params, data) + return tag + + def rm_write_registers(self, write_params: rm_peripheral_read_write_params_t, data: list[int]) -> int: + """ + 写多个寄存器 + + Args: + write_params (rm_peripheral_read_write_params_t): 多个寄存器数据写入参数结构体。其中寄存器每次写的数量不超过10个,即该结构体成员num<=10。 + data (list[int]): 要写入寄存器的数据数组,类型:byte。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + data_num = int(write_params.num * 2) + datas = (c_int * data_num)(*data) + tag = rm_write_registers(self.handle, write_params, datas) + return tag + + def rm_write_coils(self, write_params: rm_peripheral_read_write_params_t, data: list[int]) -> int: + """ + 写多圈数据 + + Args: + write_params (rm_peripheral_read_write_params_t): 多圈数据写入参数结构体。每次写的数量不超过 160 个,即该结构体成员num<=160。 + data (list[int]): 要写入线圈的数据数组,类型:byte。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + """ + data_num = int(write_params.num // 8 + 1) + datas = (c_int * data_num)(*data) + tag = rm_write_coils(self.handle, write_params, datas) + return tag + + def rm_read_multiple_coils(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, list[int]]: + """ + 读多圈数据 + + Args: + read_params (rm_peripheral_read_write_params_t): 多圈数据读取参数结构体,要读的线圈的数量 8< num <= 120,该指令最多一次性支持读 120 个线圈数据, 即 15 个 byte + + Returns: + tuple[int,list[int]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - list[int]: 返回线圈状态列表,数据类型:int8 + """ + data_num = int(read_params.num//8+1) + data = (c_int * data_num)() + tag = rm_read_multiple_coils(self.handle, read_params, data) + return tag, list(data) + + def rm_read_multiple_holding_registers(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, list[int]]: + """ + 读多个保存寄存器 + + Args: + read_params (rm_peripheral_read_write_params_t): 多个保存寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + + Returns: + tuple[int,list[int]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - list[int]: 返回寄存器数据列表,数据类型:int8 + """ + data_num = int(read_params.num * 2) + data = (c_int * data_num)() + tag = rm_read_multiple_holding_registers( + self.handle, read_params, data) + return tag, list(data) + + def rm_read_multiple_input_registers(self, read_params: rm_peripheral_read_write_params_t) -> tuple[int, list[int]]: + """ + 读多个输入寄存器 + + Args: + read_params (rm_peripheral_read_write_params_t): 多个输入寄存器读取参数结构体。要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + + Returns: + tuple[int,list[int]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 四代控制器不支持该接口 + - list[int]: 返回寄存器数据列表,数据类型:int8 + """ + data_num = int(read_params.num * 2) + data = (c_int * data_num)() + tag = rm_read_multiple_input_registers( + self.handle, read_params, data) + return tag, list(data) + + +class InstallPos: + """ + 安装方式及关节、末端软件版本号查询 + @details 睿尔曼机械臂可支持不同形式的安装方式,但是安装方式不同,机器人的动力学模型参数和坐标系的方向也有所差别。 + """ + + def rm_set_install_pose(self, x: float, y: float, z: float) -> int: + """ + 设置安装方式参数 + + Args: + x (float): 旋转角,单位 ° + y (float): 俯仰角,单位 ° + z (float): 方位角,单位 ° + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_install_pose(self.handle, x, y, z) + return tag + + def rm_get_install_pose(self) -> dict[str, any]: + """ + 获取安装方式参数 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'x' (float): 旋转角,单位 ° + - 'y' (float): 俯仰角,单位 ° + - 'z' (float): 方位角,单位 ° + """ + x = c_float() + y = c_float() + z = c_float() + + ret = rm_get_install_pose(self.handle, byref(x), byref(y), byref(z)) + + # 创建一个字典来存储返回值 + result_dict = { + 'return_code': ret, + 'x': x.value, + 'y': y.value, + 'z': z.value, + } + + return result_dict + + def rm_get_joint_software_version(self) -> tuple[int, dict[str, any]]: + """ + 查询关节软件版本号 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict[str,any]: 包含以下键值的字典: + -'version' (list[int]): (三代控制器)获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8 + - 'joints_v' (list[str]): (四代控制器)获取到的各关节软件版本号字符串数组 + """ + if self.arm_dof != 0: + version = (c_int * self.arm_dof)() + joints_v = (rm_version_t * self.arm_dof)() + else: + version = (c_int * ARM_DOF)() + joints_v = (rm_version_t * ARM_DOF)() + + ret = rm_get_joint_software_version(self.handle, version, joints_v) + result_dict = {} + if(self.robot_controller_version == 3): + result_dict['version'] = [version[i] for i in range(self.arm_dof)] + else: + result_dict['joints_v'] = [joints_v[i].version.decode('utf-8') for i in range(self.arm_dof)] + return ret, result_dict + + def rm_get_tool_software_version(self) -> tuple[int,dict[str,any]]: + """ + 查询末端接口板软件版本号 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - dict[str,any]: 包含以下键值的字典: + -'version' (int): (三代控制器)获取到的末端接口板软件版本号,需转换为十六进制,例如获取到版本号393,转换为十六进制为189,则当前关节的版本号为 V1.8.9 + - 'tool_v' (str): (四代控制器)获取到的末端接口板软件版本号字符串 + """ + version = c_int() + tool_v = rm_version_t() + + ret = rm_get_tool_software_version(self.handle, byref(version), byref(tool_v)) + result_dict = {} + if(self.robot_controller_version == 3): + result_dict['version'] = version.value + else: + result_dict['tool_v'] = tool_v.version.decode('utf-8') + + return ret,result_dict + + +class ForcePositionControl: + """透传力位混合控制补偿 + """ + + def rm_start_force_position_move(self) -> int: + """ + 开启透传力位混合控制补偿模式 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_start_force_position_move(self.handle) + return tag + + def rm_stop_force_position_move(self) -> int: + """ + 停止透传力位混合控制补偿模式 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_stop_force_position_move(self.handle) + return tag + + def rm_force_position_move_joint(self, joint: list[float], sensor: int, mode: int, dir: int, force: float, follow: bool) -> int: + """ + 透传力位混合补偿-角度方式 + + Args: + joint (list[float]): 目标关节角度,单位:° + sensor (int): 所使用传感器类型,0-一维力,1-六维力 + mode (int): 模式,0-沿基坐标系,1-沿工具端坐标系 + dir (int): 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + force (float): 力的大小 单位N + follow (bool): 是否高跟随 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + if self.arm_dof != 0: + joint = (c_float * self.arm_dof)(*joint) + else: + joint = (c_float * ARM_DOF)(*joint) + tag = rm_force_position_move_joint( + self.handle, joint, sensor, mode, dir, force, follow) + return tag + + def rm_force_position_move_pose(self, pose: list[float], sensor: int, mode: int, dir: int, force: float, follow: bool) -> int: + """ + 透传力位混合补偿-位姿方式 + + Args: + pose (list[float]): 当前坐标系下目标位姿列表,支持欧拉角及四元数方式表示姿态,若列表长度为6,则认为使用欧拉角方式表示;列表长度为7则认为使用四元数表示 + sensor (int): 所使用传感器类型,0-一维力,1-六维力 + mode (int): 模式,0-沿基坐标系,1-沿工具端坐标系 + dir (int): 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + force (float): 力的大小 单位N + follow (bool): 是否高跟随 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + po1 = rm_pose_t() + + po1.position = rm_position_t(*pose[:3]) + # 四元数 + if len(pose) == 7: + po1.quaternion = rm_quat_t(*pose[3:]) + # 欧拉角 + elif len(pose) == 6: + po1.euler = rm_euler_t(*pose[3:]) + else: + print("Error: pose length is error.") + tag = rm_force_position_move_pose( + self.handle, po1, sensor, mode, dir, force, follow) + return tag + + def rm_force_position_move(self, param:rm_force_position_move_t) -> int: + """透传力位混合补偿-新参数 + + Args: + param (rm_force_position_move_t): 透传力位混合补偿参数 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + + tag = rm_force_position_move(self.handle, param) + return tag + +class LiftControl: + """升降机构控制 + """ + + def rm_set_lift_speed(self, speed: int) -> int: + """ + 升降机构速度开环控制 + + Args: + speed (int): 速度百分比,-100~100。 + - speed<0:升降机构向下运动 + - speed>0:升降机构向上运动 + - speed=0:升降机构停止运动 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_lift_speed(self.handle, speed) + return tag + + def rm_set_lift_height(self, speed: int, height: int, block: int) -> int: + """ + 升降机构位置闭环控制 + + Args: + speed (int): 速度百分比,1~100 + height (int): 目标高度,单位 mm,范围:0~2600 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_lift_height(self.handle, speed, height, block) + return tag + + def rm_get_lift_state(self) -> tuple[int, dict[str, any]]: + """ + 获取升降机构状态 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str,any]: 获取到的升降机构状态字典,键为rm_expand_state_t结构体的字段名称 + """ + data = rm_expand_state_t() + tag = rm_get_lift_state(self.handle, byref(data)) + return tag, data.to_dict() + + +class ExpandControl: + """扩展关节控制 + """ + + def rm_set_expand_speed(self, speed: int) -> int: + """ + 扩展关节速度环控制 + + Args: + speed (int): 速度百分比,-100~100。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_expand_speed(self.handle, speed) + return tag + + def rm_set_expand_pos(self, speed: int, height: int, block: int) -> int: + """ + 扩展关节位置环控制 + + Args: + speed (int): 速度百分比,1~100 + height (int): 扩展关节角度,单位度 + block (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_expand_pos(self.handle, speed, height, block) + return tag + + def rm_get_expand_state(self) -> tuple[int, dict[str, any]]: + """ + 获取扩展关节状态 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - dict[str,any]: 获取到的扩展关节状态字典,键为rm_expand_state_t结构体的字段名称 + """ + data = rm_expand_state_t() + tag = rm_get_expand_state(self.handle, byref(data)) + return tag, data.to_dict() + + +class ProjectManagement: + """ + 在线编程文件下发、管理 + """ + + def rm_send_project(self, send_project: rm_send_project_t) -> tuple[int, int]: + """ + 文件下发。 + + Args: + send_project (rm_send_project_t): 要发送的文件数据。 + + Returns: + Tuple[int, int]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 文件名称校验失败 + - -5: 文件读取失败 + - -6: 四代控制器不支持该接口 + -int 若运行失败,该参数返回有问题的工程行数 + - -1: 无错误,文件成功下发 + - 0: 校验数据长度不对 + - 其他值: 有问题的工程行数 + """ + err_line = c_int() + tag = rm_send_project(self.handle, send_project, byref(err_line)) + return tag, err_line.value if tag != 0 else -1 + + def rm_set_plan_speed(self, speed: int) -> int: + """ + 规划过程中改变速度系数 + Args: + speed (int): 速度系数,1-100 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_set_plan_speed(self.handle, speed) + return tag + + def rm_get_program_trajectory_list(self, page_num: int, page_size: int, vague_search: str) -> tuple[int, dict[str, any]]: + """ + 获取在线编程列表 + + Args: + page_num (int): 页码 + page_size (int): 每页大小 + vague_search (str): 模糊搜索 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 获取到的在线编程列表字典,键为rm_program_trajectorys_t结构体的字段名称 + """ + trajectorys = rm_program_trajectorys_t() + ret = rm_get_program_trajectory_list( + self.handle, page_num, page_size, vague_search, byref(trajectorys)) + return ret, trajectorys.to_dict() + + def rm_set_program_id_run(self, tra_id: int, speed: int, timeout: int) -> int: + """ + 开始运行指定编号轨迹 + + Args: + tra_id (int): 运行指定的ID,1-100,存在轨迹可运行 + speed (int): 1-100,需要运行轨迹的速度,若设置为0,则按照存储的速度运行 + timeout (int): 阻塞设置 + - 多线程模式: + - 0:非阻塞模式,发送指令后立即返回。 + - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + - 单线程模式: + - 0:非阻塞模式。 + - 其他值:阻塞模式并设置超时时间,单位为秒。 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 运行状态已停止但未接收到运行成功,是否在外部停止了轨迹。 + """ + tag = rm_set_program_id_run(self.handle, tra_id, speed, timeout) + return tag + + def rm_get_program_run_state(self) -> tuple[int, dict[str, any]]: + """ + 查询在线编程运行状态 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 获取到的在线编程运行状态字典,键为rm_program_run_state_t结构体的字段名称 + """ + run_state = rm_program_run_state_t() + ret = rm_get_program_run_state(self.handle, byref(run_state)) + return ret, run_state.to_dict() + + def rm_get_flowchart_program_run_state(self) -> tuple[int, dict[str, any]]: + """ + 查询流程图编程运行状态 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any] 获取到的在线编程运行状态字典,键为rm_program_run_state_t结构体的字段名称 + """ + run_state = rm_flowchart_run_state_t() + ret = rm_get_flowchart_program_run_state(self.handle, byref(run_state)) + return ret, run_state.to_dict() + + def rm_delete_program_trajectory(self, tra_id: int) -> int: + """ + 删除指定编号轨迹 + + Args: + tra_id (int): 指定轨迹的ID + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_delete_program_trajectory(self.handle, tra_id) + return tag + + def rm_update_program_trajectory(self, tra_id: int, speed: int, name: str) -> int: + """ + 修改指定编号的轨迹信息 + + Args: + tra_id (int): 指定在线编程轨迹编号 + speed (int): 更新后的规划速度比例 1-100 + name (str): 更新后的文件名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_update_program_trajectory(self.handle, tra_id, speed, name) + return tag + + def rm_set_default_run_program(self, tra_id: int) -> int: + """ + 设置 IO 默认运行编号 + + Args: + tra_id (int): 设置 IO 默认运行的在线编程文件编号,支持 0-100,0 代表取消设置 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_default_run_program(self.handle, tra_id) + return tag + + def rm_get_default_run_program(self) -> tuple[int, int]: + """ + 获取 IO 默认运行编号 + + Returns: + tuple[int,int]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -int IO 默认运行的在线编程文件编号,支持 0-100,0 代表无默认 + """ + tra_id = c_int() + tag = rm_get_default_run_program(self.handle, byref(tra_id)) + return tag, tra_id.value + + +class GlobalWaypointManage: + """ + 全局路点管理 + """ + + def rm_add_global_waypoint(self, waypoint: rm_waypoint_t) -> int: + """ + 新增全局路点 + + Args: + waypoint (rm_waypoint_t): 新增全局路点参数(无需输入新增全局路点时间) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_add_global_waypoint(self.handle, waypoint) + return tag + + def rm_update_global_waypoint(self, waypoint: rm_waypoint_t) -> int: + """ + 更新全局路点 + + Args: + waypoint (rm_waypoint_t): 更新全局路点参数(无需输入更新全局路点时间) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_update_global_waypoint(self.handle, waypoint) + return tag + + def rm_delete_global_waypoint(self, point_name: str) -> int: + """ + 删除全局路点 + + Args: + point_name (str): 全局路点名称 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_delete_global_waypoint(self.handle, point_name) + return tag + + def rm_get_given_global_waypoint(self, point_name: str) -> tuple[int, dict[str, any]]: + """ + 查询指定全局路点 + + Args: + point_name (str): 指定全局路点名称 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回指定全局路点的参数字典,键为rm_waypoint_t结构体的字段名称 + """ + waypoint = rm_waypoint_t() + tag = rm_get_given_global_waypoint( + self.handle, point_name, byref(waypoint)) + return tag, waypoint.to_dict() + + def rm_get_global_waypoints_list(self, page_num: int, page_size: int, vague_search: str) -> tuple[int, dict[str, any]]: + """ + 查询多个全局路点 + + Args: + page_num (int): 页码 + page_size (int): 每页大小 + vague_search (str): 模糊搜索 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回符合条件的全局路点列表字典,键为rm_waypoint_list_t结构体的字段名称 + """ + waypoint_list = rm_waypoint_list_t() + ret = rm_get_global_waypoints_list( + self.handle, page_num, page_size, vague_search, byref(waypoint_list)) + return ret, waypoint_list.to_dict() + + +class ElectronicFenceConfig: + """ + 电子围栏和虚拟墙 + + @details I 系列机械臂具备电子围栏与虚拟墙功能,并提供了针对控制器所保存的电子围栏或虚拟墙几何模型参数的操作接口。 + 用户可以通过这些接口,实现对电子围栏或虚拟墙的新增、查询、更新和删除操作,在使用中,可以灵活地使用保存在 + 控制器中的参数配置,需要注意的是,目前控制器支持保存的参数要求不超过10 个。 + + 电子围栏 + 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动 + 轨迹可能超出电子围栏的界限时,系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。 + @attention 电子围栏目前仅支持长方体和点面矢量平面这两种形状,并且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境。 + + 虚拟墙 + 虚拟墙功能支持在电流环拖动示教与力控拖动示教两种模式下,对拖动范围进行精确限制。在这两种特定的示教模式下,用户可以借助虚拟墙功能,确保 + 机械臂的拖动操作不会超出预设的范围。 + @attention 虚拟墙功能目前支持长方体和球体两种形状,并仅在上述两种示教模式下有效。在其他操作模式下,此功能将自动失效。因此,请确保在正确的操作模式 + 下使用虚拟墙功能,以充分发挥其限制拖动范围的作用。 + """ + + def rm_add_electronic_fence_config(self, electronic_fence: rm_fence_config_t) -> int: + """ + 新增几何模型参数 + + Args: + electronic_fence (rm_fence_config_t): 几何模型参数结构体 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_add_electronic_fence_config(self.handle, electronic_fence) + return tag + + def rm_update_electronic_fence_config(self, electronic_fence: rm_fence_config_t) -> int: + """ + 更新几何模型参数 + + Args: + electronic_fence (rm_fence_config_t): 几何模型参数结构体 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_update_electronic_fence_config(self.handle, electronic_fence) + return tag + + def rm_delete_electronic_fence_config(self, name: str) -> int: + """ + 删除指定几何模型 + + Args: + name (str): 几何模型名称,不超过 10 个字节,支持字母、数字、下划线 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_delete_electronic_fence_config(self.handle, name) + return tag + + def rm_get_electronic_fence_list_names(self) -> dict[str, any]: + """ + 查询所有几何模型名称 + + Returns: + dict[str,any]: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'job_names' (list[str]): 字符串列表,表示所有几何模型名称。 + - 'len' (int): 几何模型名称列表长度 + """ + max_len = 10 + names = (rm_fence_names_t * max_len)() + length = c_int() + ret = rm_get_electronic_fence_list_names( + self.handle, names, byref(length)) + job_names = [names[i].name.decode('utf-8') + for i in range(length.value)] + result_dict = { + 'return_code': ret, + 'job_names': job_names, + 'len': length.value, + } + + return result_dict + + def rm_get_given_electronic_fence_config(self, name: str) -> tuple[int, dict[str, any]]: + """ + 查询指定几何模型参数 + + Args: + name (str): 指定几何模型名称 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回指定几何模型的参数字典,键为rm_fence_config_t结构体的字段名称 + """ + config = rm_fence_config_t() + ret = rm_get_given_electronic_fence_config( + self.handle, name, byref(config)) + return ret, config.to_dict() + + def rm_get_electronic_fence_list_infos(self) -> dict[str, any]: + """ + 查询所有几何模型参数 + + Returns: + _type_: 包含以下键值的字典: + - 'return_code' (int): 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - 'electronic_fence_list' (list[dict]): 几何模型参数列表,。 + - 'len' (int): 几何模型列表长度 + """ + infos = rm_fence_config_list_t() + length = c_int() + ret = rm_get_electronic_fence_list_infos( + self.handle, byref(infos), byref(length)) + result_dict = { + 'return_code': ret, + 'electronic_fence_list': [infos.config[i].to_dict() for i in range(length.value)], + 'len': length.value, + } + + return result_dict + + def rm_set_electronic_fence_enable(self, electronic_fence_enable: rm_electronic_fence_enable_t) -> int: + """ + 设置电子围栏使能状态 + + Args: + electronic_fence_enable (rm_electronic_fence_enable_t): 电子围栏使能状态 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_electronic_fence_enable( + self.handle, electronic_fence_enable) + return tag + + def rm_get_electronic_fence_enable(self) -> tuple[int, dict[str, any]]: + """ + 获取电子围栏使能状态 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回电子围栏使能状态字典,键为rm_electronic_fence_enable_t结构体的字段名称 + """ + enable = rm_electronic_fence_enable_t() + ret = rm_get_electronic_fence_enable(self.handle, byref(enable)) + return ret, enable.to_dict() + + def rm_set_electronic_fence_config(self, electronic_fence: rm_fence_config_t) -> int: + """ + 设置当前电子围栏参数配置 + + Args: + electronic_fence (rm_fence_config_t): 当前电子围栏参数结构体(无需设置电子围栏名称) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_electronic_fence_config(self.handle, electronic_fence) + return tag + + def rm_get_electronic_fence_config(self) -> tuple[int, dict[str, any]]: + """ + 获取当前电子围栏参数 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回当前电子围栏参数字典,键为rm_fence_config_t结构体的字段名称(不返回电子围栏名称) + """ + config = rm_fence_config_t() + ret = rm_get_electronic_fence_config(self.handle, byref(config)) + return ret, config.to_dict() + + def rm_set_virtual_wall_enable(self, virtual_wall_enable: rm_electronic_fence_enable_t) -> int: + """ + 设置虚拟墙使能状态 + + Args: + virtual_wall_enable (rm_electronic_fence_enable_t): 虚拟墙状态结构体 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_virtual_wall_enable(self.handle, virtual_wall_enable) + return tag + + def rm_get_virtual_wall_enable(self) -> tuple[int, dict[str, any]]: + """ + 获取虚拟墙使能状态 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回虚拟墙使能状态字典,键为rm_electronic_fence_enable_t结构体的字段名称 + """ + enable = rm_electronic_fence_enable_t() + ret = rm_get_virtual_wall_enable(self.handle, byref(enable)) + return ret, enable.to_dict() + + def rm_set_virtual_wall_config(self, virtual_wall: rm_fence_config_t) -> int: + """ + 设置当前虚拟墙参数 + + Args: + virtual_wall (rm_fence_config_t): 当前虚拟墙参数(无需设置虚拟墙名称) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_virtual_wall_config(self.handle, virtual_wall) + return tag + + def rm_get_virtual_wall_config(self) -> tuple[int, dict[str, any]]: + """ + 获取当前虚拟墙参数 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回当前虚拟墙参数字典,键为rm_fence_config_t结构体的字段名称(不返回虚拟墙名称) + """ + config = rm_fence_config_t() + ret = rm_get_virtual_wall_config(self.handle, byref(config)) + return ret, config.to_dict() + + +class SelfCollision: + """ + 自碰撞安全检测 + @details 睿尔曼机械臂支持自碰撞安全检测,自碰撞安全检测使能状态下,可确保在轨迹规划、示教等运动过程中机械臂的各个部分不会相互碰撞。 + @attention 以上自碰撞安全检测功能目前只在仿真模式下生效,用于进行预演轨迹与轨迹优化。 + """ + + def rm_set_self_collision_enable(self, enable: bool) -> int: + """ + 设置自碰撞安全检测使能状态 + + Args: + enable (bool): true代表使能,false代表禁使能 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + """ + tag = rm_set_self_collision_enable(self.handle, enable) + return tag + + def rm_get_self_collision_enable(self) -> tuple[int, bool]: + """ + 获取自碰撞安全检测使能状态 + + Returns: + tuple[int,bool]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -bool 返回自碰撞安全检测使能状态,true代表使能,false代表禁使能 + """ + enable = c_bool() + tag = rm_get_self_collision_enable(self.handle, byref(enable)) + return tag, enable.value + + +class UdpConfig: + """ + UDP 主动上报配置 + @details 睿尔曼机械臂提供 UDP 机械臂状态主动上报接口,使用时,需要和机械臂处于同一局域网络下,通过设置主动上报配置接口的目标 IP或和机械臂建立 TCP 连接, + 机械臂即会主动周期性上报机械臂状态数据,数据周期可配置,默认 5ms。 + @attention 配置正确并开启三线程模式后,通过注册回调函数可接收并处理主动上报数据。 + """ + + def rm_set_realtime_push(self, config: rm_realtime_push_config_t) -> int: + """ + 设置 UDP 机械臂状态主动上报配置 + + Args: + config (rm_realtime_push_config_t): UDP配置结构体 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + tag = rm_set_realtime_push(self.handle, config) + return tag + + def rm_get_realtime_push(self) -> tuple[int, dict[str, any]]: + """ + 查询 UDP 机械臂状态主动上报配置 + + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + -dict[str,any] 返回 UDP 机械臂状态主动上报配置字典,键为rm_realtime_push_config_t结构体的字段名称 + """ + config = rm_realtime_push_config_t() + tag = rm_get_realtime_push(self.handle, byref(config)) + return tag, config.to_dict() + + def rm_realtime_arm_state_call_back(self, arm_state_callback:rm_realtime_arm_state_callback_ptr): + """ + 注册UDP机械臂实时状态主动上报信息回调函数,该回调函数接收rm_realtime_arm_joint_state_t类型数据 + 作为参数,没有返回值 + 当使用三线程,并且UDP机械臂状态主动上报正确配置时,数据会以设定的周期返回 + + Args: + arm_state_callback (rm_realtime_arm_state_callback_ptr): + 机械臂实时状态信息回调函数 + + Notes: + - 需确保打开三线程模式,仅在三线程模式会打开UDP接口接收数据 + - 需确保广播端口号、上报目标IP、是否主动上报等 UDP 机械臂状态主动上报配置正确 + - 需确保防火墙不会阻止数据的接收 + """ + rm_realtime_arm_state_call_back(arm_state_callback) + + +class TrajectoryManage: + """ + 轨迹管理 + @details 轨迹管理功能可以对机械臂的拖动示教轨迹进行管理,包括添加、删除、查询等操作。用户可以通过这些接口,实现对机械臂拖动示教轨迹的增删改查操作, + 从而实现对机械臂运动轨迹的管理和控制。 + """ + def rm_get_trajectory_file_list(self, page_num: int, page_size: int, vague_search: str) -> tuple[int, dict[str, any]]: + """ + 查询多个拖动示教轨迹(第四代控制器接口) + Args: + page_num (int): 页码 + page_size (int): 每页大小 + vague_search (str): 模糊搜索 + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any] 返回符合条件的拖动示教轨迹列表字典,键为rm_trajectory_list_t结构体的字段名称 + """ + trajectory_list = rm_trajectory_list_t() + ret = rm_get_trajectory_file_list( + self.handle, page_num, page_size, vague_search, byref(trajectory_list)) + return ret, trajectory_list.to_dict() + + def rm_set_run_trajectory(self, trajectory_name: str) -> int: + """ + 运行指定拖动示教轨迹(第四代控制器接口) + Args: + trajectory_name (str): 拖动示教轨迹名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_set_run_trajectory(self.handle, trajectory_name) + return tag + + def rm_delete_trajectory_file(self, trajectory_name: str) -> int: + """ + 删除指定拖动示教轨迹(第四代控制器接口) + Args: + trajectory_name (str): 拖动示教轨迹名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_delete_trajectory_file(self.handle, trajectory_name) + return tag + + def rm_save_trajectory_file(self, trajectory_name: str) -> int: + """ + 保存拖动示教轨迹(第四代控制器接口) + Args: + trajectory_name (str): 拖动示教轨迹名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_save_trajectory_file(self.handle, trajectory_name) + return tag + + +class ModbusV4: + """四代控制器Modbus接口类 + @details 四代控制器Modbus接口类,可通过该类提供的接口,实现对四代控制器的Modbus功能的控制。 + @attention 仅在四代控制器上可用。 + """ + def rm_add_modbus_tcp_master(self, modbus_tcp_master: rm_modbus_tcp_master_info_t) -> int: + """ + 添加Modbus TCP主站(第四代控制器接口) + Args: + modbus_tcp_master (rm_modbus_tcp_master_info_t): Modbus TCP主站配置结构体 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_add_modbus_tcp_master(self.handle, modbus_tcp_master) + return tag + + def rm_update_modbus_tcp_master(self, master_name:str, modbus_tcp_master: rm_modbus_tcp_master_info_t) -> int: + """ + 更新Modbus TCP主站(第四代控制器接口) + Args: + master_name (str): Modbus TCP主站名称 + modbus_tcp_master (rm_modbus_tcp_master_t): 要修改的Modbus TCP主站信息 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_update_modbus_tcp_master(self.handle, master_name, modbus_tcp_master) + return tag + + def rm_delete_modbus_tcp_master(self, master_name:str) -> int: + """ + 删除Modbus TCP主站(第四代控制器接口) + Args: + master_name (str): Modbus TCP主站名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_delete_modbus_tcp_master(self.handle, master_name) + return tag + + def rm_get_modbus_tcp_master(self, master_name:str) -> tuple[int, dict[str, any]]: + """ + 查询Modbus TCP主站(第四代控制器接口) + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any] 返回指定Modbus TCP主站信息字典,键为rm_modbus_tcp_master_info_t结构体的字段名称 + """ + master_info = rm_modbus_tcp_master_info_t() + tag = rm_get_modbus_tcp_master(self.handle, master_name, byref(master_info)) + return tag, master_info.to_dict() + + def rm_get_modbus_tcp_master_list(self, page_num: int, page_size: int, vague_search: str) -> tuple[int, dict[str, any]]: + """ + 查询多个Modbus TCP主站(第四代控制器接口) + Args: + page_num (int): 页码 + page_size (int): 每页大小 + vague_search (str): 模糊搜索 + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any] 返回符合条件的Modbus TCP主站列表字典,键为rm_modbus_tcp_master_info_t结构体的字段名称 + """ + master_list = rm_modbus_tcp_master_list_t() + tag = rm_get_modbus_tcp_master_list(self.handle, page_num, page_size, vague_search, byref(master_list)) + return tag, master_list.to_dict() + + def rm_set_controller_rs485_mode(self, mode:int, baudrate:int) -> int: + """ + 设置控制器RS485模式(第四代控制器接口) + Args: + mode (int): 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + baudrate (int): 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_set_controller_rs485_mode(self.handle, mode, baudrate) + return tag + + def rm_get_controller_rs485_mode_v4(self) -> tuple[int, dict[str, any]]: + """ + 获取控制器RS485模式(第四代控制器接口) + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any]: 包含以下键值的字典: + -"mode" (int): 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + -"baudrate" (int): 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + """ + mode = c_int() + baudrate = c_int() + tag = rm_get_controller_rs485_mode_v4(self.handle, byref(mode), byref(baudrate)) + return tag, {'mode':mode.value, 'baudrate':baudrate.value} + + def rm_set_tool_rs485_mode(self, mode:int, baudrate:int) -> int: + """ + 设置工具端RS485模式(第四代控制器接口) + Args: + mode (int): 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + baudrate (int): 波特率(当前支持9600,115200,460800) + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_set_tool_rs485_mode(self.handle, mode, baudrate) + return tag + + def rm_get_tool_rs485_mode_v4(self) -> tuple[int, dict[str, any]]: + """ + 查询工具端RS485模式(第四代控制器接口) + Returns: + tuple[int,dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -dict[str,any]: 包含以下键值的字典: + -"mode" (int): 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + -"baudrate" (int): 波特率(当前支持9600,115200,460800) + """ + mode = c_int() + baudrate = c_int() + tag = rm_get_tool_rs485_mode_v4(self.handle, byref(mode), byref(baudrate)) + return tag, {'mode':mode.value, 'baudrate':baudrate.value} + + def rm_read_modbus_rtu_coils(self, param:rm_modbus_rtu_read_params_t) -> tuple[int, list[int]]: + """ + Modbus RTU协议读线圈(第四代控制器接口) + Args: + param (rm_modbus_rtu_read_params_t): Modbus RTU读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读线圈数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_rtu_coils(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_write_modbus_rtu_coils(self, param:rm_modbus_rtu_write_params_t) -> int: + """ + Modbus RTU协议写线圈(第四代控制器接口) + Args: + param (rm_modbus_rtu_write_params_t): Modbus RTU写入参数结构体 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_write_modbus_rtu_coils(self.handle, param) + return tag + + def rm_read_modbus_rtu_input_status(self, param:rm_modbus_rtu_read_params_t) -> tuple[int, list[int]]: + """ + Modbus RTU协议读离散量输入(第四代控制器接口) + Args: + param (rm_modbus_rtu_read_params_t): Modbus RTU读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读离散量输入数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_rtu_input_status(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_read_modbus_rtu_holding_registers(self, param:rm_modbus_rtu_read_params_t) -> tuple[int, list[int]]: + """ + Modbus RTU协议读保持寄存器(第四代控制器接口) + Args: + param (rm_modbus_rtu_read_params_t): Modbus RTU读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读保持寄存器数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_rtu_holding_registers(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_write_modbus_rtu_registers(self, param:rm_modbus_rtu_write_params_t) -> int: + """ + Modbus RTU协议写保持寄存器(第四代控制器接口) + Args: + param (rm_modbus_rtu_write_params_t): Modbus RTU写入参数结构体 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_write_modbus_rtu_registers(self.handle, param) + return tag + + def rm_read_modbus_rtu_input_registers(self, param:rm_modbus_rtu_read_params_t) -> tuple[int, list[int]]: + """ + Modbus RTU协议读输入寄存器(第四代控制器接口) + Args: + param (rm_modbus_rtu_read_params_t): Modbus RTU读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读输入寄存器数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_rtu_input_registers(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_read_modbus_tcp_coils(self, param:rm_modbus_tcp_read_params_t) -> tuple[int, list[int]]: + """ + Modbus TCP协议读线圈(第四代控制器接口) + Args: + param (rm_modbus_tcp_read_params_t): Modbus TCP读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读线圈数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_tcp_coils(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_write_modbus_tcp_coils(self, param:rm_modbus_tcp_write_params_t) -> int: + """ + Modbus TCP协议写线圈(第四代控制器接口) + Args: + param (rm_modbus_tcp_write_params_t): Modbus TCP写入参数结构体 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_write_modbus_tcp_coils(self.handle, param) + return tag + + def rm_read_modbus_tcp_input_status(self, param:rm_modbus_tcp_read_params_t) -> tuple[int, list[int]]: + """ + Modbus TCP协议读离散量输入(第四代控制器接口) + Args: + param (rm_modbus_tcp_read_params_t): Modbus TCP读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读离散量输入数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_tcp_input_status(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_read_modbus_tcp_holding_registers(self, param:rm_modbus_tcp_read_params_t) -> tuple[int, list[int]]: + """ + Modbus TCP协议读保持寄存器(第四代控制器接口) + Args: + param (rm_modbus_tcp_read_params_t): Modbus TCP读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读保持寄存器数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_tcp_holding_registers(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + + def rm_write_modbus_tcp_registers(self, param:rm_modbus_tcp_write_params_t) -> int: + """ + Modbus TCP协议写保持寄存器(第四代控制器接口) + Args: + param (rm_modbus_tcp_write_params_t): Modbus TCP写入参数结构体 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_write_modbus_tcp_registers(self.handle, param) + return tag + + def rm_read_modbus_tcp_input_registers(self, param:rm_modbus_tcp_read_params_t) -> tuple[int, list[int]]: + """ + Modbus TCP协议读输入寄存器(第四代控制器接口) + Args: + param (rm_modbus_tcp_read_params_t): Modbus TCP读取参数结构体 + Returns: + tuple[int,list[int]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + -list[int] 返回读输入寄存器数据,数组大小为param.num + """ + data = (c_int * param.num)() + tag = rm_read_modbus_tcp_input_registers(self.handle, param, data) + return tag, [data[i] for i in range(param.num)] + +class ActionV4: + """四代控制器末端动作接口类 + @details 四代控制器末端动作接口类,可通过该类提供的接口,实现对四代控制器的末端动作功能的控制。 + @attention 仅在四代控制器上可用。 + """ + + def rm_get_tool_action_list(self, page_num: int, page_size: int, vague_search: str) -> tuple[int, dict[str, any]]: + """ + 获取动作列表(第四代控制器接口) + + Args: + page_num (int): 页码 + page_size (int): 每页大小 + vague_search (str): 模糊搜索 + + Returns: + tuple[int, dict[str,any]]: 包含两个元素的元组。 + -int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口。 + -dict[str,any] 获取到的动作列表字典,键为rm_tool_action_list_t结构体的字段名称 + """ + list = rm_tool_action_list_t() + ret = rm_get_tool_action_list( + self.handle, page_num, page_size, vague_search, byref(list)) + return ret, list.to_dict() + + def rm_run_tool_action(self, action_name: str) -> int: + """ + 运行指定末端动作(第四代控制器接口) + Args: + action_name (str): 末端动作名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + - -5: 当前到位设备校验失败,即当前到位设备不为末端工具动作。 + """ + tag = rm_run_tool_action(self.handle, action_name) + return tag + + def rm_delete_tool_action(self, action_name: str) -> int: + """ + 删除指定末端动作(第四代控制器接口) + Args: + action_name (str): 末端动作名称 + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + tag = rm_delete_tool_action(self.handle, action_name) + return tag + + def rm_save_tool_action(self, action_name: str, selected_array: list, array_size: int, array_type: int) -> int: + """ + 保存末端动作(第四代控制器接口) + Args: + action_name (str): 末端动作名称 + selected_array(list): 保存数组的值 + array_size(int): 保存数组的大小 + array_type(int): 保存数字的类型(0-表示保存类型为hand_pos。 1-表示保存类型为hand_angle) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + c_array = (c_long * array_size)(*selected_array) + array_ptr = cast(c_array, POINTER(c_long)) + tag = rm_save_tool_action(self.handle, action_name, array_ptr, array_size, array_type) + return tag + + def rm_update_tool_action(self, action_name: str, new_name: str, selected_array: list[int], array_size: int, array_type: int) -> int: + """ + 更新末端动作(第四代控制器接口) + Args: + action_name (str): 末端动作名称 + new_name (str): 更新后的末端动作名称 + selected_array(list): 保存数组的值 + array_size(int): 保存数组的大小 + array_type(int): 保存数字的类型(0-表示保存类型为hand_pos。 1-表示保存类型为hand_angle) + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,控制器返回的数据无法识别或不完整等情况。 + - -4: 三代控制器不支持该接口 + """ + # 将Python列表转换为C数组 + c_array = (c_long * array_size)(*selected_array) + array_ptr = cast(c_array, POINTER(c_long)) + tag = rm_update_tool_action(self.handle, action_name, new_name, array_ptr, array_size, array_type) + return tag + + + + +class Algo: + """ + 算法接口 + @details 针对睿尔曼机械臂,提供正逆解、各种位姿参数转换等工具接口。既可通过RoboticArm类连接机械臂使用该类中的成员函数,也可单独使用该类 + """ + + def __init__(self, arm_model: rm_robot_arm_model_e, force_type: rm_force_type_e, arm_dof: int = -1, dh: rm_dh_t = None): + """初始化算法依赖 + + Args: + arm_model (rm_robot_arm_model_e): 机械臂型号 + force_type (rm_force_type_e): 传感器类型 + arm_dof (int, optional): 机械臂自由度,设置机械臂型号为通用型(RM_MODEL_UNIVERSAL_E)时需设置机械臂自由度. Defaults to -1. + dh (rm_dh_t, optional): 根据给定的DH参数判断机械臂类型,设置为None时根据arm_model判断机械臂类型. Defaults to None. + """ + self.handle = rm_robot_handle() + if(dh is not None): + arm_model = rm_robot_arm_model_e.RM_MODEL_UNIVERSAL_E + rm_algo_init_sys_data_by_dh(force_type, dh, arm_dof) + else: + rm_algo_init_sys_data(arm_model, force_type) + + ARM_7DOF_MODELS = { + rm_robot_arm_model_e.RM_MODEL_RM_75_E, + rm_robot_arm_model_e.RM_MODEL_GEN_72_E, + rm_robot_arm_model_e.RM_MODEL_ZM7L_E, + rm_robot_arm_model_e.RM_MODEL_ZM7R_E, + rm_robot_arm_model_e.RM_MODEL_RXL75_E, + rm_robot_arm_model_e.RM_MODEL_RXR75_E, + } + if arm_model == rm_robot_arm_model_e.RM_MODEL_UNIVERSAL_E: + if arm_dof == -1: + raise Exception("arm_dof is not set") + else: + rm_algo_set_robot_dof(arm_dof) + self.arm_dof = arm_dof + elif arm_model in ARM_7DOF_MODELS: + self.arm_dof = 7 + else: + self.arm_dof = 6 + + if(arm_model == rm_robot_arm_model_e.RM_MODEL_ZM7L_E or arm_model == rm_robot_arm_model_e.RM_MODEL_ZM7R_E or + arm_model == rm_robot_arm_model_e.RM_MODEL_RXL75_E or arm_model == rm_robot_arm_model_e.RM_MODEL_RXR75_E): + self.dh_dof = 8 + else: + self.dh_dof = self.arm_dof + + def rm_algo_version(self) -> str: + """获取算法库版本 + + Returns: + str: 算法库版本号 + """ + return rm_algo_version() + + def rm_algo_set_angle(self, x: float, y: float, z: float) -> None: + """设置安装角度 + + Args: + x (float): X轴安装角度 单位° + y (float): Y轴安装角度 单位° + z (float): z轴安装角度 单位° + """ + rm_algo_set_angle(x, y, z) + + def rm_algo_get_angle(self) -> tuple[float, float, float]: + """获取安装角度 + + Returns: + tuple[float,float,float]: 包含三个浮点数的元组,分别代表x、y和z轴的安装角度,单位:° + """ + x = c_float() + y = c_float() + z = c_float() + rm_algo_get_angle(x, y, z) + + return x.value, y.value, z.value + + def rm_algo_set_redundant_parameter_traversal_mode(self, mode: bool) -> None: + """ + 设置逆解求解模式 + + Args: + mode (bool): + - true:遍历模式,冗余参数遍历的求解策略。适于当前位姿跟要求解的位姿差别特别大的应用场景,如MOVJ_P、位姿编辑等,耗时较长 + - false:单步模式,自动调整冗余参数的求解策略。适于当前位姿跟要求解的位姿差别特别小、连续周期控制的场景,如笛卡尔空间规划的位姿求解等,耗时短 + + """ + rm_algo_set_redundant_parameter_traversal_mode(mode) + + def rm_algo_set_workframe(self, frame: rm_frame_t) -> None: + """ + 设置工作坐标系 + + Args: + frame (rm_frame_t): 坐标系数据 + """ + rm_algo_set_workframe(frame) + + def rm_algo_get_curr_workframe(self) -> dict[str, any]: + """ + 获取当前工作坐标系 + + Returns: + dict[str, any]: 返回当前工作坐标系字典,键为rm_frame_t结构体的字段名称 + """ + frame = rm_frame_t() + rm_algo_get_curr_workframe(byref(frame)) + return frame.to_dictionary() + + def rm_algo_set_toolframe(self, frame: rm_frame_t) -> None: + """ + 设置工具坐标系 + + Args: + frame (rm_frame_t): 坐标系数据 + """ + + rm_algo_set_toolframe(frame) + + def rm_algo_get_curr_toolframe(self) -> dict[str, any]: + """ + 获取算法当前工具坐标系 + + Returns: + dict[str, any]: 返回当前工具坐标系字典,键为rm_frame_t结构体的字段名称 + """ + frame = rm_frame_t() + rm_algo_get_curr_toolframe(byref(frame)) + return frame.to_dictionary() + + def rm_algo_set_joint_max_limit(self, joint_limit: list[float]) -> None: + """ + 设置算法关节最大限位 + + Args: + joint_limit (list[float]): 关节最大限位数组,单位:° + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)(*joint_limit) + else: + joint_positions = (c_float * ARM_DOF)(*joint_limit) + rm_algo_set_joint_max_limit(joint_positions) + + def rm_algo_get_joint_max_limit(self) -> list[float]: + """ + 获取算法关节最大限位 + + Returns: + list[float]: 关节最大限位数组,单位:° + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)() + else: + joint_positions = (c_float * ARM_DOF)() + rm_algo_get_joint_max_limit(joint_positions) + return list(joint_positions) + + def rm_algo_set_joint_min_limit(self, joint_limit: list[float]) -> None: + """ + 设置算法关节最小限位 + + Args: + joint_limit (list[float]): 关节最小限位数组,单位:° + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)(*joint_limit) + else: + joint_positions = (c_float * ARM_DOF)(*joint_limit) + rm_algo_set_joint_min_limit(joint_positions) + + def rm_algo_get_joint_min_limit(self) -> list[float]: + """ + 获取算法关节最小限位 + + Returns: + list[float]: 关节最小限位数组,单位:° + """ + if self.arm_dof != 0: + joint_positions = (c_float * self.arm_dof)() + else: + joint_positions = (c_float * ARM_DOF)() + rm_algo_get_joint_min_limit(joint_positions) + return list(joint_positions) + + def rm_algo_set_joint_max_speed(self, joint_limit: list[float]) -> None: + """ + 设置算法关节最大速度 + + Args: + joint_limit (list[float]): 关节最大速度,单位:RPM + """ + if self.arm_dof != 0: + speed = (c_float * self.arm_dof)(*joint_limit) + else: + speed = (c_float * ARM_DOF)(*joint_limit) + rm_algo_set_joint_max_speed(speed) + + def rm_algo_get_joint_max_speed(self) -> list[float]: + """ + 获取算法关节最大速度 + + Returns: + list[float]: 关节最大速度,单位:RPM + """ + if self.arm_dof != 0: + speed = (c_float * self.arm_dof)() + else: + speed = (c_float * ARM_DOF)() + rm_algo_get_joint_max_speed(speed) + return list(speed) + + def rm_algo_set_joint_max_acc(self, joint_limit: list[float]) -> None: + """ + 设置算法关节最大加速度 + + Args: + joint_limit (list[float]): 关节最大加速度,单位:RPM/s + """ + if self.arm_dof != 0: + acc = (c_float * self.arm_dof)(*joint_limit) + else: + acc = (c_float * ARM_DOF)(*joint_limit) + rm_algo_set_joint_max_acc(acc) + + def rm_algo_get_joint_max_acc(self) -> list[float]: + """ + 获取算法关节最大加速度 + + Returns: + list[float]: 关节最大加速度,单位:RPM/s + """ + if self.arm_dof != 0: + acc = (c_float * self.arm_dof)() + else: + acc = (c_float * ARM_DOF)() + rm_algo_get_joint_max_acc(acc) + return list(acc) + + def rm_algo_inverse_kinematics(self, params: rm_inverse_kinematics_params_t) -> tuple[int, list[float]]: + """ + 逆解函数 + + Args: + params (rm_inverse_kinematics_params_t): 逆解输入参数结构体 + + Returns: + tuple[int,list[float]]: 包含两个元素的元组。 + -int 逆解结果 + - 0: 逆解成功 + - 1: 逆解失败 + - -1: 上一时刻关节角度输入为空 + - -2: 目标位姿四元数不合法 + -list[float] 输出的关节角度 单位°,长度为机械臂自由度 + """ + q_out = (c_float * ARM_DOF)() + + ret = rm_algo_inverse_kinematics(self.handle, params, q_out) + out = list(q_out) + return ret, out[:self.arm_dof] + + def rm_algo_inverse_kinematics_all(self, params:rm_inverse_kinematics_params_t) -> rm_inverse_kinematics_all_solve_t: + """ + 计算逆运动学全解(当前仅支持六自由度机器人) + Args: + params(rm_inverse_kinematics_params_t) 逆解输入参数结构体 + Returns: + rm_inverse_kinematics_all_solve_t 逆解的全解结构体 + """ + ret = rm_inverse_kinematics_all_solve_t() + ret = rm_algo_inverse_kinematics_all(self.handle, params) + return ret + + + def rm_algo_ikine_select_ik_solve(self, weight:list[float], params:rm_inverse_kinematics_all_solve_t) -> int: + """ + 从多解中选取最优解(当前仅支持六自由度机器人) + Args: + weight(list[float]) 权重,建议默认值为{1,1,1,1,1,1} + params(rm_inverse_kinematics_all_solve_t) 待选解的全解结构体 + Returns: + int 最优解索引,选解结果为ik_solve.q_solve[i] -1:当前机器人非六自由度,当前仅支持六自由度机器人 + """ + weight_c = (c_float * 6)(*weight) + ret = rm_algo_ikine_select_ik_solve(weight_c, params) + return ret + + + def rm_algo_ikine_check_joint_position_limit(self, q_solve_i:list[float]) -> int: + """ + 检查逆解结果是否超出关节限位(当前仅支持六自由度机器人) + Args: + q_solve_i (list[float]) 一组解,即一组关节角度,单位:° + Returns: + 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 + """ + ret = rm_algo_ikine_check_joint_position_limit(q_solve_i) + return ret + + + def rm_algo_ikine_check_joint_velocity_limit(self, dt:float, q_ref:list[float], q_solve_i:list[float]) -> int: + """ + 检查逆解结果是否超出速度限位(当前仅支持六自由度机器人) + Args: + dt 两帧数据之间的时间间隔,即控制周期,单位sec + q_ref(list[float]) 参考关节角度或者第一帧数据角度,单位:° + q_solve_i (list[float]) 一组解,即一组关节角度,单位:° + Returns: + int 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 + """ + q_ref_c = (c_float * 8)(*q_ref) + q_solve_c = (c_float * 8)(*q_solve_i) + + ret = rm_algo_ikine_check_joint_velocity_limit(dt, q_ref_c, q_solve_c) + return ret + + def rm_algo_calculate_arm_angle_from_config_rm75(self,q_ref:list[float]) -> tuple[int, float]: + """ + 根据参考位形计算臂角大小(仅支持RM75) + Args: + q_ref(list[float]),当前参考位形的关节角度,单位° + Returns: + int: - 0: 求解成功 - -1: 求解失败,或机型非RM75 - -2: q_ref 输入参数非法 + float: 计算结果,当前参考位形对应的臂角大小,单位° + """ + q_ref_c = (c_float * ARM_DOF)(*q_ref) + arm_angle = c_float() + ret = rm_algo_calculate_arm_angle_from_config_rm75(q_ref_c, byref(arm_angle)) + return ret,arm_angle.value + + def rm_algo_inverse_kinematics_rm75_for_arm_angle(self,params:rm_inverse_kinematics_params_t,arm_angle:float) -> tuple[int,list[float]]: + """ + 臂角法求解RM75逆运动学 + Args: + params:rm_inverse_kinematics_params_t,逆解参数结构体 + arm_angle:float,指定轴角大小,单位:° + Returns: + int 0: 求解成功 + -1: 求解失败 + -2: 求解结果超出限位 + -3: 机型非RM75 + list[float]: q_solve,求解结果,单位:° + """ + q_solve = (c_float * ARM_DOF)() + ret = rm_algo_inverse_kinematics_rm75_for_arm_angle(params,arm_angle,q_solve) + out = list(q_solve) + return ret, out[:self.arm_dof] + + + def rm_algo_forward_kinematics(self, joint: list[float], flag: int = 1) -> list[float]: + """ + 正解算法接口 + + Args: + joint (list[float]): 关节角度,单位:° + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 解得目标位姿列表 + """ + if self.arm_dof != 0: + joint = (c_float * self.arm_dof)(*joint) + else: + joint = (c_float * ARM_DOF)(*joint) + pose = rm_algo_forward_kinematics(self.handle, joint) + position = pose.position + euler = pose.euler + qua = pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # 保留三位小数 + # return [round(value, 3) for value in pose_eul] if flag else [round(value, 3) for value in pose_qua] + + def rm_algo_euler2quaternion(self, eul: list[float]) -> list[float]: + """ + 欧拉角转四元数 + + Args: + eul (list[float]): 欧拉角列表[rx.ry,rz],单位:rad + + Returns: + list[float]: 四元数列表[w,x,y,z] + """ + eul = rm_euler_t(*eul) + quat = rm_algo_euler2quaternion(eul) + return [quat.w, quat.x, quat.y, quat.z] + + def rm_algo_quaternion2euler(self, quat: list[float]) -> list[float]: + """ + 四元数转欧拉角 + + Args: + quat (list[float]): 四元数列表[w,x,y,z] + + Returns: + list[float]: 欧拉角列表[rx.ry,rz],单位:rad + """ + quat = rm_quat_t(*quat) + eul = rm_algo_quaternion2euler(quat) + return [eul.rx, eul.ry, eul.rz] + + def rm_algo_euler2matrix(self, eu: list[float]) -> rm_matrix_t: + """ + 欧拉角转旋转矩阵 + + Args: + eu (list[float]): 欧拉角列表[rx.ry,rz],单位:rad + + Returns: + rm_matrix_t: 旋转矩阵 + """ + eu = rm_euler_t(*eu) + matrix = rm_algo_euler2matrix(eu) + return matrix + + def rm_algo_pos2matrix(self, pose: list[float]) -> rm_matrix_t: + """ + 位姿转旋转矩阵 + + Args: + pose (list[float]): 位置姿态列表[x,y,z,rx,ry,rz] + + Returns: + rm_matrix_t: 旋转矩阵 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*pose[:3]) + po1.euler = rm_euler_t(*pose[3:]) + matrix = rm_algo_pos2matrix(po1) + return matrix + + def rm_algo_matrix2pos(self, matrix: rm_matrix_t, flag: int = 1) -> list[float]: + """ + 旋转矩阵转位姿 + + Args: + matrix (rm_matrix_t): 旋转矩阵 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 解得目标位姿 + """ + pose = rm_algo_matrix2pos(matrix) + position = pose.position + euler = pose.euler + qua = pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return pose.to_dict() + + def rm_algo_base2workframe(self, matrix: rm_matrix_t, pose_in_base: rm_pose_t, flag: int = 1) -> list[float]: + """ + 基坐标系转工作坐标系 + + Args: + matrix (rm_matrix_t): 工作坐标系在基坐标系下的矩阵 + pose_in_base (rm_pose_t): 工具端坐标在基坐标系下位姿 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 基坐标系在工作坐标系下的位姿 + """ + pose_in_work = rm_algo_matrix2pos(matrix, pose_in_base) + position = pose_in_work.position + euler = pose_in_work.euler + qua = pose_in_work.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return pose_in_work.to_dict() + + def rm_algo_workframe2base(self, matrix: rm_matrix_t, pose_in_work: rm_pose_t, flag: int = 1) -> list[float]: + """ + 工作坐标系转基坐标系 + + Args: + matrix (rm_matrix_t): 工具端坐标在工作坐标系下矩阵 + pose_in_work (rm_pose_t): 工具端坐标在工作坐标系下位姿 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 工作坐标系在基坐标系下的位姿 + """ + pose_in_base = rm_algo_workframe2base(matrix, pose_in_work) + position = pose_in_base.position + euler = pose_in_base.euler + qua = pose_in_base.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return pose_in_base.to_dict() + + def rm_algo_end2tool(self, eu_end: rm_pose_t, flag: int = 1) -> list[float]: + """ + 末端位姿转成工具位姿 + + Args: + eu_end (rm_pose_t): 基于世界坐标系和默认工具坐标系的末端位姿 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 基于工作坐标系和工具坐标系的末端位姿 + """ + end_pose = rm_algo_end2tool(self.handle, eu_end) + position = end_pose.position + euler = end_pose.euler + qua = end_pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return end_pose.to_dict() + + def rm_algo_tool2end(self, eu_tool: rm_pose_t, flag: int = 1) -> list[float]: + """ + 工具位姿转末端位姿 + + Args: + eu_tool (rm_pose_t): 基于工作坐标系和工具坐标系的末端位姿 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 基于世界坐标系和默认工具坐标系的末端位姿 + """ + end_pose = rm_algo_tool2end(self.handle, eu_tool) + position = end_pose.position + euler = end_pose.euler + qua = end_pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return end_pose.to_dict() + + def rm_algo_rotate_move(self, curr_joint: list[float], rotate_axis: int, rotate_angle: float, choose_axis: rm_pose_t, flag: int = 1) -> list[float]: + """ + 计算环绕运动位姿 + + Args: + curr_joint (list[float]): 当前关节角度 单位° + rotate_axis (int): 旋转轴: 1:x轴, 2:y轴, 3:z轴 + rotate_angle (float): 旋转角度: 旋转角度, 单位(度) + choose_axis (rm_pose_t): 指定计算时使用的坐标系 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 目标位姿 + """ + if self.arm_dof != 0: + curr_joint = (c_float * self.arm_dof)(*curr_joint) + else: + curr_joint = (c_float * ARM_DOF)(*curr_joint) + pose = rm_algo_rotate_move( + self.handle, curr_joint, rotate_axis, rotate_angle, choose_axis) + position = pose.position + euler = pose.euler + qua = pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return pose.to_dict() + + def rm_algo_cartesian_tool(self, curr_joint: list[float], move_lengthx: float, move_lengthy: float, move_lengthz: float, flag: int = 1) -> list[float]: + """ + 计算沿工具坐标系运动位姿 + + Args: + curr_joint (list[float]): 当前关节角度,单位:度 + move_lengthx (float): 沿X轴移动长度,单位:米 + move_lengthy (float): 沿Y轴移动长度,单位:米 + move_lengthz (float): 沿Z轴移动长度,单位:米 + flag (int, optional): 选择姿态表示方式,默认欧拉角表示姿态 + - 0: 返回使用四元数表示姿态的位姿列表[x,y,z,w,x,y,z] + - 1: 返回使用欧拉角表示姿态的位姿列表[x,y,z,rx,ry,rz] + + Returns: + list[float]: 目标位姿 + """ + if self.arm_dof != 0: + curr_joint = (c_float * self.arm_dof)(*curr_joint) + else: + curr_joint = (c_float * ARM_DOF)(*curr_joint) + pose = rm_algo_cartesian_tool( + self.handle, curr_joint, move_lengthx, move_lengthy, move_lengthz) + position = pose.position + euler = pose.euler + qua = pose.quaternion + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + pose_qua = [position.x, position.y, + position.z, qua.w, qua.x, qua.y, qua.z] + return pose_eul if flag else pose_qua + # return pose.to_dict() + + def rm_algo_pose_move(self, poseCurrent: list[float], deltaPosAndRot: list[float], frameMode: int) -> list[float]: + """ + 计算Pos和Rot沿某坐标系有一定的位移和旋转角度后,所得到的位姿数据 + + Args: + poseCurrent (list[float]): 当前时刻位姿(欧拉角形式) + deltaPosAndRot (list[float]): 移动及旋转数组,位置移动(单位:m),旋转(单位:度) + frameMode (int): 坐标系模式选择 0:Work(work即可任意设置坐标系),1:Tool + + Returns: + list[float]: 平移旋转后的位姿 + """ + po1 = rm_pose_t() + po1.position = rm_position_t(*poseCurrent[:3]) + po1.euler = rm_euler_t(*poseCurrent[3:]) + + deltaPosAndRot = (c_float * 6)(*deltaPosAndRot) + + pose = rm_algo_pose_move( + self.handle, po1, deltaPosAndRot, frameMode) + + position = pose.position + euler = pose.euler + pose_eul = [position.x, position.y, + position.z, euler.rx, euler.ry, euler.rz] + return pose_eul + + def rm_algo_set_dh(self, dh: rm_dh_t) -> None: + """ + 设置DH参数 + Args: + dh (rm_dh_t): DH参数列表 + """ + rm_algo_set_dh(dh) + + def rm_algo_get_dh(self) -> rm_dh_t: + """ + 获取DH参数 + Returns: + list[float]: DH参数列表 + """ + dh = rm_algo_get_dh() + return dh.to_dict(self.dh_dof) + + def rm_algo_universal_singularity_analyse(self, q:list[float], singluar_value_limit:float) -> int: + """ + 通过分析雅可比矩阵最小奇异值, 判断机器人是否处于奇异状态 + Args: + -q 要判断的关节角度(机械零位描述),单位:° + -singluar_value_limit 最小奇异值阈值,若传NULL,则使用内部默认值,默认值为0.01(该值在0-1之间) + Returns: + int + 0:在当前阈值条件下正常 + -1:表示在当前阈值条件下判断为奇异区 + -2:表示计算失败 + """ + q_c = (c_float * 7)(*q) + # singluar_value_limit_c = (c_float * 6)(*singluar_value_limit) + ret = rm_algo_universal_singularity_analyse(q_c, singluar_value_limit) + return ret + + def rm_algo_kin_singularity_thresholds_init(self)-> None: + """ + 恢复初始阈值(仅适用于解析法分析机器人奇异状态),阈值初始化为:limit_qe=10deg,limit_qw=10deg,limit_d = 0.05m + """ + rm_algo_kin_singularity_thresholds_init() + + def rm_algo_kin_set_singularity_thresholds(self,limit_qe:float,limit_qw:float, limit_d:float)-> None: + """ + 设置自定义阈值(仅适用于解析法分析机器人奇异状态) + Args: + limit_qe 肘部奇异区域范围设置(即J3接近0的范围,若为RML63,则是J3接近-9.68的范围),单位: °,default: 10° + limit_qw 腕部奇异区域范围设置(即J5接近0的范围),单位: °,default: 10° + limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), 单位: m, default: 0.05 + Returns: + None + """ + rm_algo_kin_set_singularity_thresholds(limit_qe,limit_qw,limit_d) + + + + def rm_algo_kin_get_singularity_thresholds(self)-> tuple[float,float,float]: + """ + 获取自定义阈值(仅适用于解析法分析机器人奇异状态) + Args: + None + Returns: + limit_qe 肘部奇异区域范围设置(即J3接近0的范围,若为RML63,则是J3接近-9.68的范围),单位: °,default: 10° + limit_qw 腕部奇异区域范围设置(即J5接近0的范围),单位: °,default: 10° + limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), 单位: m, default: 0.05 + """ + limit_qe = c_float() + limit_qw = c_float() + limit_d = c_float() + rm_algo_kin_get_singularity_thresholds(byref(limit_qe),byref(limit_qw),byref(limit_d)) + return limit_qe.value,limit_qw.value,limit_d.value + + + + def rm_algo_kin_robot_singularity_analyse(self,q:list[float]) -> tuple[int,float]: + """ + 解析法判断机器人是否处于奇异位形(仅支持六自由度) + Args: + q:list[float] 要判断的关节角度,单位° + Returns: + tuple[int,float]: 包含两个元素的元组。 + - int: 0:正常 -1:肩部奇异 -2:肘部奇异 -3:腕部奇异 + - float: 返回腕部中心点到肩部奇异平面的距离,该值越接近0说明越接近肩部奇异,单位m + """ + q_c = (c_float * 6)(*q) + distance_c = c_float() + ret = rm_algo_kin_robot_singularity_analyse(q_c, byref(distance_c)) + return ret, distance_c.value + + + def rm_algo_set_tool_envelope(self, toolSphere_i:int, data:rm_tool_sphere_t) -> None: + """ + 设置工具包络球参数 + Args: + toolSphere_i 工具包络球编号 (0~4) + data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + """ + rm_algo_set_tool_envelope(toolSphere_i, data) + + + def rm_algo_get_tool_envelope(self, toolSphere_i:int) -> rm_tool_sphere_t: + """ + 获取工具包络球参数 + Args: + toolSphere_i 工具rm_get_tool_voltage包络球编号 (0~4) + Returns: + (rm_tool_sphere_t) 工具包络球参数,注意其参数在末端法兰坐标系下描述 + """ + tool_sphere_type = rm_tool_sphere_t() + rm_algo_get_tool_envelope(toolSphere_i, byref(tool_sphere_type)) + return tool_sphere_type + + + def rm_algo_safety_robot_self_collision_detection(self,joint_deg:list[float]) -> int: + """ + 自碰撞检测 + Args: + joint_deg(list[float]) 要判断的关节角度,单位° + Returns: + int + -0: 无碰撞 + 1: 发生碰撞,超出关节限位将被认为发生碰撞 + """ + joint_deg_c = (c_float * 7)(*joint_deg) + ret = rm_algo_safety_robot_self_collision_detection(joint_deg_c) + return ret + + + +class RoboticArm(ArmState, MovePlan, JointConfigSettings, JointConfigReader, ArmTipVelocityParameters, + ToolCoordinateConfig, WorkCoordinateConfig, ArmTeachMove, ArmMotionControl, ControllerConfig, + CommunicationConfig, ControllerIOConfig, EffectorIOConfig, GripperControl, Force, DragTeach, HandControl, ModbusConfig, InstallPos, + ForcePositionControl, ProjectManagement, GlobalWaypointManage, ElectronicFenceConfig, SelfCollision, + UdpConfig, Algo, LiftControl, ExpandControl, TrajectoryManage, ModbusV4, ActionV4): + """机械臂连接、断开、日志设置等操作 + """ + + def __init__(self, mode: rm_thread_mode_e = None): + """初始化线程模式 + + Args: + mode (rm_thread_mode_e): + RM_SINGLE_MODE_E:单线程模式,单线程非阻塞等待数据返回; + RM_DUAL_MODE_E:双线程模式,增加接收线程监测队列中的数据; + RM_TRIPLE_MODE_E:三线程模式,在双线程模式基础上增加线程监测UDP接口数据; + """ + if mode == None: + return + rm_init(mode) + print("current c api version: ", rm_api_version()) + + def rm_create_robot_arm(self, ip: str, port: int, level: int = 3, log_func: CFUNCTYPE = None) -> rm_robot_handle: + """ + 初始化RoboticArm类,创建机械臂连接控制句柄。 + + Args: + ip (str): 机械臂的IP地址。 + port (int): 机械臂的端口号。 + level (int, optional): 日志打印等级,默认为3。 + - 0: debug模式 + - 1: info模式 + - 2: warning模式 + - 3: error模式 + log_func (CFUNCTYPE, optional): 自定义日志打印函数(当前Python版本API暂不支持)。默认为None。 + + Returns: + rm_robot_handle: 机械臂句柄,其中包含机械臂id标识。 + """ + if log_func is None: + rm_set_log_call_back(0, level) + else: + LOGCALLBACK = CFUNCTYPE(UNCHECKED(None), String, c_void_p) + log_func = LOGCALLBACK(log_func) + rm_set_log_call_back(log_func, level) + + # rm_init(thread_mode) + self.handle = rm_create_robot_arm(ip, port) + if self.handle.contents.id == -1: + self.arm_dof = 0 + self.robot_controller_version = 4 + else: + info = rm_robot_info_t() + if rm_get_robot_info(self.handle, info) == 0: + self.arm_dof = info.arm_dof + self.robot_controller_version = info.robot_controller_version + if(info.arm_model == rm_robot_arm_model_e.RM_MODEL_ZM7L_E or info.arm_model == rm_robot_arm_model_e.RM_MODEL_ZM7R_E or + info.arm_model == rm_robot_arm_model_e.RM_MODEL_RXL75_E or info.arm_model == rm_robot_arm_model_e.RM_MODEL_RXR75_E): + self.dh_dof = 8 + else: + self.dh_dof = self.arm_dof + return self.handle.contents + + def rm_delete_robot_arm(self) -> int: + """ + 根据句柄删除机械臂 + + Returns: + int: 0 表示成功,非0 表示失败 + """ + return rm_delete_robot_arm(self.handle) + + @classmethod + def rm_destroy(cls) -> int: + """关闭所有机械臂连接,销毁所有线程 + Returns: + int: 0 表示成功,非0 表示失败 + + """ + return rm_destroy() + + def rm_set_log_save(self, path) -> None: + """保存日志到文件 + + Args: + path (string): 日志保存文件路径 + """ + rm_set_log_save(path) + + def rm_set_timeout(self,timeout: int) -> None: + """ + 设置全局超时时间 + Args: + timeout(int):接收控制器返回指令超时时间,多数接口默认超时时间为500ms,单位ms + """ + rm_set_timeout(timeout) + + def rm_set_arm_run_mode(self, mode: int) -> int: + """设置真实/仿真模式 + + Args: + mode (int): 模式 0:仿真 1:真实 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + """ + return rm_set_arm_run_mode(self.handle, mode) + + def rm_get_arm_run_mode(self) -> tuple[int, int]: + """获取真实/仿真模式 + + Returns: + tuple[int, int]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - int: 模式 0:仿真 1:真实 + """ + mode = c_int() + ret = rm_get_arm_run_mode(self.handle, byref(mode)) + return ret, mode.value + + def rm_set_arm_emergency_stop(self, state:bool) -> int: + """设置机械臂急停状态 + Args: + state (bool): 急停状态,true:急停,false:恢复 + + Returns: + int: 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 三代控制器不支持该接口。 + """ + return rm_set_arm_emergency_stop(self.handle, state) + + def rm_get_robot_info(self) -> tuple[int, dict[str, any]]: + """获取机械臂基本信息 + Returns: + tuple[int, dict[str, any]]: 包含两个元素的元组。 + - int: 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 获取到的机械臂基本信息非法,检查句柄是否已被删除。 + - dict[str, any]: 返回机械臂基本信息字典,键为rm_robot_info_t结构体的字段名称。 + """ + info = rm_robot_info_t() + ret = rm_get_robot_info(self.handle, info) + return ret, info.to_dictionary() #返回字典,也可直接返回info + + def rm_get_arm_event_call_back(self, event_callback: rm_event_callback_ptr): + """注册机械臂事件回调函数 + 当机械臂返回运动到位指令或者文件运行结束指令时会有数据返回 + + Args: + event_callback (rm_event_callback_ptr): 机械臂事件回调函数,该回调函数接收rm_event_push_data_t类型的数据作为参数,没有返回值 + + Notes: + 单线程无法使用该回调函数 + """ + rm_get_arm_event_call_back(event_callback) diff --git a/pyproject.toml b/pyproject.toml index 466951a1..a5e8012c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -6,6 +6,5 @@ readme = "README.md" requires-python = ">=3.12" dependencies = [ "lerobot>=0.4.2", - "Robotic_Arm==1.1.3", "pygame==2.6.1", -] +] \ No newline at end of file diff --git a/uv.lock b/uv.lock index 24fca1b4..4a2e18be 100644 --- a/uv.lock +++ b/uv.lock @@ -1066,7 +1066,7 @@ name = "nvidia-cudnn-cu12" version = "9.5.1.17" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12" }, + { name = "nvidia-cublas-cu12", marker = "sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/2a/78/4535c9c7f859a64781e43c969a3a7e84c54634e319a996d43ef32ce46f83/nvidia_cudnn_cu12-9.5.1.17-py3-none-manylinux_2_28_x86_64.whl", hash = "sha256:30ac3869f6db17d170e0e556dd6cc5eee02647abc31ca856634d5a40f82c15b2", size = 570988386, upload-time = "2024-10-25T19:54:26.39Z" }, @@ -1077,7 +1077,7 @@ name = "nvidia-cufft-cu12" version = "11.3.0.4" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12" }, + { name = "nvidia-nvjitlink-cu12", marker = "sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/8f/16/73727675941ab8e6ffd86ca3a4b7b47065edcca7a997920b831f8147c99d/nvidia_cufft_cu12-11.3.0.4-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:ccba62eb9cef5559abd5e0d54ceed2d9934030f51163df018532142a8ec533e5", size = 200221632, upload-time = "2024-11-20T17:41:32.357Z" }, @@ -1106,9 +1106,9 @@ name = "nvidia-cusolver-cu12" version = "11.7.1.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12" }, - { name = "nvidia-cusparse-cu12" }, - { name = "nvidia-nvjitlink-cu12" }, + { name = "nvidia-cublas-cu12", marker = "sys_platform == 'linux'" }, + { name = "nvidia-cusparse-cu12", marker = "sys_platform == 'linux'" }, + { name = "nvidia-nvjitlink-cu12", marker = "sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/f0/6e/c2cf12c9ff8b872e92b4a5740701e51ff17689c4d726fca91875b07f655d/nvidia_cusolver_cu12-11.7.1.2-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e9e49843a7707e42022babb9bcfa33c29857a93b88020c4e4434656a655b698c", size = 158229790, upload-time = "2024-11-20T17:43:43.211Z" }, @@ -1120,7 +1120,7 @@ name = "nvidia-cusparse-cu12" version = "12.5.4.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12" }, + { name = "nvidia-nvjitlink-cu12", marker = "sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/06/1e/b8b7c2f4099a37b96af5c9bb158632ea9e5d9d27d7391d7eb8fc45236674/nvidia_cusparse_cu12-12.5.4.2-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7556d9eca156e18184b94947ade0fba5bb47d69cec46bf8660fd2c71a4b48b73", size = 216561367, upload-time = "2024-11-20T17:44:54.824Z" }, @@ -1651,10 +1651,10 @@ name = "pyobjc-framework-applicationservices" version = "12.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core" }, - { name = "pyobjc-framework-cocoa" }, - { name = "pyobjc-framework-coretext" }, - { name = "pyobjc-framework-quartz" }, + { name = "pyobjc-core", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-cocoa", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-coretext", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-quartz", marker = "sys_platform != 'linux'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/be/6a/d4e613c8e926a5744fc47a9e9fea08384a510dc4f27d844f7ad7a2d793bd/pyobjc_framework_applicationservices-12.1.tar.gz", hash = "sha256:c06abb74f119bc27aeb41bf1aef8102c0ae1288aec1ac8665ea186a067a8945b", size = 103247, upload-time = "2025-11-14T10:08:52.18Z" } wheels = [ @@ -1670,7 +1670,7 @@ name = "pyobjc-framework-cocoa" version = "12.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core" }, + { name = "pyobjc-core", marker = "sys_platform != 'linux'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/02/a3/16ca9a15e77c061a9250afbae2eae26f2e1579eb8ca9462ae2d2c71e1169/pyobjc_framework_cocoa-12.1.tar.gz", hash = "sha256:5556c87db95711b985d5efdaaf01c917ddd41d148b1e52a0c66b1a2e2c5c1640", size = 2772191, upload-time = "2025-11-14T10:13:02.069Z" } wheels = [ @@ -1686,9 +1686,9 @@ name = "pyobjc-framework-coretext" version = "12.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core" }, - { name = "pyobjc-framework-cocoa" }, - { name = "pyobjc-framework-quartz" }, + { name = "pyobjc-core", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-cocoa", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-quartz", marker = "sys_platform != 'linux'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/29/da/682c9c92a39f713bd3c56e7375fa8f1b10ad558ecb075258ab6f1cdd4a6d/pyobjc_framework_coretext-12.1.tar.gz", hash = "sha256:e0adb717738fae395dc645c9e8a10bb5f6a4277e73cba8fa2a57f3b518e71da5", size = 90124, upload-time = "2025-11-14T10:14:38.596Z" } wheels = [ @@ -1704,8 +1704,8 @@ name = "pyobjc-framework-quartz" version = "12.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core" }, - { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-core", marker = "sys_platform != 'linux'" }, + { name = "pyobjc-framework-cocoa", marker = "sys_platform != 'linux'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/94/18/cc59f3d4355c9456fc945eae7fe8797003c4da99212dd531ad1b0de8a0c6/pyobjc_framework_quartz-12.1.tar.gz", hash = "sha256:27f782f3513ac88ec9b6c82d9767eef95a5cf4175ce88a1e5a65875fee799608", size = 3159099, upload-time = "2025-11-14T10:21:24.31Z" } wheels = [ @@ -1935,23 +1935,12 @@ source = { virtual = "." } dependencies = [ { name = "lerobot" }, { name = "pygame" }, - { name = "robotic-arm" }, ] [package.metadata] requires-dist = [ { name = "lerobot", specifier = ">=0.4.2" }, { name = "pygame", specifier = "==2.6.1" }, - { name = "robotic-arm", specifier = "==1.1.3" }, -] - -[[package]] -name = "robotic-arm" -version = "1.1.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a2/d1/b72f31497f1d45171d49e998f60c5f578e6b6abb7e8623329c173a122728/robotic_arm-1.1.3.tar.gz", hash = "sha256:771e841974d20fb5ffe6e2900b1ca805789cc2f351f12c9e743114d4c43307cf", size = 2617179, upload-time = "2025-11-11T08:20:07.457Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/fd/16/09b350c6128b173c33a51d1f98c1dda7e7f2ddf03d2318370465771101d3/robotic_arm-1.1.3-py3-none-any.whl", hash = "sha256:e01af2313ed02888ce07d11d3b76fe8dc3266e20f1a1e1e9c3372bccd024e896", size = 2631534, upload-time = "2025-11-11T08:20:05.521Z" }, ] [[package]] @@ -2141,7 +2130,7 @@ name = "triton" version = "3.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "setuptools" }, + { name = "setuptools", marker = "sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/24/5f/950fb373bf9c01ad4eb5a8cd5eaf32cdf9e238c02f9293557a2129b9c4ac/triton-3.3.1-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9999e83aba21e1a78c1f36f21bce621b77bcaa530277a50484a7cb4a822f6e43", size = 155669138, upload-time = "2025-05-29T23:39:51.771Z" },