Browse Source

在robot_bringup.launch中新增加启动usb_cam节点的代码,可以使用外接usb相机

corvin rasp melodic 1 year ago
parent
commit
6afec0e168
1 changed files with 14 additions and 2 deletions
  1. 14 2
      src/robot_bringup/launch/robot_bringup.launch

+ 14 - 2
src/robot_bringup/launch/robot_bringup.launch

@@ -1,5 +1,5 @@
 <!--
-  Copyright: 2016-2022 ROS小课堂 www.corvin.cn
+  Copyright: 2016-2023 ROS小课堂 www.corvin.cn
   Description:robot启动时最先需要启动的launch文件,主要加载各基础功能模块启动.
     首先就需要启动机器人的urdf文件,这样就可以在rviz中可视化显示机器人模型.然后
     启动下位机arduino的程序,上下位机建立连接,这样上位机就可以发送控制命令.接下来
@@ -12,6 +12,7 @@
     20220902:增加启动oled显示屏的launch.
     20220928:将robot_pose_ekf的数据融合发布频率从10hz提高为20hz,同时将输出的
       tf变换从odom_combined更新为odom,这样就不用在arduino轮式里程计那边发布odom的tf了.
+    20230327:增加使用usb_cam节点的代码,当外接usb相机的时候可以使用该代码.
 -->
 <launch>
     <!-- (1) startup panda robot urdf description -->
@@ -24,7 +25,18 @@
     <include file="$(find serial_imu_hat_6dof)/launch/serial_imu_hat.launch" />
 
     <!-- (4) startup rasp cam-->
-    <include file="$(find rasp_camera)/launch/rasp_camera.launch" />
+    <!--<include file="$(find rasp_camera)/launch/rasp_camera.launch" />-->
+    <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
+        <param name="video_device"    value="/dev/video0" />
+        <param name="image_width"     value="640" />
+        <param name="image_height"    value="480" />
+        <param name="pixel_format"    value="yuyv" />
+        <param name="color_format"    value="yuv422p" />
+        <param name="camera_frame_id" value="usb_cam" />
+        <param name="io_method"       value="mmap"/>
+        <param name="framerate"       value="25" />
+        <param name="autofocus"       value="true" />
+    </node>
 
     <!-- (5) startup robot_pose_ekf node -->
     <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">