From 0a262cb74d6dc4c3c7e790d31ea20c40944c666b Mon Sep 17 00:00:00 2001 From: LihanChen2004 <757003373@qq.com> Date: Thu, 23 Nov 2023 17:17:15 +0800 Subject: [PATCH 1/2] =?UTF-8?q?=F0=9F=93=83=20docs:=20=E4=BF=AE=E6=94=B9RE?= =?UTF-8?q?ADME=E9=93=BE=E6=8E=A5?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README.md | 19 ++----------------- 1 file changed, 2 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index b50cf93..d5dbb11 100644 --- a/README.md +++ b/README.md @@ -1,21 +1,6 @@ # PB_RM_Simulation 深圳北理莫斯科大学 北极熊战队 哨兵导航仿真包 -> 请注意!当前分支为**开发分支**! - -- 2023.10.23 - - 目的:导入[华农步兵真实模型](https://github.com/SCAU-RM-NAV/rm2022_auto_infantry_ws),将 turtlebot 键盘控制器替换为 teleop_twist_keyboard - - DEBUFF:仿真性能极度不足,/scan 话题发布频率几乎为0,/imu 也严重受影响。 - - 测试:经过控制变量后,发现在 RMUC_2023 官方地图中仿真频率严重受限。更换为 华农RMUC 地图后,仿真频率有所改善,再更换为原华农 RM2022 自动步兵赛地图 后发现帧率基本正常。 - - 小结:性能严重不足。地图模型复杂度和车辆模型严重影响仿真频率,此外还发现 单独仿真mid360点云时,也无法达到设定的 10Hz,仅 3~4Hz。**一核有难,八核围观** -- NOW - - 编写决策有限状态机中... - ## 1. 项目介绍 本项目使用麦克纳姆轮仿真小车,附加 Livox mid360 雷达与 IMU,在 2023 RMUC 地图进行导航算法仿真。 @@ -100,7 +85,7 @@ ros2 run teleop_twist_keyboard teleop_twist_keyboard -- 如需更换地图,在 [race.launch.py](/pb_rm_simulation/launch/race.launch.py) 中配置地图路径即可,也可以通过命令行指定地图路径 +- 如需更换地图,在 [rm_simulation.launch.py](/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py) 中配置地图路径即可,也可以通过命令行指定地图路径 ```python declare_world_cmd = DeclareLaunchArgument( @@ -130,7 +115,7 @@ ros2 run teleop_twist_keyboard teleop_twist_keyboard 目前支持 livox 系列部分雷达: avia, HAP, horizon, mid40, mid70, mid360, tele 雷达。 -当前默认使用 mid360 仿真,如需更换其它 Livox 系列雷达进行仿真,请在 [waking_robot.xacro](/pb_rm_simulation/urdf/waking_robot.xacro) 中仿照下述样式修改 +当前默认使用 mid360 仿真,如需更换其它 Livox 系列雷达进行仿真,请在 [waking_robot.xacro](/src/rm_simulation/pb_rm_simulation/urdf/waking_robot.xacro) 中仿照下述样式修改 ```xml -- Gitee From 00d90d22ea6f58cc74f2d035c6714e60a2a3ed2f Mon Sep 17 00:00:00 2001 From: LihanChen2004 <757003373@qq.com> Date: Sat, 25 Nov 2023 18:35:37 +0800 Subject: [PATCH 2/2] =?UTF-8?q?=E2=9C=A8=20feat(pb=5Frm=5Fsimulation):=20?= =?UTF-8?q?=E6=B7=BB=E5=8A=A0=E5=8A=9F=E8=83=BD=EF=BC=9A=E5=91=BD=E4=BB=A4?= =?UTF-8?q?=E8=A1=8C=E9=80=89=E6=8B=A9=E4=BB=BF=E7=9C=9F=E5=9C=B0=E5=9B=BE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README.md | 45 ++----- mapping.sh | 2 +- nav.sh | 2 +- .../launch/rm_simulation.launch.py | 123 ++++++++++-------- 4 files changed, 82 insertions(+), 90 deletions(-) diff --git a/README.md b/README.md index d5dbb11..070dc8a 100644 --- a/README.md +++ b/README.md @@ -77,40 +77,17 @@ ros2 run teleop_twist_keyboard teleop_twist_keyboard | 地图 | 描述 | 来源 | |:---------------------:|:----------:|:---:| -| auto_world.world | 2022 3V3 地图 | [华农](https://github.com/SCAU-RM-NAV/rm2022_auto_infantry_ws) | -| RMUC2023_world | 2023 7V7 地图 | [Robomaster 官方](https://bbs.robomaster.com/thread-22576-1-1.html) | +| auto_world.world | 2022 RMUL-步兵对抗 地图 | [华农](https://github.com/SCAU-RM-NAV/rm2022_auto_infantry_ws) | +| RMUC2023_world | 2023 RMUC 地图 | [Robomaster 官方](https://bbs.robomaster.com/thread-22576-1-1.html) | -当前默认地图为 RMUC2023_world
+当前默认地图为 `RMUC2023_world`
注:在原有基础上增加了重力、摩擦力、材质颜色和室内灯光 +如需更换地图,在终端 launch 时添加参数即可: - -- 如需更换地图,在 [rm_simulation.launch.py](/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py) 中配置地图路径即可,也可以通过命令行指定地图路径 - - ```python - declare_world_cmd = DeclareLaunchArgument( - 'world', - default_value=os.path.join(bringup_dir, 'world', 'RMUC2023_world', 'RMUC2023_world.world'), - # default_value=os.path.join(bringup_dir, 'world', 'auto_world', 'auto_world.world'), - description='Full path to world model file to load' - ) - ``` -- 更换地图后记得修改机器人出生点 - - ```python - # Pose where we want to spawn the robot - ## RMUC2023_world - spawn_x_val = '2.5' - spawn_y_val = '0.0' - spawn_z_val = '0.08' - spawn_yaw_val = '0.0' - - ## auto_world - # spawn_x_val = '0.0' - # spawn_y_val = '0.0' - # spawn_z_val = '0.0' - # spawn_yaw_val = '0.0' - ``` +`ros2 launch pb_rm_simulation rm_simulation.launch.py world:=RMUC`
+or
+`ros2 launch pb_rm_simulation rm_simulation.launch.py world:=RMUL` ## 6. 雷达选择 目前支持 livox 系列部分雷达: avia, HAP, horizon, mid40, mid70, mid360, tele 雷达。 @@ -134,10 +111,6 @@ avia, HAP, horizon, mid40, mid70, mid360, tele 雷达。 4. ~~完成 nav 的适配~~ (忘记记录时间了) -5. 优化键盘控制器 - -6. 根据不同地图适配小车出生点 - -7. 优雅的选择地图 +5. ~~优雅的选择地图,并根据不同地图适配小车出生点~~(2023.11.25完成) -8. 决策树 +6. 决策树 diff --git a/mapping.sh b/mapping.sh index f104864..3f2293b 100755 --- a/mapping.sh +++ b/mapping.sh @@ -1,5 +1,5 @@ colcon build --symlink-install -cmds=( "ros2 launch pb_rm_simulation rm_simulation.launch.py" +cmds=( "ros2 launch pb_rm_simulation rm_simulation.launch.py world:=RMUC" "ros2 launch linefit_ground_segmentation_ros segmentation.launch.py" "ros2 launch fast_lio mapping_mid360.launch.py rviz:=false" "ros2 launch pointcloud_to_laserscan pointcloud_to_laserscan_launch.py" diff --git a/nav.sh b/nav.sh index 1b23298..db657ff 100755 --- a/nav.sh +++ b/nav.sh @@ -1,5 +1,5 @@ colcon build --symlink-install -cmds=( "ros2 launch pb_rm_simulation rm_simulation.launch.py" +cmds=( "ros2 launch pb_rm_simulation rm_simulation.launch.py world:=RMUC" "ros2 launch linefit_ground_segmentation_ros segmentation.launch.py" "ros2 launch fast_lio mapping_mid360.launch.py rviz:=false" "ros2 launch pointcloud_to_laserscan pointcloud_to_laserscan_launch.py" diff --git a/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py b/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py index d9eed58..5a36016 100644 --- a/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py +++ b/src/rm_simulation/pb_rm_simulation/launch/rm_simulation.launch.py @@ -6,30 +6,39 @@ from ament_index_python.packages import get_package_share_directory, get_package from launch import LaunchDescription from launch.substitutions import LaunchConfiguration, Command -from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument, GroupAction from launch.launch_description_sources import PythonLaunchDescriptionSource from launch_ros.actions import Node from launch_ros.parameter_descriptions import ParameterValue - +from launch.conditions import LaunchConfigurationEquals + +# Enum for world types +class WorldType: + RMUC = 'RMUC' + RMUL = 'RMUL' + +def get_world_config(world_type): + world_configs = { + WorldType.RMUC: { + 'x': '2.5', + 'y': '0.0', + 'z': '0.08', + 'yaw': '0.0', + 'world_path': 'RMUC2023_world/RMUC2023_world.world' + }, + WorldType.RMUL: { + 'x': '0.0', + 'y': '0.0', + 'z': '0.15', + 'yaw': '-0.8', + 'world_path': 'auto_world/auto_world.world' + } + } + return world_configs.get(world_type, None) def generate_launch_description(): - - # Pose where we want to spawn the robot - ## RMUC2023_world - spawn_x_val = '2.5' - spawn_y_val = '0.0' - spawn_z_val = '0.08' - spawn_yaw_val = '0.0' - - ## auto_world - # spawn_x_val = '0.0' - # spawn_y_val = '0.0' - # spawn_z_val = '0.0' - # spawn_yaw_val = '0.0' - # Get the launch directory bringup_dir = get_package_share_directory('pb_rm_simulation') - launch_dir = os.path.join(bringup_dir, 'launch') pkg_gazebo_ros = get_package_share_directory('gazebo_ros') # Specify xacro path @@ -42,26 +51,22 @@ def generate_launch_description(): declare_use_sim_time_cmd = DeclareLaunchArgument( 'use_sim_time', default_value='True', - description='Use simulation (Gazebo) clock if true') + description='Use simulation (Gazebo) clock if true' + ) declare_world_cmd = DeclareLaunchArgument( 'world', - default_value=os.path.join(bringup_dir, 'world', 'RMUC2023_world', 'RMUC2023_world.world'), - # default_value=os.path.join(bringup_dir, 'world', 'auto_world', 'auto_world.world'), - description='Full path to world model file to load' + default_value=WorldType.RMUC, + description='Choose or ' ) declare_rviz_config_file_cmd = DeclareLaunchArgument( 'rviz_config_file', default_value=os.path.join(bringup_dir, 'rviz', 'rviz2.rviz'), - description='Full path to the RVIZ config file to use') - - # Specify the actions - gazebo_server_launch = IncludeLaunchDescription( - PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')), - launch_arguments={'world': world}.items() + description='Full path to the RVIZ config file to use' ) - + + # Specify the actions gazebo_client_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')), ) @@ -92,42 +97,56 @@ def generate_launch_description(): output='screen' ) - start_spawn_entity_cmd = Node( - package='gazebo_ros', - executable='spawn_entity.py', - arguments=[ '-entity', 'robot', - '-topic', 'robot_description', - '-x', spawn_x_val, - '-y', spawn_y_val, - '-z', spawn_z_val, - '-Y', spawn_yaw_val], - # output='screen' - ) - start_rviz_cmd = Node( - package='rviz2', - namespace='', - executable='rviz2', - name='rviz2', - arguments=['-d' + os.path.join(bringup_dir, 'rviz', 'rviz2.rviz')] + package='rviz2', + namespace='', + executable='rviz2', + arguments=['-d' + os.path.join(bringup_dir, 'rviz', 'rviz2.rviz')] ) + def create_gazebo_launch_group(world_type): + world_config = get_world_config(world_type) + if world_config is None: + return None + + return GroupAction( + condition=LaunchConfigurationEquals('world', world_type), + actions=[ + Node( + package='gazebo_ros', + executable='spawn_entity.py', + arguments=[ + '-entity', 'robot', + '-topic', 'robot_description', + '-x', world_config['x'], + '-y', world_config['y'], + '-z', world_config['z'], + '-Y', world_config['yaw'] + ], + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')), + launch_arguments={'world': os.path.join(bringup_dir, 'world', world_config['world_path'])}.items(), + ) + ] + ) + + bringup_RMUC_cmd_group = create_gazebo_launch_group(WorldType.RMUC) + bringup_RMUL_cmd_group = create_gazebo_launch_group(WorldType.RMUL) + # Create the launch description and populate ld = LaunchDescription() - # Declare the launch options ld.add_action(declare_use_sim_time_cmd) ld.add_action(declare_world_cmd) ld.add_action(declare_rviz_config_file_cmd) - - # Add the actions to launch all of the pb_rm_simulation nodes - ld.add_action(gazebo_server_launch) ld.add_action(gazebo_client_launch) - ld.add_action(start_joint_state_publisher_cmd) ld.add_action(start_robot_state_publisher_cmd) - ld.add_action(start_spawn_entity_cmd) + ld.add_action(bringup_RMUL_cmd_group) + ld.add_action(bringup_RMUC_cmd_group) + # Uncomment this line if you want to start RViz # ld.add_action(start_rviz_cmd) - return ld \ No newline at end of file + return ld -- Gitee