forked from MarkFzp/mobile-aloha
-
Notifications
You must be signed in to change notification settings - Fork 0
/
4arms_teleop.launch
144 lines (120 loc) · 6.65 KB
/
4arms_teleop.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
<launch>
<arg name="robot_model_master" default="wx250s"/>
<arg name="robot_model_puppet" default="vx300s"/>
<arg name="base_link_master" default="base_link"/>
<arg name="base_link_puppet" default="base_link"/>
<arg name="master_modes_left" default="$(find aloha)/config/master_modes_left.yaml"/>
<arg name="puppet_modes_left" default="$(find aloha)/config/puppet_modes_left.yaml"/>
<arg name="master_modes_right" default="$(find aloha)/config/master_modes_right.yaml"/>
<arg name="puppet_modes_right" default="$(find aloha)/config/puppet_modes_right.yaml"/>
<arg name="launch_driver" default="true"/>
<arg name="use_sim" default="false"/>
<arg name="robot_name_master_left" value="master_left"/>
<arg name="robot_name_puppet_left" value="puppet_left"/>
<arg name="robot_name_master_right" value="master_right"/>
<arg name="robot_name_puppet_right" value="puppet_right"/>
<include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch">
<arg name="robot_model" value="$(arg robot_model_master)"/>
<arg name="robot_name" value="$(arg robot_name_master_left)"/>
<arg name="base_link_frame" value="$(arg base_link_master)"/>
<arg name="use_world_frame" value="false"/>
<arg name="use_rviz" value="false"/>
<arg name="mode_configs" value="$(arg master_modes_left)"/>
<arg name="use_sim" value="$(arg use_sim)"/>
</include>
<include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch">
<arg name="robot_model" value="$(arg robot_model_master)"/>
<arg name="robot_name" value="$(arg robot_name_master_right)"/>
<arg name="base_link_frame" value="$(arg base_link_master)"/>
<arg name="use_world_frame" value="false"/>
<arg name="use_rviz" value="false"/>
<arg name="mode_configs" value="$(arg master_modes_right)"/>
<arg name="use_sim" value="$(arg use_sim)"/>
</include>
<include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch">
<arg name="robot_model" value="$(arg robot_model_puppet)"/>
<arg name="robot_name" value="$(arg robot_name_puppet_left)"/>
<arg name="base_link_frame" value="$(arg base_link_puppet)"/>
<arg name="use_world_frame" value="false"/>
<arg name="use_rviz" value="false"/>
<arg name="mode_configs" value="$(arg puppet_modes_left)"/>
<arg name="use_sim" value="$(arg use_sim)"/>
</include>
<include if="$(arg launch_driver)" file="$(find interbotix_xsarm_control)/launch/xsarm_control.launch">
<arg name="robot_model" value="$(arg robot_model_puppet)"/>
<arg name="robot_name" value="$(arg robot_name_puppet_right)"/>
<arg name="base_link_frame" value="$(arg base_link_puppet)"/>
<arg name="use_world_frame" value="false"/>
<arg name="use_rviz" value="false"/>
<arg name="mode_configs" value="$(arg puppet_modes_right)"/>
<arg name="use_sim" value="$(arg use_sim)"/>
</include>
<node
name="master_left_transform_broadcaster"
pkg="tf2_ros"
type="static_transform_publisher"
args="0 -0.25 0 0 0 0 /world /$(arg robot_name_master_left)/base_link"/>
<node
name="master_right_transform_broadcaster"
pkg="tf2_ros"
type="static_transform_publisher"
args="0 -0.25 0 0 0 0 /world /$(arg robot_name_master_right)/base_link"/>
<node
name="puppet_left_transform_broadcaster"
pkg="tf2_ros"
type="static_transform_publisher"
args="0 0.25 0 0 0 0 /world /$(arg robot_name_puppet_left)/base_link"/>
<node
name="puppet_right_transform_broadcaster"
pkg="tf2_ros"
type="static_transform_publisher"
args="0 0.25 0 0 0 0 /world /$(arg robot_name_puppet_right)/base_link"/>
<node name="usb_cam_high" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/CAM_HIGH" />
<param name="framerate" value="60" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="autofocus" value="false"/>
<param name="focus" value="5"/>
<param name="autoexposure" value="true"/>
</node>
<!-- <node name="usb_cam_low" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/CAM_LOW" />
<param name="framerate" value="60" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="autofocus" value="false"/>
<param name="focus" value="35"/>
<param name="autoexposure" value="true"/>
</node> -->
<node name="usb_cam_left_wrist" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/CAM_LEFT_WRIST" />
<param name="framerate" value="60" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="autofocus" value="false"/>
<param name="focus" value="40"/>
<param name="autoexposure" value="true"/>
</node>
<node name="usb_cam_right_wrist" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/CAM_RIGHT_WRIST" />
<param name="framerate" value="60" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="autofocus" value="false"/>
<param name="focus" value="40"/>
<param name="autoexposure" value="true"/>
</node>
</launch>