-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathnao.launch
62 lines (48 loc) · 2.99 KB
/
nao.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
<launch>
<arg name="force_python" default="true" />
<arg name="nao_ip" default="$(optenv NAO_IP 127.0.0.1)" />
<arg name="nao_port" default="$(optenv NAO_PORT 9559)" />
<arg name="source" default="0" /> <!-- top, bottom, depth -->
<arg name="resolution" default="0" />
<arg name="color_space" default="13" />
<arg name="frame_rate" default="15" />
<arg name="use_ros_time" default="True" />
<arg name="auto_exposition" default="1" />
<arg name="auto_exposure_algo" default="0" />
<arg name="exposure" default="128" />
<arg name="gain" default="128" />
<arg name="brightness" default="128" />
<arg name="contrast" default="64" />
<arg name="saturation" default="128" />
<arg name="hue" default="0" />
<arg name="sharpness" default="0" />
<arg name="auto_white_balance" default="1" />
<arg name="white_balance" default="-50" />
<arg name="frequency" default="16000" />
<node pkg="naoqi_driver_py" type="naoqi_joint_states.py" name="naoqi_joint_states" required="true" args="--pip=$(arg nao_ip) --pport=$(arg nao_port)" />
<!-- upload nao robot model V40 by default-->
<include file="$(find nao_description)/launch/robot_state_publisher.launch" >
<arg name="version" value="V40" />
</include>
<!-- camera-->
<node pkg="naoqi_sensors_py" type="camera.py" name="camera" required="true" args="--pip=$(arg nao_ip) --pport=$(arg nao_port)" output="screen">
<param name="calibration_file_bottom" type="string" value="file://$(find naoqi_sensors_py)/share/nao_camera_bottom_160x120.yaml"/>
<param name="calibration_file_top" type="string" value="file://$(find naoqi_sensors_py)/share/nao_camera_top_160x120.yaml"/>
<param name="resolution" type="int" value="$(arg resolution)" /> <!--QQVGA=0, QVGA=1, VGA=2 -->
<param name="color_space" type="int" value="$(arg color_space)" /> <!-- 9 = YUV422, 11 = RGB, 13 = BGR -->
<param name="frame_rate" type="int" value="$(arg frame_rate)" />
<param name="source" type="int" value="$(arg source)" /> --> <!-- 0 = top, 1 = bottom -->
<param name="auto_exposition" type="int" value="$(arg auto_exposition)" /> <!-- 0 = off, 1 = auto -->
<param name="auto_exposure_algo" type="int" value="$(arg auto_exposure_algo)" /> <!-- 0 = average, 1 = weighted, 2 = adaptive hightlights, 3 = adaptive lowlights-->
<param name="exposure" type="int" value="$(arg exposure)" />
<param name="gain" type="int" value="$(arg gain)" />
<param name="brightness" type="int" value="$(arg brightness)" />
<param name="contrast" type="int" value="$(arg contrast)" />
<param name="saturation" type="int" value="$(arg saturation)" />
<param name="hue" type="int" value="$(arg hue)" />
<param name="sharpness" type="int" value="$(arg sharpness)" />
<param name="auto_white_balance" type="int" value="$(arg auto_white_balance)" />
<param name="white_balance" type="int" value="$(arg white_balance)" />
<param name="use_ros_time" type="bool" value="$(arg use_ros_time)" />
</node>
</launch>