msckf_vio/launch/msckf_vio_euroc.launch

77 lines
2.8 KiB
Plaintext
Raw Permalink Normal View History

2018-01-08 20:41:37 +01:00
<launch>
<arg name="robot" default="firefly_sbx"/>
<arg name="fixed_frame_id" default="world"/>
<arg name="calibration_file"
default="$(find msckf_vio)/config/camchain-imucam-euroc.yaml"/>
<!-- Image Processor Nodelet -->
<include file="$(find msckf_vio)/launch/image_processor_euroc.launch">
<arg name="robot" value="$(arg robot)"/>
<arg name="calibration_file" value="$(arg calibration_file)"/>
</include>
<!-- Msckf Vio Nodelet -->
<group ns="$(arg robot)">
<node pkg="nodelet" type="nodelet" name="vio"
args='standalone msckf_vio/MsckfVioNodelet'
output="screen">
2019-07-12 14:25:41 +02:00
<!-- Filter Flag, 0 = msckf, 1 = photometric, 2 = two -->
2019-07-16 09:53:30 +02:00
<param name="FILTER" value="1"/>
2019-06-25 19:05:53 +02:00
<!-- Debugging Flaggs -->
2019-06-27 18:25:43 +02:00
<param name="StreamPause" value="true"/>
2019-07-16 09:53:30 +02:00
<param name="PrintImages" value="true"/>
2019-06-25 19:05:53 +02:00
<param name="GroundTruth" value="false"/>
2019-07-16 09:53:30 +02:00
<param name="patch_size_n" value="5"/>
<param name="image_scale" value ="1"/>
2019-06-25 19:05:53 +02:00
2018-01-08 20:41:37 +01:00
<!-- Calibration parameters -->
<rosparam command="load" file="$(arg calibration_file)"/>
<param name="publish_tf" value="true"/>
<param name="frame_rate" value="20"/>
<param name="fixed_frame_id" value="$(arg fixed_frame_id)"/>
<param name="child_frame_id" value="odom"/>
<param name="max_cam_state_size" value="20"/>
<param name="position_std_threshold" value="8.0"/>
<param name="rotation_threshold" value="0.2618"/>
<param name="translation_threshold" value="0.4"/>
<param name="tracking_rate_threshold" value="0.5"/>
<!-- Feature optimization config -->
<param name="feature/config/translation_threshold" value="-1.0"/>
<!-- These values should be standard deviation -->
<param name="noise/gyro" value="0.005"/>
<param name="noise/acc" value="0.05"/>
<param name="noise/gyro_bias" value="0.001"/>
<param name="noise/acc_bias" value="0.01"/>
<param name="noise/feature" value="0.035"/>
<param name="initial_state/velocity/x" value="0.0"/>
<param name="initial_state/velocity/y" value="0.0"/>
<param name="initial_state/velocity/z" value="0.0"/>
<!-- These values should be covariance -->
<param name="initial_covariance/velocity" value="0.25"/>
<param name="initial_covariance/gyro_bias" value="0.01"/>
<param name="initial_covariance/acc_bias" value="0.01"/>
<param name="initial_covariance/extrinsic_rotation_cov" value="3.0462e-4"/>
<param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
<remap from="~imu" to="/imu0"/>
<remap from="~cam0_image" to="/cam0/image_raw"/>
<remap from="~cam1_image" to="/cam1/image_raw"/>
2018-01-08 20:41:37 +01:00
<remap from="~features" to="image_processor/features"/>
</node>
</group>
</launch>