-
Notifications
You must be signed in to change notification settings - Fork 6
/
rovio_full.launch
75 lines (53 loc) · 3.64 KB
/
rovio_full.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
<launch>
<!-- First the camera node -->
<node name="check_ueye_api" pkg="ueye_cam" type="check_ueye_api" required="true" />
<arg name="nodelet_manager_name" value="nodelet_manager" />
<arg name="camera_name" value="cam0" />
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" />
<node pkg="nodelet" type="nodelet" name="ueye_cam_nodelet"
args="load ueye_cam/ueye_cam_nodelet $(arg nodelet_manager_name)">
<param name="camera_name" type="str" value="$(arg camera_name)" /> <!-- == namespace for topics and services -->
<param name="camera_topic" type="str" value="image_raw" />
<param name="camera_id" type="int" value="0" /> <!-- 0 = any camera; 1+: camera ID -->
<param name="camera_intrinsics_file" type="string" value="" /> <!-- default: ~/.ros/camera_info/<camera_name>.yaml -->
<param name="camera_parameters_file" type="string" value="" /> <!-- default: ~/.ros/camera_conf/<camera_name>.ini -->
<param name="ext_trigger_mode" type="bool" value="True" /> <!-- if False, then camera will operate in free-run mode; otherwise, frames need to be triggered by hardware signal (falling-edge) on digital input pin of camera -->
<!-- Additional camera configuration parameters -->
<param name="color_mode" type="str" value="mono8" /> <!-- valid options: 'rgb8', 'mono8', 'bayer_rggb8' -->
<param name="image_width" type="int" value="320" />
<param name="image_height" type="int" value="240" />
<param name="image_top" type="int" value="-1" /> <!-- -1: center -->
<param name="image_left" type="int" value="-1" /> <!-- -1: center -->
<param name="auto_gain" type="bool" value="False" />
<param name="master_gain" type="int" value="40" />
<param name="red_gain" type="int" value="40" />
<param name="green_gain" type="int" value="40" />
<param name="blue_gain" type="int" value="50" />
<param name="gain_boost" type="bool" value="True" />
<param name="auto_exposure" type="bool" value="False" />
<param name="exposure" type="int" value="20" /> <!-- in ms THIS IS AN IMPORTANT TIMING ISSUE !!!!-->
<param name="auto_white_balance" type="bool" value="False" />
<param name="white_balance_red_offset" type="int" value="0" />
<param name="white_balance_blue_offset" type="int" value="0" />
<param name="EdgeEnhancementFactor" type="int" value="9" />
<param name="flash_delay" type="int" value="0" /> <!-- in us -->
<param name="flash_duration" type="int" value="1000" /> <!-- in us -->
<param name="auto_frame_rate" type="bool" value="False" />
<param name="frame_rate" type="double" value="20.0" />
<param name="output_rate" type="double" value="0.0" /> <!-- >0: throttle rate for publishing frames -->
<param name="pixel_clock" type="int" value="40" />
<param name="flip_upd" type="bool" value="False" />
<param name="flip_lr" type="bool" value="False" />
</node>
<!-- launch the IMU NODE to start sync camera & Link 1 broadcaster -->
<node pkg="mpu6050_serial_to_imu" type="mpu6050_serial_to_imu_node" name="mpu6050_serial_to_imu_node" required="true">
<param name="port" value="/dev/ttyACM0"/>
<!-- node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 /imu/data link1" /-->>
</node>
<!-- launch ROVIO -->
<node pkg="rovio" type="rovio_node" name="rovio" output="screen">
<param name="filter_config" value="$(find rovio)/cfg/rovio.info"/>
<param name="camera0_config" value="$(find rovio)/cfg/ueye_cam400_fisheye.yaml"/>
<remap from="rovio/pose_with_covariance_stamped" to="/mavros/vision_pose/pose_cov"/>
</node>
</launch>