Adjust aruco.launch arguments

This commit is contained in:
Oleg Kalachev
2020-08-05 02:06:41 +03:00
committed by GitHub
parent 4fe6f24d16
commit c254691f80

View File

@@ -1,7 +1,10 @@
<launch>
<arg name="aruco_detect" default="false"/>
<arg name="aruco_map" default="false"/>
<arg name="aruco_vpe" default="false"/>
<arg name="aruco_detect" default="false"/> <!-- markers recognition enabled -->
<arg name="aruco_map" default="false"/> <!-- markers map recognition enabled -->
<arg name="aruco_vpe" default="false"/> <!-- markers map positioning enabled -->
<arg name="placement" default="floor"/> <!-- markers placement: floor, ceiling, unknown -->
<arg name="length" default="0.33"/> <!-- not-in-map markers length, m -->
<arg name="map" default="map.txt"/> <!-- markers map file name -->
<!-- For additional help go to https://clover.coex.tech/aruco -->
@@ -12,8 +15,9 @@
<remap from="map_markers" to="aruco_map/markers" if="$(arg aruco_map)"/>
<param name="estimate_poses" value="true"/>
<param name="send_tf" value="true"/>
<param name="known_tilt" value="map"/>
<param name="length" value="0.33"/>
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
<param name="known_tilt" value="map_flipped" if="$(eval position == 'ceiling')"/>
<param name="length" value="$(arg length)"/>
<!-- aruco detector parameters -->
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
@@ -24,8 +28,9 @@
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/>
<param name="map" value="$(find aruco_pose)/map/map.txt"/>
<param name="known_tilt" value="map"/>
<param name="map" value="$(find aruco_pose)/map/$(arg map)"/>
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
<param name="image_axis" value="true"/>
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
<param name="frame_id" value="aruco_map" unless="$(arg aruco_vpe)"/>