Browse Source

robot_bringup.launch启动时增加机器人的命名空间,方便进行多机器人编队控制

corvin rasp melodic 10 months ago
parent
commit
639f3344fd

+ 0 - 4
src/robot_bringup/launch/get_battery.launch

@@ -1,4 +0,0 @@
-<launch>
-    <node pkg="robot_bringup" type="get_battery_node" name="get_battery_node" output="screen">
-    </node>
-</launch>

+ 49 - 41
src/robot_bringup/launch/robot_bringup.launch

@@ -15,58 +15,66 @@
     20230327:增加使用usb_cam节点的代码,当外接usb相机的时候可以使用该代码.
     20240106:根据环境变量IS_USB_CAMERA来启动不同的摄像头,CSI或者USB类型摄像头.
       需要在.bashrc文件中配置好该变量(export IS_USB_CAMERA=true/false).
+      配置节点运行命名空间,用于机器人编队.
 -->
 <launch>
+    <!-- 配置机器人的命名空间,用于多机器人编队 -->
+    <arg name="robot_ns" default="$(env ROBOT_NS)" />
+
     <!-- 根据环境变量配置的不同摄像头类型来启动对应的摄像头 -->
     <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" />
+    <group ns="$(arg robot_ns)">
+        <!-- (1) startup panda robot urdf description -->
+        <include file="$(find robot_description)/launch/robot_description.launch" />
 
-    <!-- (2) startup mobilebase arduino launch -->
-    <include file="$(find ros_arduino_python)/launch/arduino.launch" />
+        <!-- (2) startup mobilebase arduino launch -->
+        <include file="$(find ros_arduino_python)/launch/arduino.launch" />
 
-    <!-- (3) startup rasp serial imu-6DOF board-->
-    <include file="$(find serial_imu_hat_6dof)/launch/serial_imu_hat.launch" />
+        <!-- (3) startup rasp serial imu-6DOF board-->
+        <include file="$(find serial_imu_hat_6dof)/launch/serial_imu_hat.launch" />
 
-    <!-- (4) startup rasp cam -->
-    <group unless="$(arg is_usb_camera)">
-      <include file="$(find rasp_camera)/launch/rasp_camera.launch" />
-    </group>
+        <!-- (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" />
-        <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>
-    </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" />
+            <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>
+        </group>
 
-    <!-- (5) startup robot_pose_ekf node -->
-    <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
-        <param name="output_frame" value="odom"/>
-        <param name="freq"         value="20.0"/>
-        <param name="odom_used"    value="true"/>
-        <param name="imu_used"     value="true"/>
-        <param name="vo_used"      value="false"/>
-        <param name="debug"        value="false"/>
-        <param name="sensor_timeout" value="1.0"/>
-        <param name="self_diagnose"  value="false"/>
-    </node>
+        <!-- (5) startup robot_pose_ekf node -->
+        <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
+            <param name="output_frame" value="odom"/>
+            <param name="freq"         value="20.0"/>
+            <param name="odom_used"    value="true"/>
+            <param name="imu_used"     value="true"/>
+            <param name="vo_used"      value="false"/>
+            <param name="debug"        value="false"/>
+            <param name="sensor_timeout" value="1.0"/>
+            <param name="self_diagnose"  value="false"/>
+        </node>
 
-    <!-- (6) dwa_local_planner subscribe /odom_ekf topic -->
-    <node pkg="robot_bringup" type="odom_ekf.py" name="odom_ekf_node" output="screen">
-        <remap from="input_topic"  to="/robot_pose_ekf/odom_combined" />
-        <remap from="output_topic" to="/odom_ekf" />
-    </node>
+        <!-- (6) dwa_local_planner subscribe /odom_ekf topic -->
+        <node pkg="robot_bringup" type="odom_ekf.py" name="odom_ekf_node" output="screen">
+            <remap from="input_topic"  to="$(arg robot_ns)/robot_pose_ekf/odom_combined" />
+            <remap from="output_topic" to="$(arg robot_ns)/odom_ekf" />
+        </node>
 
-    <!-- (7) startup get battery oled show -->
-    <include file="$(find robot_bringup)/launch/get_battery.launch"/>
+        <!-- (7) startup get battery oled show -->
+        <node pkg="robot_bringup" type="get_battery_node" name="get_battery_node" output="screen">
+          <param name="bat_topic" value="$(arg robot_ns)/mobilebase_arduino/sensor/batPercent" />
+        </node>
+    </group>
 </launch>
 

+ 6 - 1
src/robot_bringup/src/get_battery.cpp

@@ -19,9 +19,14 @@ void battery_callback(const ros_arduino_msgs::Digital::ConstPtr& msg)
 
 int main(int argc, char **argv)
 {
+    std::string bat_topic;
+
     ros::init(argc, argv, "get_battery_node");
     ros::NodeHandle handle;
-    ros::Subscriber sub_battey = handle.subscribe("/mobilebase_arduino/sensor/batPercent", 1, battery_callback);
+    ros::param::get("~bat_topic", bat_topic);
+
+    ros::Subscriber sub_battey = handle.subscribe(bat_topic, 1, battery_callback);
     ros::spin();
     return 0;
 }
+