Chinaunix首页 | 论坛 | 博客
  • 博客访问: 9085632
  • 博文数量: 1732
  • 博客积分: 12961
  • 博客等级: 上将
  • 技术积分: 19830
  • 用 户 组: 普通用户
  • 注册时间: 2009-01-09 11:25
个人简介

偷得浮生半桶水(半日闲), 好记性不如抄下来(烂笔头). 信息爆炸的时代, 学习是一项持续的工作.

文章分类

全部博文(1732)

文章存档

2023年(26)

2022年(112)

2021年(217)

2020年(157)

2019年(192)

2018年(81)

2017年(78)

2016年(70)

2015年(52)

2014年(40)

2013年(51)

2012年(85)

2011年(45)

2010年(231)

2009年(287)

分类: 其他平台

2019-08-23 17:57:40

ROS找ARTag需要两个摄像头. 
1. 首先让两个摄像头的usb_cam加载不同的标定文件.
vertical_ttq.launch

点击(此处)折叠或打开

  1. <launch>
  2.   <node name="v_ttq" pkg="usb_cam" type="usb_cam_node" output="screen" //节点名会被 ARTAG 使用. 输出的报文为节点名为group的域.
  3.     <param name="video_device" value="/dev/video0" />
  4.     <param name="image_width" value="640" />
  5.     <param name="image_height" value="480" />
  6.     <param name="pixel_format" value="yuyv" />
  7.     <param name="camera_frame_id" value="vertical_ttq " /图像报文的 frame_id,在ARTAG进行报文坐标转化时用到.
  8.     <param name="io_method" value="mmap"/>
  9.     <param name="autofocus" value="false"/> <!-- default: 是否自动对焦 -->
  10.     <param name="framerate" value="10"/> <!-- default: 30 -->
  11.     <param name="camera_name" value="ttq_v"/> <!-- 摄像头名字, 标定后的校准文件也需要是这个名字 -->
  12.   </node>

  13.   <node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
  14.     <remap from="image" to="/v_ttq/image_raw"/>
  15.     <param name="autosize" value="true" />
  16.   </node>
  17. </launch>

点击(此处)折叠或打开

  1. 把对应的标定校准文件命名为 ~/.ros/camera_info/ttq_v.yaml  ttq_v的名字必须摄像头说明的标定文件

  2. image_width: 640
    image_height: 480
    camera_name: ttq_v    名字必须和文件名相同
    camera_matrix:
      rows: 3
      cols: 3
      data: [937.201327980486, 0, 311.1737643945229, 0, 933.1201188723156, 261.7306612787383, 0, 0, 1]
    distortion_model: plumb_bob
    distortion_coefficients:
      rows: 1
      cols: 5
      data: [-0.3359625974294541, 0.3303787971606723, 0.001045630984260697, -0.00343677576556448, 0]
    rectification_matrix:
      rows: 3
      cols: 3
      data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
    projection_matrix:
      rows: 3
      cols: 4
      data: [901.9790649414062, 0, 309.2476349179378, 0, 0, 912.2044067382812, 262.8613621604109, 0, 0, 0, 1, 0]
对应的 artag_v_ttq.launch

点击(此处)折叠或打开

  1. <launch>
  2.     <node pkg="tf" type="static_transform_publisher" name="world_to_cam_v_ttq" args="0 0 0 0 0 0 ar_output_v_ttq vertical_ttq 10" />   坐标转化: 报文的frame_id

  3.     <arg name="marker_size" default="9.0" />  //要检测的码的边长. 
  4.     <arg name="max_new_marker_error" default="0.05" />
  5.     <arg name="max_track_error" default="0.05" />
  6.     <arg name="cam_image_topic" default="/v_ttq/image_raw" />
  7.     <arg name="cam_info_topic" default="/v_ttq/camera_info" />  v_ttq 为 摄像头的 node 名字.
  8.     <arg name="output_frame" default="/ar_output_v_ttq" /> 这个用于不同frame_id的报文进行坐标转化时用
  9.     <node name="ar_track_alvar_v_ttq" pkg="ar_track_alvar" type="individualMarkersNoKinect" respawn="false" output="screen">
  10.         <param name="marker_size" type="double" value="$(arg marker_size)" />
  11.         <param name="max_new_marker_error" type="double" value="$(arg max_new_marker_error)" />
  12.         <param name="max_track_error" type="double" value="$(arg max_track_error)" />
  13.         <param name="output_frame" type="string" value="$(arg output_frame)" />
  14.         <remap from="camera_image" to="$(arg cam_image_topic)" />
  15.         <remap from="camera_info" to="$(arg cam_info_topic)" />
  16.         <remap from="ar_pose_marker" to="ar_pose_marker_v_ttq" /> 这是检测到的tag的姿态话题
  17.     </node>
  18. </launch>

另外一个摄像头同理.

ar_track_alvar 占用的资源很大,  如果摄像头相同, 并且Tag也相同的情况, 但是可以考虑把多个 image_raw组装在一起, 让后统一给一个 ar_track_alvar 处理, 应该会省很多资源.

阅读(5124) | 评论(0) | 转发(0) |
给主人留下些什么吧!~~