From 15e27b7435a54bfa247e0706554d28b742ad5284 Mon Sep 17 00:00:00 2001 From: wangWking <842749351@qq.com> Date: Tue, 23 Jan 2024 18:35:39 +0800 Subject: [PATCH] update port --- Mercury/mercury_b1/scripts/follow_display.py | 10 +++++----- Mercury/mercury_b1/scripts/slider_control.py | 4 ++-- Mercury/mercury_b1_moveit/scripts/sync_plan.py | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Mercury/mercury_b1/scripts/follow_display.py b/Mercury/mercury_b1/scripts/follow_display.py index ca200e49..603ce1e7 100755 --- a/Mercury/mercury_b1/scripts/follow_display.py +++ b/Mercury/mercury_b1/scripts/follow_display.py @@ -14,8 +14,8 @@ def talker(): rospy.init_node("display", anonymous=True) print("Try connect real Mercury...") - port1 = rospy.get_param("~port1", "/dev/ttyTHS1") - port2 = rospy.get_param("~port2", "/dev/ttyS0") + port1 = rospy.get_param("~port1", "/dev/ttyTHS0") + port2 = rospy.get_param("~port2", "/dev/ttyACM0") baud = rospy.get_param("~baud", 115200) print("left arm: {}, baud: {}\n".format(port1, baud)) print("right arm: {}, baud: {}\n".format(port2, baud)) @@ -106,11 +106,11 @@ def talker(): right_coords = r.get_coords() - eye_coords = r.get_angle(11) + eye_coords = [r.get_angle(11)] - head_coords = r.get_angle(12) + head_coords = [r.get_angle(12)] - body_coords = r.get_angle(13) + body_coords = [r.get_angle(13)] # marker marker_.header.stamp = rospy.Time.now() diff --git a/Mercury/mercury_b1/scripts/slider_control.py b/Mercury/mercury_b1/scripts/slider_control.py index 48fe1bc1..cbe27020 100755 --- a/Mercury/mercury_b1/scripts/slider_control.py +++ b/Mercury/mercury_b1/scripts/slider_control.py @@ -52,8 +52,8 @@ def listener(): rospy.init_node("control_slider", anonymous=True) rospy.Subscriber("joint_states", JointState, callback) - port1 = rospy.get_param("~port1", "/dev/ttyTHS1") - port2 = rospy.get_param("~port2", "/dev/ttyS0") + port1 = rospy.get_param("~port1", "/dev/ttyTHS0") + port2 = rospy.get_param("~port2", "/dev/ttyACM0") baud = rospy.get_param("~baud", 115200) print('left arm: {}, {}'.format(port1, baud)) print('right arm: {}, {}'.format(port2, baud)) diff --git a/Mercury/mercury_b1_moveit/scripts/sync_plan.py b/Mercury/mercury_b1_moveit/scripts/sync_plan.py index 318542e0..3bf53ec5 100755 --- a/Mercury/mercury_b1_moveit/scripts/sync_plan.py +++ b/Mercury/mercury_b1_moveit/scripts/sync_plan.py @@ -52,8 +52,8 @@ def listener(): rospy.init_node("control_slider", anonymous=True) rospy.Subscriber("joint_states", JointState, callback) - port1 = rospy.get_param("~port1", "/dev/ttyTHS1") - port2 = rospy.get_param("~port2", "/dev/ttyS0") + port1 = rospy.get_param("~port1", "/dev/ttyTHS0") + port2 = rospy.get_param("~port2", "/dev/ttyACM0") baud = rospy.get_param("~baud", 115200) print('left arm: {}, {}'.format(port1, baud)) print('right arm: {}, {}'.format(port2, baud))