Browse Source

根据.bashrc中配置的不同摄像头变量来启动对应摄像头,ros代码不用修改

corvin rasp melodic 10 months ago
parent
commit
ee1f67ef9e
1 changed files with 15 additions and 7 deletions
  1. 15 7
      src/robot_bringup/launch/robot_bringup.launch

+ 15 - 7
src/robot_bringup/launch/robot_bringup.launch

@@ -1,5 +1,5 @@
 <!--
-  Copyright: 2016-2023 ROS小课堂 www.corvin.cn
+  Copyright: 2016-2024 ROS小课堂 www.corvin.cn
   Description:robot启动时最先需要启动的launch文件,主要加载各基础功能模块启动.
     首先就需要启动机器人的urdf文件,这样就可以在rviz中可视化显示机器人模型.然后
     启动下位机arduino的程序,上下位机建立连接,这样上位机就可以发送控制命令.接下来
@@ -13,8 +13,13 @@
     20220928:将robot_pose_ekf的数据融合发布频率从10hz提高为20hz,同时将输出的
       tf变换从odom_combined更新为odom,这样就不用在arduino轮式里程计那边发布odom的tf了.
     20230327:增加使用usb_cam节点的代码,当外接usb相机的时候可以使用该代码.
+    20240106:根据环境变量IS_USB_CAMERA来启动不同的摄像头,CSI或者USB类型摄像头.
+      需要在.bashrc文件中配置好该变量(export IS_USB_CAMERA=true/false).
 -->
 <launch>
+    <!-- 根据环境变量配置的不同摄像头类型来启动对应的摄像头 -->
+    <arg name="is_usb_camera" default="$(env IS_USB_CAMERA)" />
+
     <!-- (1) startup panda robot urdf description -->
     <include file="$(find robot_description)/launch/robot_description.launch" />
 
@@ -24,10 +29,13 @@
     <!-- (3) startup rasp serial imu-6DOF board-->
     <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" />
-    <!--
-    <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
+    <!-- (4) startup rasp cam -->
+    <group unless="$(arg is_usb_camera)">
+      <include file="$(find rasp_camera)/launch/rasp_camera.launch" />
+    </group>
+
+    <group if="$(arg is_usb_camera)">
+      <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" />
@@ -37,8 +45,8 @@
         <param name="io_method"       value="mmap"/>
         <param name="framerate"       value="25" />
         <param name="autofocus"       value="true" />
-    </node>
-    -->
+      </node>
+    </group>
 
     <!-- (5) startup robot_pose_ekf node -->
     <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">