First commit of the code
This commit is contained in:
		
							
								
								
									
										33
									
								
								launch/image_processor_euroc.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										33
									
								
								launch/image_processor_euroc.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,33 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-euroc.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="image_processor"
 | 
			
		||||
      args="standalone msckf_vio/ImageProcessorNodelet"
 | 
			
		||||
      output="screen">
 | 
			
		||||
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
      <param name="grid_row" value="4"/>
 | 
			
		||||
      <param name="grid_col" value="5"/>
 | 
			
		||||
      <param name="grid_min_feature_num" value="3"/>
 | 
			
		||||
      <param name="grid_max_feature_num" value="4"/>
 | 
			
		||||
      <param name="pyramid_levels" value="3"/>
 | 
			
		||||
      <param name="patch_size" value="15"/>
 | 
			
		||||
      <param name="fast_threshold" value="10"/>
 | 
			
		||||
      <param name="max_iteration" value="30"/>
 | 
			
		||||
      <param name="track_precision" value="0.01"/>
 | 
			
		||||
      <param name="ransac_threshold" value="3"/>
 | 
			
		||||
      <param name="stereo_threshold" value="5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										33
									
								
								launch/image_processor_fla.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										33
									
								
								launch/image_processor_fla.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,33 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="fla"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-fla.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="image_processor"
 | 
			
		||||
      args="standalone msckf_vio/ImageProcessorNodelet"
 | 
			
		||||
      output="screen">
 | 
			
		||||
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
      <param name="grid_row" value="4"/>
 | 
			
		||||
      <param name="grid_col" value="5"/>
 | 
			
		||||
      <param name="grid_min_feature_num" value="2"/>
 | 
			
		||||
      <param name="grid_max_feature_num" value="3"/>
 | 
			
		||||
      <param name="pyramid_levels" value="3"/>
 | 
			
		||||
      <param name="patch_size" value="15"/>
 | 
			
		||||
      <param name="fast_threshold" value="10"/>
 | 
			
		||||
      <param name="max_iteration" value="30"/>
 | 
			
		||||
      <param name="track_precision" value="0.01"/>
 | 
			
		||||
      <param name="ransac_threshold" value="3"/>
 | 
			
		||||
      <param name="stereo_threshold" value="5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="sync/imu/imu"/>
 | 
			
		||||
      <remap from="~cam0_image" to="sync/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="sync/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										61
									
								
								launch/msckf_vio_euroc.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										61
									
								
								launch/msckf_vio_euroc.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,61 @@
 | 
			
		||||
<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">
 | 
			
		||||
 | 
			
		||||
      <!-- 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="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										61
									
								
								launch/msckf_vio_fla.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										61
									
								
								launch/msckf_vio_fla.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,61 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="fla"/>
 | 
			
		||||
  <arg name="fixed_frame_id" default="vision"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-fla.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <include file="$(find msckf_vio)/launch/image_processor_fla.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">
 | 
			
		||||
 | 
			
		||||
      <!-- Calibration parameters -->
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
 | 
			
		||||
      <param name="publish_tf" value="true"/>
 | 
			
		||||
      <param name="frame_rate" value="40"/>
 | 
			
		||||
      <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.01"/>
 | 
			
		||||
      <param name="noise/acc" value="0.1"/>
 | 
			
		||||
      <param name="noise/gyro_bias" value="0.005"/>
 | 
			
		||||
      <param name="noise/acc_bias" value="0.05"/>
 | 
			
		||||
      <param name="noise/feature" value="0.03"/>
 | 
			
		||||
 | 
			
		||||
      <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.0001"/>
 | 
			
		||||
      <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="sync/imu/imu"/>
 | 
			
		||||
      <remap from="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										7
									
								
								launch/reset.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										7
									
								
								launch/reset.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,7 @@
 | 
			
		||||
<launch>
 | 
			
		||||
  <arg name="robot" default="fla1"/>
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="rosservice" type="rosservice" name="reset_vio"
 | 
			
		||||
      args="call --wait vio/reset"/>
 | 
			
		||||
  </group>
 | 
			
		||||
</launch>
 | 
			
		||||
		Reference in New Issue
	
	Block a user