12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152 |
- <launch>
- <arg name="camera_id" default="/"/>
- <arg name="camera_info_src" default="/camera/camera_info"/>
- <arg name="projection_matrix_src" default="/projection_matrix"/>
- <!-- parameters for points2vscan -->
- <arg name="beam_num" default="1440"/>
- <arg name="step" default="0.1"/>
- <arg name="min_floor" default="-1.0"/>
- <arg name="max_floor" default="-0.5"/>
- <arg name="max_ceiling" default="6.0" />
- <arg name="min_ceiling" default="1.5" />
- <arg name="road_slop_min_height" default="80.0" />
- <arg name="road_slop_max_height" default="30.0" />
- <arg name="rotation" default="3" />
- <arg name="obstacle_min_height" default="1" />
- <arg name="max_back_distance" default="1" />
- <arg name="pass_height" default="2" />
- <arg name="max_range" default="80.0" />
- <arg name="min_range" default="3" />
- <arg name="grid_size" default="10.0" />
- <arg name="image_size" default="1000.0" />
- <arg name="sync" default="false" />
- <arg name="points_node" default="points_fused" />
- <node pkg="points2image" type="points2vscan" name="points2vscan" output="screen" >
- <param name="points_node" type="string" value="$(arg points_node)" />
- <param name="BEAMNUM" type="int" value="$(arg beam_num)" />
- <param name="STEP" type="double" value="$(arg step)" />
- <param name="MINFLOOR" type="double" value="$(arg min_floor)" />
- <param name="MAXFLOOR" type="double" value="$(arg max_floor)" />
- <param name="MAXCEILING" type="double" value="$(arg max_ceiling)" />
- <param name="MINCEILING" type="double" value="$(arg min_ceiling)" />
- <param name="ROADSLOPMINHEIGHT" type="double" value="$(arg road_slop_min_height)" />
- <param name="ROADSLOPMAXHEIGHT" type="double" value="$(arg road_slop_max_height)" />
- <param name="ROTATION" type="double" value="$(arg rotation)" />
- <param name="OBSTACLEMINHEIGHT" type="double" value="$(arg obstacle_min_height)" />
- <param name="MAXBACKDISTANCE" type="double" value="$(arg max_back_distance)" />
- <param name="PASSHEIGHT" type="double" value="$(arg pass_height)" />
- <param name="MAXRANGE" type="double" value="$(arg max_range)" />
- <param name="MINRANGE" type="double" value="$(arg min_range)" />
- <param name="GRIDSIZE" type="double" value="$(arg grid_size)" />
- <param name="IMAGESIZE" type="double" value="$(arg image_size)" />
- <param name="SYNC" type="bool" value="$(arg sync)" />
- </node>
- <node pkg="points2image" type="vscan2image" name="vscan2image" output="screen">
- <param name="camera_info_topic" value="$(arg camera_id)$(arg camera_info_src)" />
- <param name="projection_matrix_topic" value="$(arg camera_id)$(arg projection_matrix_src)" />
- </node>
- <node pkg="points2image" type="vscan2linelist" name="vscan2linelist" output="screen" />
- </launch>
|