Skip to content

Commit

Permalink
260/270/280/myarm300使用pymycobot提示指定版本范围
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Dec 27, 2024
1 parent 514b05a commit 672dd9c
Show file tree
Hide file tree
Showing 78 changed files with 805 additions and 109 deletions.
14 changes: 12 additions & 2 deletions mecharm/mecharm/scripts/follow_display.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python2
#!/usr/bin/env python3
# -*- coding:utf-8 -*-
import time

Expand All @@ -8,7 +8,17 @@
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.5.3'
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():
Expand Down
2 changes: 1 addition & 1 deletion mecharm/mecharm/scripts/listen_real.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python2
#!/usr/bin/env python3
# -*- coding:utf-8 -*-
# license removed for brevity
import time
Expand Down
12 changes: 11 additions & 1 deletion mecharm/mecharm/scripts/slider_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,17 @@
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.5.3'
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



Expand Down
12 changes: 11 additions & 1 deletion mecharm/mecharm_communication/scripts/mecharm_services.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,17 @@
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.5.3'
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

Expand Down
12 changes: 11 additions & 1 deletion mecharm/mecharm_communication/scripts/mecharm_topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,17 @@
MycobotPumpStatus,
)

from pymycobot.mycobot import MyCobot
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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


class Watcher:
Expand Down
17 changes: 13 additions & 4 deletions mecharm/mecharm_communication/scripts/mecharm_topics_jsnn.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,19 @@
MycobotPumpStatus,
)


# from pymycobot import MyCobot

from pymycobot import MyCobotSocket # pi
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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 import MyCobot

from pymycobot import MyCobotSocket # pi


class Watcher:
Expand Down
14 changes: 12 additions & 2 deletions mecharm/mecharm_communication/scripts/mecharm_topics_pi.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python2
#!/usr/bin/env python
# -*- coding:utf-8 -*-
import time
import os
Expand All @@ -17,7 +17,17 @@
MycobotPumpStatus,
)

from pymycobot import MyCobot
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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

# from pymycobot import MyCobotSocket

Expand Down
12 changes: 11 additions & 1 deletion mecharm/mecharm_communication/scripts/mecharm_topics_seeed.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,17 @@
)


from pymycobot import MyCobot
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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


class Watcher:
Expand Down
13 changes: 11 additions & 2 deletions mecharm/mecharm_moveit/scripts/sync_plan.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,17 @@
import rospy
from sensor_msgs.msg import JointState

from pymycobot.mycobot import MyCobot
# from pymycobot.mypalletizer import MyPalletizer
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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
Expand Down
12 changes: 11 additions & 1 deletion mecharm/mecharm_pi_moveit/scripts/sync_plan.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,17 @@
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.5.3'
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
Expand Down
12 changes: 11 additions & 1 deletion myArm/myarm/scripts/follow_display.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,17 @@
from std_msgs.msg import Header
from visualization_msgs.msg import Marker

from pymycobot.myarm import MyArm
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm


def talker():
Expand Down
12 changes: 11 additions & 1 deletion myArm/myarm/scripts/slider_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,17 @@
import rospy
from sensor_msgs.msg import JointState

from pymycobot.myarm import MyArm
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm


mc = None
Expand Down
16 changes: 12 additions & 4 deletions myArm/myarm_communication/scripts/myarm_services.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,17 @@
import os
import fcntl
from myarm_communication.srv import *

from pymycobot.myarm import MyArm
from pymycobot.myarmc import MyArmC
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm

mc = None

Expand Down Expand Up @@ -57,7 +65,7 @@ def create_handle():
port = rospy.get_param("~port")
baud = rospy.get_param("~baud")
rospy.loginfo("%s,%s" % (port, baud))
mc = MyArmC(port, baud)
mc = MyArm(port, baud)


def create_services():
Expand Down
12 changes: 11 additions & 1 deletion myArm/myarm_communication/scripts/myarm_topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,17 @@
MyArmPumpStatus,
)

from pymycobot.myarm import MyArm
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm


class Watcher:
Expand Down
14 changes: 11 additions & 3 deletions myArm/myarm_communication/scripts/myarm_topics_pi.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,17 @@
MyArmPumpStatus,
)


from pymycobot import MyArm
# from pymyarm import myarmSocket
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm


class Watcher:
Expand Down
12 changes: 11 additions & 1 deletion myArm/myarm_moveit/scripts/sync_plan.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,17 @@
import rospy
from sensor_msgs.msg import JointState

from pymycobot.myarm import MyArm
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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.myarm import MyArm


mc = None
Expand Down
12 changes: 11 additions & 1 deletion mycobot_280/mycobot_280/scripts/follow_display.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,17 @@
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.5.3'
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():
Expand Down
12 changes: 11 additions & 1 deletion mycobot_280/mycobot_280/scripts/follow_display_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,17 @@
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.5.3'
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():
Expand Down
12 changes: 11 additions & 1 deletion mycobot_280/mycobot_280/scripts/listen_real_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,18 @@
from sensor_msgs.msg import JointState
from std_msgs.msg import Header
from mycobot_communication.srv import GetAngles
from pymycobot.mycobot import MyCobot
from rospy import ServiceException
import pymycobot
from packaging import version
# min low version require
MAX_REQUIRE_VERSION = '3.5.3'
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

Expand Down
12 changes: 11 additions & 1 deletion mycobot_280/mycobot_280/scripts/slider_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,17 @@
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.5.3'
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
Expand Down
Loading

0 comments on commit 672dd9c

Please sign in to comment.