diff --git a/launch/blob_detector.launch b/launch/blob_detector.launch new file mode 100644 index 0000000000000000000000000000000000000000..f1685fd3c69428b98b3d48abf1214ca5d64d99ef --- /dev/null +++ b/launch/blob_detector.launch @@ -0,0 +1,42 @@ +<!-- --> +<launch> + + <arg name="config_yaml_file" default="$(find iri_blob_detector)/config/default_params.yaml"/> + + <group ns="usb_cam"> + <node pkg="libuvc_camera" type="camera_node" name="mycam"> + <!-- Parameters used to find the camera --> + <param name="vendor" value="0x046d"/> + <param name="product" value="0x0805"/> + <param name="serial" value="AB659260"/> + <!-- If the above parameters aren't unique, choose the first match: --> + <param name="index" value="0"/> + + <!-- Image size and type --> + <param name="width" value="640"/> + <param name="height" value="480"/> + <!-- choose whichever uncompressed format the camera supports: --> + <param name="video_mode" value="uncompressed"/> <!-- or yuyv/nv12/mjpeg --> + <param name="frame_rate" value="15"/> + + <param name="timestamp_method" value="start"/> <!-- start of frame --> + <param name="camera_info_url" value="file:///tmp/cam.yaml"/> + <param name="auto_exposure" value="0"/> <!-- use aperture_priority auto exposure --> + <param name="auto_exposure_priority" value="0"/> + <param name="exposure_absolute" value="0.90"/> <!-- use aperture_priority auto exposure --> + </node> + </group> + + <node name="blob" + pkg="iri_blob_detector" + type="iri_blob_detector" + output="screen"> + <param name="window_size" value="15"/> + <remap from="/blob/image_in/camera_info" + to="/usb_cam/camera_info"/> + <remap from="/blob/image_in/image_raw" + to="/usb_cam/image_raw"/> + <rosparam file="$(arg config_yaml_file)" command="load" /> + </node> + +</launch> diff --git a/launch/usb_cam_tag.launch b/launch/usb_cam_tag.launch deleted file mode 100644 index 040d9c6a90202a6acf072fb786868a49f7d8cd23..0000000000000000000000000000000000000000 --- a/launch/usb_cam_tag.launch +++ /dev/null @@ -1,36 +0,0 @@ -<!-- --> -<launch> - - <node name="usb_cam" - pkg ="usb_cam" - type="usb_cam_node" - respawn="false" - output="screen"> - <param name="video_device" type="string" value="/dev/video0"/> - <param name="camera_frame_id" type="string" value="usb_cam"/> - <param name="pixel_format" type="string" value="yuyv"/> -<!-- <param name="io_method" type="string" value="mmap"/> - <param name="image_width" type="int" value="1024"/> - <param name="image_height" type="int" value="768"/> - <param name="framerate" type="int" value="30"/> - <param name="pixel_format" type="string" value="yuyv"/> - <param name="camera_info_url" type="string" value="file://$(find iri_blob_detector)/calibration/usb_cam.yaml" /> --> - <remap from="/usb_cam/camera_info" - to="/camera/camera_info"/> - <remap from="/usb_cam/image_raw" - to="/camera/image_raw"/> - </node> - - <node name="blob" - pkg="iri_blob_detector" - type="iri_blob_detector" - output="screen"> - <param name="window_size" value="15"/> - <remap from="/blob/image_in/camera_info" - to="/camera/camera_info"/> - <remap from="/blob/image_in/image_raw" - to="/camera/image_raw"/> - <rosparam file="$(find iri_blob_detector)/config/default_params.yaml" command="load" /> - </node> - -</launch>