forked from IFL-CAMP/easy_handeye
-
Notifications
You must be signed in to change notification settings - Fork 0
/
ur5_kinect_calibration.launch
50 lines (41 loc) · 2.08 KB
/
ur5_kinect_calibration.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
<launch>
<arg name="namespace_prefix" default="ur5_kinect_handeyecalibration" />
<arg name="robot_ip" doc="The IP address of the UR5 robot" />
<arg name="marker_size" doc="Size of the ArUco marker used, in meters" />
<arg name="marker_id" doc="The ID of the ArUco marker used" />
<!-- start the Kinect -->
<include file="$(find freenect_launch)/launch/freenect.launch" >
<arg name="depth_registration" value="true" />
</include>
<!-- start ArUco -->
<node name="aruco_tracker" pkg="aruco_ros" type="single">
<remap from="/camera_info" to="/camera/rgb" />
<remap from="/image" to="/camera/rgb/image_rect_color" />
<param name="image_is_rectified" value="true"/>
<param name="marker_size" value="$(arg marker_size)"/>
<param name="marker_id" value="$(arg marker_id)"/>
<param name="reference_frame" value="camera_link"/>
<param name="camera_frame" value="camera_rgb_optical_frame"/>
<param name="marker_frame" value="camera_marker" />
</node>
<!-- start the robot -->
<include file="$(find ur_bringup)/launch/ur5_bringup.launch">
<arg name="limited" value="true" />
<arg name="robot_ip" value="192.168.0.21" />
</include>
<include file="$(find ur5_moveit_config)/launch/ur5_moveit_planning_execution.launch">
<arg name="limited" value="true" />
</include>
<!-- start easy_handeye -->
<include file="$(find easy_handeye)/launch/calibrate.launch" >
<arg name="namespace_prefix" value="$(arg namespace_prefix)" />
<arg name="eye_on_hand" value="false" />
<arg name="tracking_base_frame" value="camera_link" />
<arg name="tracking_marker_frame" value="camera_marker" />
<arg name="robot_base_frame" value="base_link" />
<arg name="robot_effector_frame" value="wrist_3_link" />
<arg name="freehand_robot_movement" value="false" />
<arg name="robot_velocity_scaling" value="0.5" />
<arg name="robot_acceleration_scaling" value="0.2" />
</include>
</launch>