diff --git a/mycobot_320/mycobot_320/scripts/mycobot_320_follow_display.py b/mycobot_320/mycobot_320/scripts/mycobot_320_follow_display.py
index 52de81a1..2ffd3828 100755
--- a/mycobot_320/mycobot_320/scripts/mycobot_320_follow_display.py
+++ b/mycobot_320/mycobot_320/scripts/mycobot_320_follow_display.py
@@ -7,7 +7,19 @@
from std_msgs.msg import Header
from visualization_msgs.msg import Marker
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
def talker():
diff --git a/mycobot_320/mycobot_320/scripts/mycobot_320_gripper_slider.py b/mycobot_320/mycobot_320/scripts/mycobot_320_gripper_slider.py
index 953196ae..eab02c75 100755
--- a/mycobot_320/mycobot_320/scripts/mycobot_320_gripper_slider.py
+++ b/mycobot_320/mycobot_320/scripts/mycobot_320_gripper_slider.py
@@ -13,7 +13,19 @@
import time
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
mc = None
diff --git a/mycobot_320/mycobot_320/scripts/mycobot_320_slider.py b/mycobot_320/mycobot_320/scripts/mycobot_320_slider.py
index 6eff5a52..bd2276e8 100755
--- a/mycobot_320/mycobot_320/scripts/mycobot_320_slider.py
+++ b/mycobot_320/mycobot_320/scripts/mycobot_320_slider.py
@@ -12,7 +12,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
mc = None
diff --git a/mycobot_320/mycobot_320_communication/CMakeLists.txt b/mycobot_320/mycobot_320_communication/CMakeLists.txt
index 0dc4835f..fe811050 100644
--- a/mycobot_320/mycobot_320_communication/CMakeLists.txt
+++ b/mycobot_320/mycobot_320_communication/CMakeLists.txt
@@ -170,6 +170,7 @@ include_directories(
## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMS
scripts/mycobot_services.py
+ scripts/new_mycobot_services.py
scripts/mycobot_topics.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
diff --git a/mycobot_320/mycobot_320_communication/launch/new_service.launch b/mycobot_320/mycobot_320_communication/launch/new_service.launch
index 13c72f12..ee4be1ab 100644
--- a/mycobot_320/mycobot_320_communication/launch/new_service.launch
+++ b/mycobot_320/mycobot_320_communication/launch/new_service.launch
@@ -4,7 +4,7 @@
-
+
diff --git a/mycobot_320/mycobot_320_communication/launch/new_service_pi.launch b/mycobot_320/mycobot_320_communication/launch/new_service_pi.launch
index bedb7693..3198914e 100644
--- a/mycobot_320/mycobot_320_communication/launch/new_service_pi.launch
+++ b/mycobot_320/mycobot_320_communication/launch/new_service_pi.launch
@@ -4,7 +4,7 @@
-
+
diff --git a/mycobot_320/mycobot_320_communication/scripts/mycobot_services.py b/mycobot_320/mycobot_320_communication/scripts/mycobot_services.py
index 4d9df8b5..cd9e1a8f 100755
--- a/mycobot_320/mycobot_320_communication/scripts/mycobot_services.py
+++ b/mycobot_320/mycobot_320_communication/scripts/mycobot_services.py
@@ -6,7 +6,19 @@
import fcntl
from mycobot_communication.srv import *
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
mc = None
diff --git a/mycobot_320/mycobot_320_communication/scripts/new_mycobot_services.py b/mycobot_320/mycobot_320_communication/scripts/new_mycobot_services.py
new file mode 100755
index 00000000..2767529e
--- /dev/null
+++ b/mycobot_320/mycobot_320_communication/scripts/new_mycobot_services.py
@@ -0,0 +1,217 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+import time
+import rospy
+import os
+import fcntl
+from mycobot_communication.srv import *
+
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
+
+mc = None
+
+# Avoid serial port conflicts and need to be locked
+def acquire(lock_file):
+ open_mode = os.O_RDWR | os.O_CREAT | os.O_TRUNC
+ fd = os.open(lock_file, open_mode)
+
+ pid = os.getpid()
+ lock_file_fd = None
+
+ timeout = 50.0
+ start_time = current_time = time.time()
+ while current_time < start_time + timeout:
+ try:
+ # The LOCK_EX means that only one process can hold the lock
+ # The LOCK_NB means that the fcntl.flock() is not blocking
+ # and we are able to implement termination of while loop,
+ # when timeout is reached.
+ fcntl.flock(fd, fcntl.LOCK_EX | fcntl.LOCK_NB)
+ except (IOError, OSError):
+ pass
+ else:
+ lock_file_fd = fd
+ break
+ print('pid waiting for lock:%d'% pid)
+ time.sleep(1.0)
+ current_time = time.time()
+ if lock_file_fd is None:
+ os.close(fd)
+ return lock_file_fd
+
+
+def release(lock_file_fd):
+ # Do not remove the lockfile:
+ fcntl.flock(lock_file_fd, fcntl.LOCK_UN)
+ os.close(lock_file_fd)
+ return None
+
+
+def create_handle():
+ global mc
+ rospy.init_node("mycobot_services")
+ rospy.loginfo("start ...")
+ port = rospy.get_param("~port")
+ baud = rospy.get_param("~baud")
+ rospy.loginfo("%s,%s" % (port, baud))
+ mc = MyCobot320(port, baud)
+
+
+def create_services():
+ rospy.Service("set_joint_angles", SetAngles, set_angles)
+ rospy.Service("get_joint_angles", GetAngles, get_angles)
+ rospy.Service("set_joint_coords", SetCoords, set_coords)
+ rospy.Service("get_joint_coords", GetCoords, get_coords)
+ rospy.Service("switch_gripper_status", GripperStatus, switch_status)
+ rospy.Service("switch_pump_status", PumpStatus, toggle_pump)
+ rospy.loginfo("ready")
+ rospy.spin()
+
+
+def set_angles(req):
+ """set angles,设置角度"""
+ angles = [
+ req.joint_1,
+ req.joint_2,
+ req.joint_3,
+ req.joint_4,
+ req.joint_5,
+ req.joint_6,
+ ]
+ sp = req.speed
+
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ mc.send_angles(angles, sp)
+ release(lock)
+
+ return SetAnglesResponse(True)
+
+
+def get_angles(req):
+ """get angles,获取角度"""
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ angles = mc.get_angles()
+ release(lock)
+ return GetAnglesResponse(*angles)
+
+
+def set_coords(req):
+ coords = [
+ req.x,
+ req.y,
+ req.z,
+ req.rx,
+ req.ry,
+ req.rz,
+ ]
+ sp = req.speed
+ mod = req.model
+
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ mc.send_coords(coords, sp, mod)
+ release(lock)
+
+ return SetCoordsResponse(True)
+
+
+def get_coords(req):
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ coords = mc.get_coords()
+ release(lock)
+ return GetCoordsResponse(*coords)
+
+
+def switch_status(req):
+ """Gripper switch status"""
+ """夹爪开关状态"""
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ if req.Status:
+ mc.set_gripper_state(0, 80)
+ else:
+ mc.set_gripper_state(1, 80)
+ release(lock)
+
+ return GripperStatusResponse(True)
+
+
+def toggle_pump(req):
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ if req.Status:
+ mc.set_basic_output(req.Pin1, 0)
+ mc.set_basic_output(req.Pin2, 0)
+ else:
+ mc.set_basic_output(req.Pin1, 1)
+ mc.set_basic_output(req.Pin2, 1)
+ release(lock)
+ return PumpStatusResponse(True)
+
+
+robot_msg = """
+MyCobot Status
+--------------------------------
+Joint Limit:
+ joint 1: -170 ~ +170
+ joint 2: -170 ~ +170
+ joint 3: -170 ~ +170
+ joint 4: -170 ~ +170
+ joint 5: -170 ~ +170
+ joint 6: -180 ~ +180
+
+Connect Status: %s
+
+Servo Infomation: %s
+
+Servo Temperature: %s
+
+Atom Version: %s
+"""
+
+
+def output_robot_message():
+ connect_status = False
+ servo_infomation = "unknown"
+ servo_temperature = "unknown"
+ atom_version = "unknown"
+
+ if mc:
+ lock = acquire("/tmp/mycobot_lock")
+ cn = mc.is_controller_connected()
+ release(lock)
+ if cn == 1:
+ connect_status = True
+ time.sleep(0.1)
+ lock = acquire("/tmp/mycobot_lock")
+ si = mc.is_all_servo_enable()
+ release(lock)
+ if si == 1:
+ servo_infomation = "all connected"
+
+ print(
+ robot_msg % (connect_status, servo_infomation,
+ servo_temperature, atom_version)
+ )
+
+
+if __name__ == "__main__":
+ # print(MyCobot.__dict__)
+ create_handle()
+ output_robot_message()
+ create_services()
diff --git a/mycobot_320/mycobot_320_gripper_moveit/scripts/sync_plan.py b/mycobot_320/mycobot_320_gripper_moveit/scripts/sync_plan.py
index 953196ae..eab02c75 100755
--- a/mycobot_320/mycobot_320_gripper_moveit/scripts/sync_plan.py
+++ b/mycobot_320/mycobot_320_gripper_moveit/scripts/sync_plan.py
@@ -13,7 +13,19 @@
import time
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
mc = None
diff --git a/mycobot_320/mycobot_320_moveit/scripts/sync_plan.py b/mycobot_320/mycobot_320_moveit/scripts/sync_plan.py
index 5665c3a0..f56db1ad 100755
--- a/mycobot_320/mycobot_320_moveit/scripts/sync_plan.py
+++ b/mycobot_320/mycobot_320_moveit/scripts/sync_plan.py
@@ -5,7 +5,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MAX_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) > version.parse(MAX_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be less than {} . The current version is {}. Please downgrade the library version.'.format(MAX_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot import MyCobot
mc = None
diff --git a/mycobot_320/new_mycobot_320/scripts/mycobot_320_follow_display.py b/mycobot_320/new_mycobot_320/scripts/mycobot_320_follow_display.py
index fdd5423d..ff2b70cc 100755
--- a/mycobot_320/new_mycobot_320/scripts/mycobot_320_follow_display.py
+++ b/mycobot_320/new_mycobot_320/scripts/mycobot_320_follow_display.py
@@ -8,7 +8,19 @@
from std_msgs.msg import Header
from visualization_msgs.msg import Marker
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
def talker():
@@ -19,7 +31,7 @@ def talker():
baud = rospy.get_param("~baud", 115200)
print("port: {}, baud: {}\n".format(port, baud))
try:
- mycobot = MyCobot(port, baud)
+ mycobot = MyCobot320(port, baud)
except Exception as e:
print(e)
print(
diff --git a/mycobot_320/new_mycobot_320/scripts/mycobot_320_gripper_slider.py b/mycobot_320/new_mycobot_320/scripts/mycobot_320_gripper_slider.py
index c8e80644..1e567273 100755
--- a/mycobot_320/new_mycobot_320/scripts/mycobot_320_gripper_slider.py
+++ b/mycobot_320/new_mycobot_320/scripts/mycobot_320_gripper_slider.py
@@ -14,7 +14,19 @@
import math
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -45,7 +57,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyACM0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320/scripts/mycobot_320_slider.py b/mycobot_320/new_mycobot_320/scripts/mycobot_320_slider.py
index 57f22502..b1900469 100755
--- a/mycobot_320/new_mycobot_320/scripts/mycobot_320_slider.py
+++ b/mycobot_320/new_mycobot_320/scripts/mycobot_320_slider.py
@@ -13,7 +13,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -37,7 +49,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyACM0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320/scripts/test.py b/mycobot_320/new_mycobot_320/scripts/test.py
index 6f9a7d39..c624a60e 100755
--- a/mycobot_320/new_mycobot_320/scripts/test.py
+++ b/mycobot_320/new_mycobot_320/scripts/test.py
@@ -1,10 +1,22 @@
# -*- coding: utf-8 -*-
-from pymycobot.mycobot import MyCobot
from pymycobot.genre import Angle
from pymycobot import PI_PORT, PI_BAUD # 当使用树莓派版本的mycobot时,可以引用这两个变量进行MyCobot初始化
import time
+import pymycobot
+from packaging import version
-mc = MyCobot("/dev/ttyACM0", 115200)
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
+
+mc = MyCobot320("/dev/ttyACM0", 115200)
# 通过传递角度参数,让机械臂每个关节移动到对应[0, 0, 0, 0, 0, 0]的位置
mc.send_angles([0, 0, 0, 0, 0, 0], 50)
diff --git a/mycobot_320/new_mycobot_320_gripper_moveit/scripts/sync_plan.py b/mycobot_320/new_mycobot_320_gripper_moveit/scripts/sync_plan.py
index 641fc7ea..f1bddeea 100755
--- a/mycobot_320/new_mycobot_320_gripper_moveit/scripts/sync_plan.py
+++ b/mycobot_320/new_mycobot_320_gripper_moveit/scripts/sync_plan.py
@@ -14,7 +14,19 @@
import math
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -45,7 +57,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyACM0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320_moveit/scripts/sync_plan.py b/mycobot_320/new_mycobot_320_moveit/scripts/sync_plan.py
index 93cfd214..e5043d48 100755
--- a/mycobot_320/new_mycobot_320_moveit/scripts/sync_plan.py
+++ b/mycobot_320/new_mycobot_320_moveit/scripts/sync_plan.py
@@ -6,7 +6,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -30,7 +42,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyACM0")
baud = rospy.get_param("~baud", 115200)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_follow_display.py b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_follow_display.py
index 6a50e817..32471a05 100755
--- a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_follow_display.py
+++ b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_follow_display.py
@@ -7,7 +7,19 @@
from std_msgs.msg import Header
from visualization_msgs.msg import Marker
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
def talker():
@@ -18,7 +30,7 @@ def talker():
baud = rospy.get_param("~baud", 115200)
print("port: {}, baud: {}\n".format(port, baud))
try:
- mycobot = MyCobot(port, baud)
+ mycobot = MyCobot320(port, baud)
except Exception as e:
print(e)
print(
diff --git a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_gripper_slider.py b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_gripper_slider.py
index 84971dd2..f6adce05 100755
--- a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_gripper_slider.py
+++ b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_gripper_slider.py
@@ -14,7 +14,19 @@
import math
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -45,7 +57,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyAMA0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_slider.py b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_slider.py
index cdaab1ad..7bb76adc 100755
--- a/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_slider.py
+++ b/mycobot_320/new_mycobot_320_pi/scripts/mycobot_320_slider.py
@@ -14,7 +14,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -40,7 +52,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyAMA0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320_pi/scripts/test.py b/mycobot_320/new_mycobot_320_pi/scripts/test.py
index fef5a4e0..8910f144 100755
--- a/mycobot_320/new_mycobot_320_pi/scripts/test.py
+++ b/mycobot_320/new_mycobot_320_pi/scripts/test.py
@@ -1,10 +1,21 @@
# -*- coding: utf-8 -*-
-from pymycobot.mycobot import MyCobot
from pymycobot.genre import Angle
from pymycobot import PI_PORT, PI_BAUD # 当使用树莓派版本的mycobot时,可以引用这两个变量进行MyCobot初始化
import time
+import pymycobot
+from packaging import version
-mc = MyCobot("/dev/ttyUSB0", 115200)
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
+mc = MyCobot320("/dev/ttyUSB0", 115200)
# 通过传递角度参数,让机械臂每个关节移动到对应[0, 0, 0, 0, 0, 0]的位置
mc.send_angles([0, 0, 0, 0, 0, 0], 50)
diff --git a/mycobot_320/new_mycobot_320_pi_gripper_moveit/scripts/sync_plan.py b/mycobot_320/new_mycobot_320_pi_gripper_moveit/scripts/sync_plan.py
index adc3372e..9a9f4414 100755
--- a/mycobot_320/new_mycobot_320_pi_gripper_moveit/scripts/sync_plan.py
+++ b/mycobot_320/new_mycobot_320_pi_gripper_moveit/scripts/sync_plan.py
@@ -14,7 +14,19 @@
import math
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -45,7 +57,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyAMA0")
baud = rospy.get_param("~baud", 115200)
print(port, baud)
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)
diff --git a/mycobot_320/new_mycobot_320_pi_moveit/scripts/sync_plan.py b/mycobot_320/new_mycobot_320_pi_moveit/scripts/sync_plan.py
index 79ecebe5..5b59aa14 100755
--- a/mycobot_320/new_mycobot_320_pi_moveit/scripts/sync_plan.py
+++ b/mycobot_320/new_mycobot_320_pi_moveit/scripts/sync_plan.py
@@ -6,7 +6,19 @@
import rospy
from sensor_msgs.msg import JointState
-from pymycobot.mycobot import MyCobot
+import pymycobot
+from packaging import version
+
+# min low version require
+MIN_REQUIRE_VERSION = '3.6.0'
+
+current_verison = pymycobot.__version__
+print('current pymycobot library version: {}'.format(current_verison))
+if version.parse(current_verison) < version.parse(MIN_REQUIRE_VERSION):
+ raise RuntimeError('{}The version of pymycobot library must be greater than {} or higher. The current version is {}. Please upgrade the library version.'.format(MIN_REQUIRE_VERSION, current_verison))
+else:
+ print('pymycobot library version meets the requirements!')
+ from pymycobot.mycobot320 import MyCobot320
mc = None
@@ -30,7 +42,7 @@ def listener():
port = rospy.get_param("~port", "/dev/ttyAMA0")
baud = rospy.get_param("~baud", 115200)
# 115200
- mc = MyCobot(port, baud)
+ mc = MyCobot320(port, baud)
time.sleep(0.05)
mc.set_fresh_mode(1)
time.sleep(0.05)