Browse Source

修改成多机模式

zhuo 4 years ago
parent
commit
b3ffd3af3a

+ 1 - 1
src/rasp_imu_hat_6dof/rasp_imu_hat_6dof/cfg/param.yaml

@@ -12,5 +12,5 @@ pub_data_topic: imu_data
 pub_temp_topic: imu_temp
 yaw_topic: yaw_data
 pub_yposition_topic: yposition_data
-link_name: base_imu_link
+link_name: robot1/base_imu_link
 pub_hz: 120

+ 2 - 2
src/robot_bringup/launch/odom_ekf.py

@@ -42,8 +42,8 @@ class OdomEKF():
     def pub_ekf_odom(self, msg):
         odom = Odometry()
         odom.header = msg.header
-        odom.header.frame_id = '/odom_combined'
-        odom.child_frame_id = 'base_footprint'
+        odom.header.frame_id = 'robot1/odom_combined'
+        odom.child_frame_id = 'robot1/base_footprint'
         odom.pose = msg.pose
 
         self.ekf_pub.publish(odom)

+ 6 - 3
src/robot_bringup/launch/robot_bringup.launch

@@ -14,6 +14,7 @@
     20201019:增加启动树莓派排线CSI摄像头的launch.
 -->
 <launch>
+    <group ns="robot1">
     <!-- (1) startup robot urdf description -->
     <include file="$(find robot_description)/launch/robot_description.launch" />
 
@@ -25,7 +26,8 @@
 
     <!-- (4) startup robot_pose_ekf node -->
     <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
-        <param name="output_frame" value="odom_combined"/>
+        <param name="output_frame" value="robot1/odom_combined"/>
+        <param name="base_footprint_frame" value="robot1/base_footprint"/>
         <param name="freq" value="10.0"/>
         <param name="sensor_timeout" value="1.2"/>
         <param name="odom_used" value="true"/>
@@ -37,8 +39,8 @@
 
     <!-- (5) /odom_combined view in rviz -->
     <node pkg="robot_bringup" type="odom_ekf.py" name="odom_ekf" output="screen">
-        <remap from="input" to="/robot_pose_ekf/odom_combined" />
-        <remap from="output" to="/odom_ekf" />
+        <remap from="input" to="robot_pose_ekf/odom_combined" />
+        <remap from="output" to="odom_ekf" />
     </node>
 
     <!-- (6) startup voice system -->
@@ -46,5 +48,6 @@
 
     <!-- (7) startup rasp camera -->
     <include file="$(find rasp_camera)/launch/rasp_camera.launch" />
+    </group>
 
 </launch>

+ 1 - 0
src/robot_description/launch/robot_description.launch

@@ -25,6 +25,7 @@
     pkg="robot_state_publisher"
     type="robot_state_publisher" >
     <param name="publish_frequency" value="20.0"/>
+    <param name="tf_prefix" value="robot1" />
   </node>
 </launch>
 

+ 7 - 7
src/robot_new_year/cfg/param.yaml

@@ -1,13 +1,13 @@
 robot_id: 1
 
-odom_frame: odom_combined
-base_frame: base_footprint
+odom_frame: /robot1/odom_combined
+base_frame: /robot1/base_footprint
 
-cmd_topic: /cmd_vel
-voice_topic: /voice_system/iflytek_offline_tts_topic
-yaw_service: /imu_node/GetYawData
-gripper_service: /mobilebase_arduino/gripper_angle
-control_service: /mobilebase_arduino/gripper_control
+cmd_topic: /robot1/cmd_vel
+voice_topic: /robot1/voice_system/iflytek_offline_tts_topic
+yaw_service: /robot1/imu_node/GetYawData
+gripper_service: /robot1/mobilebase_arduino/gripper_angle
+control_service: /robot1/mobilebase_arduino/gripper_control
 
 vertical_linear_x_speed: 0.1
 turn_angular_z_speed: -0.8

+ 2 - 2
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -31,8 +31,8 @@ base_controller_rate: 10.0
 base_controller_timeout: 0.7
 
 # For a robot that uses base_footprint, change base_frame to base_footprint
-base_frame: base_footprint
-odom_name: odom
+base_frame: robot1/base_footprint
+odom_name: robot1/odom
 
 # Robot drivetrain parameters
 wheel_diameter: 0.058

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -347,7 +347,7 @@ class BaseController:
             """
 ##########################################################
             odom = Odometry()
-            odom.header.frame_id = self.odom_name
+            odom.header.frame_id = "robot1/odom"
             odom.child_frame_id  = self.base_frame
             odom.header.stamp    = time_now
             odom.pose.pose.position.x  = self.pose_x

+ 1 - 1
src/voice_system/iflytek_offline_tts/launch/iflytek_offline_tts.launch

@@ -6,7 +6,7 @@
     20200324:init this file.
 -->
 <launch>
-  <arg name="TTS_Topic" default="/voice_system/iflytek_offline_tts_topic" />
+  <arg name="TTS_Topic" default="/robot1/voice_system/iflytek_offline_tts_topic" />
 
   <node pkg="iflytek_offline_tts" type="iflytek_offline_tts_node" name="iflytek_offline_tts_node" output="screen">
     <param name="app_id" type="String" value="5d5b9efd" />