Skip to content

Commit

Permalink
增加280 M5和PI ROS 摄像头模组和吸泵配置
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Nov 7, 2023
1 parent 25fdeb5 commit 8a5b5d5
Show file tree
Hide file tree
Showing 28 changed files with 3,535 additions and 77 deletions.
15 changes: 8 additions & 7 deletions mycobot_280/mycobot_280/config/mycobot.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,10 @@ Panels:
- /Status1
- /RobotModel1
- /TF1
- /Marker1
- /TF1/Frames1
- /TF1/Tree1
Splitter Ratio: 0.5
Tree Height: 657
Tree Height: 609
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand Down Expand Up @@ -246,7 +247,7 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 1.2028908729553223
Distance: 1.1026314496994019
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Expand All @@ -262,17 +263,17 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.32539835572242737
Pitch: 0.7153984904289246
Target Frame: <Fixed Frame>
Yaw: 3.0853891372680664
Yaw: 3.8853836059570312
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 954
Height: 906
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000031cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000031c000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c20000031cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000031c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000004000000031c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd00000004000000000000016a000002ecfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002ec000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c2000002ecfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002ec000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d0065010000000000000450000000000000000000000400000002ec00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand Down
23 changes: 23 additions & 0 deletions mycobot_280/mycobot_280/launch/simple_gui_pump.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<launch>
<!-- Select connecting device and serial port ,选择连接设备及串口-->
<arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" />

<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_pump.urdf"/>
<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="false" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF ,将值合并到TF-->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />

<include file="$(find mycobot_communication)/launch/communication_service.launch">
<arg name="port" value="$(arg port)" />
<arg name="baud" value="$(arg baud)" />
</include>
<node name="real_listener" pkg="mycobot_280" type="listen_real.py" />
<node name="simple_gui" pkg="mycobot_280" type="simple_gui.py" />
</launch>
23 changes: 23 additions & 0 deletions mycobot_280/mycobot_280/launch/teleop_keyboard_pump.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<launch>
<!-- Select connecting device and serial port ,选择连接设备及串口-->
<arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" />

<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_pump.urdf"/>
<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="false" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF ,将值合并到TF-->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />

<include file="$(find mycobot_communication)/launch/communication_service.launch">
<arg name="port" value="$(arg port)" />
<arg name="baud" value="$(arg baud)" />
</include>
<!-- listen and pub the real angles ,监听并发布真实角度-->
<node name="real_listener" pkg="mycobot_280" type="listen_real.py" />
</launch>
2 changes: 1 addition & 1 deletion mycobot_280/mycobot_280/launch/test.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_vision.urdf"/>
<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_urdf.urdf"/>
<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="true" />

Expand Down
25 changes: 25 additions & 0 deletions mycobot_280/mycobot_280/launch/test_camera_flange.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<launch>
<!-- <arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" /> -->
<!-- Load file model ,加载文件模型-->
<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_camera_flange.urdf"/>

<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF,将值合并到TF -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui">
<!-- <param name="use_gui" value="$(arg gui)" /> -->
<!-- <rosparam param="source_list" subst_value="true">["joint_states"]</rosparam> -->
</node>
<!-- Open control script -->
<!-- <node name="control_slider" pkg="mycobot_280" type="slider_control.py">
<param name="port" type="string" value="$(arg port)" />
<param name="baud" type="int" value="$(arg baud)" />
</node> -->
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
16 changes: 16 additions & 0 deletions mycobot_280/mycobot_280/launch/test_gripper.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>
<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_gripper_parallel.urdf"/>
<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg gui)" />
<!-- <rosparam param="source_list" subst_value="true">["joint_states"]</rosparam> -->
</node>
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
25 changes: 25 additions & 0 deletions mycobot_280/mycobot_280/launch/test_pump.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<launch>
<!-- <arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" /> -->
<!-- Load file model ,加载文件模型-->
<arg name="model" default="$(find mycobot_description)/urdf/mycobot/mycobot_with_pump.urdf"/>

<arg name="rvizconfig" default="$(find mycobot_280)/config/mycobot.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<!-- Combinejoin values to TF,将值合并到TF -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui">
<!-- <param name="use_gui" value="$(arg gui)" /> -->
<!-- <rosparam param="source_list" subst_value="true">["joint_states"]</rosparam> -->
</node>
<!-- Open control script -->
<!-- <node name="control_slider" pkg="mycobot_280" type="slider_control.py">
<param name="port" type="string" value="$(arg port)" />
<param name="baud" type="int" value="$(arg baud)" />
</node> -->
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
31 changes: 28 additions & 3 deletions mycobot_280/mycobot_280/scripts/simple_gui.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import tkinter as tk
except ImportError:
import Tkinter as tk
from mycobot_communication.srv import GetCoords, SetCoords, GetAngles, SetAngles, GripperStatus
from mycobot_communication.srv import GetCoords, SetCoords, GetAngles, SetAngles, GripperStatus, PumpStatus
import rospy
import time
from rospy import ServiceException
Expand Down Expand Up @@ -36,7 +36,7 @@ def __init__(self, handle):
# 计算 Tk 根窗口的 x 和 y 坐标
x = int((self.ws / 2) - 190)
y = int((self.hs / 2) - 250)
self.win.geometry("430x400+{}+{}".format(x, y))
self.win.geometry("440x440+{}+{}".format(x, y))
# layout,布局
self.set_layout()
# input section,输入部分
Expand All @@ -56,11 +56,18 @@ def __init__(self, handle):

# Gripper switch button,夹爪开关按钮
tk.Button(self.frmLB, text="夹爪(开)", command=self.gripper_open, width=5).grid(
row=1, column=0, sticky="w", padx=3, pady=50
row=1, column=0, sticky="w", padx=3, pady=20
)
tk.Button(self.frmLB, text="夹爪(关)", command=self.gripper_close, width=5).grid(
row=1, column=1, sticky="w", padx=3, pady=2
)

tk.Button(self.frmLB, text=" 吸泵(开)", command=self.pump_open, width=5).grid(
row=2, column=0, sticky="w", padx=3, pady=20
)
tk.Button(self.frmLB, text="吸泵(关)", command=self.pump_close, width=5).grid(
row=2, column=1, sticky="w", padx=3, pady=2
)

def connect_ser(self):
rospy.init_node("simple_gui", anonymous=True, disable_signals=True)
Expand All @@ -70,6 +77,7 @@ def connect_ser(self):
rospy.wait_for_service("get_joint_coords")
rospy.wait_for_service("set_joint_coords")
rospy.wait_for_service("switch_gripper_status")
rospy.wait_for_service("switch_pump_status")
try:
self.get_coords = rospy.ServiceProxy("get_joint_coords", GetCoords)
self.set_coords = rospy.ServiceProxy("set_joint_coords", SetCoords)
Expand All @@ -78,6 +86,9 @@ def connect_ser(self):
self.switch_gripper = rospy.ServiceProxy(
"switch_gripper_status", GripperStatus
)
self.switch_pump = rospy.ServiceProxy(
"switch_pump_status", PumpStatus
)
except:
print("start error ...")
exit(1)
Expand Down Expand Up @@ -372,6 +383,20 @@ def gripper_close(self):
self.switch_gripper(False)
except ServiceException:
pass

def pump_open(self):
try:
self.switch_pump(True,2, 5)
except ServiceException:
# Probably because the method has no return value, the service throws an unhandled error
# 可能由于该方法没有返回值,服务抛出无法处理的错误
pass

def pump_close(self):
try:
self.switch_pump(False, 2, 5)
except ServiceException:
pass

def get_coord_input(self):
# Get the data input by coord and send it to the robotic arm
Expand Down
2 changes: 1 addition & 1 deletion mycobot_280/mycobot_280/scripts/slider_control_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def callback(data):
mc.send_radians(data_list[:6], 80)
gripper_value = int(abs(-0.7-data_list[6])* 117)
print("gripper_value:%s"%gripper_value)
mc.set_gripper_value(gripper_value, 80)
mc.set_gripper_value(gripper_value, 80, 1)


def listener():
Expand Down
13 changes: 12 additions & 1 deletion mycobot_280/mycobot_280/scripts/teleop_keyboard.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
from __future__ import print_function
from mycobot_communication.srv import GetCoords, SetCoords, GetAngles, SetAngles, GripperStatus
from mycobot_communication.srv import GetCoords, SetCoords, GetAngles, SetAngles, GripperStatus, PumpStatus
import rospy
import sys
import select
Expand Down Expand Up @@ -28,6 +28,10 @@
g - open
h - close
Pump control:
b - open
m - close
Other:
1 - Go to init pose
2 - Go to home pose
Expand Down Expand Up @@ -68,6 +72,7 @@ def teleop_keyboard():
rospy.wait_for_service("get_joint_coords")
rospy.wait_for_service("set_joint_coords")
rospy.wait_for_service("switch_gripper_status")
rospy.wait_for_service("switch_pump_status")
print("service ready.")
try:
get_coords = rospy.ServiceProxy("get_joint_coords", GetCoords)
Expand All @@ -76,6 +81,8 @@ def teleop_keyboard():
set_angles = rospy.ServiceProxy("set_joint_angles", SetAngles)
switch_gripper = rospy.ServiceProxy(
"switch_gripper_status", GripperStatus)
switch_pump = rospy.ServiceProxy(
"switch_pump_status", PumpStatus)
except:
print("start error ...")
exit(1)
Expand Down Expand Up @@ -145,6 +152,10 @@ def teleop_keyboard():
switch_gripper(True)
elif key in ["h", "H"]:
switch_gripper(False)
elif key in ["b", "B"]:
switch_pump(True, 2, 5)
elif key in ["m", "M"]:
switch_pump(False, 2, 5)
elif key == "1":
rsp = set_angles(*init_pose)
elif key in "2":
Expand Down
Loading

0 comments on commit 8a5b5d5

Please sign in to comment.