Skip to content

Commit

Permalink
🎉 init: first commit
Browse files Browse the repository at this point in the history
  • Loading branch information
LihanChen2004 committed Jun 29, 2024
0 parents commit 28fab61
Show file tree
Hide file tree
Showing 33 changed files with 3,677 additions and 0 deletions.
19 changes: 19 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
# Python
__pycache__/
*.pyc

# ROS
build/
devel/
logs/
install/
build_isolated/
devel_isolated/
*.bag
CATKIN_IGNORE

# Misc
.vscode/
*.swp
log/
test/
18 changes: 18 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
cmake_minimum_required(VERSION 3.5)
project(rmul24_gazebo_simulator)

find_package(ament_cmake REQUIRED)

install(DIRECTORY
config
launch
rviz
resource

DESTINATION share/${PROJECT_NAME}/
)

#environment
ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/gazebo.dsv.in")

ament_package()
101 changes: 101 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
# rmul24_gazebo_simulator

[![State-of-the-art Shitcode](https://img.shields.io/static/v1?label=State-of-the-art&message=Shitcode&color=7B5804)](https://github.com/trekhleb/state-of-the-art-shitcode)

> Still in **develop**, shit code
## 简介

rmul24_gazebo_simulator 是基于 Gazebo (Ignition 字母版本) 的仿真环境,为 RoboMaster University League 中的机器人算法开发提供仿真环境,方便测试 AI 算法,加快开发效率。

目前 rmul24_gazebo_simulator 还不完善,仅提供以下功能:

在 rmua19 标准机器人(rmua19_standard_robot)上增加相关传感器,构建不同机器人模型:

- rmua19_standard_robot_a:搭载云台相机 industrial_camera和搭载激光雷达 rplidar_a2,其中相机放置有在 yaw 轴。

- rmua19_standard_robot_b:搭载云台相机 industrial_camera 和搭载激光雷达 rplidar_a2,其中相机放置有在 pitch 轴。

- rmul24_sentry_robot:搭载云台相机 industrial_camera 和搭载激光雷达 rplidar_a2 和 Livox mid360,其中相机放置有在 pitch 轴

构建 RoboMaster University League 2024 简易场地 (models/RMUL_2024):

## 一. 基本使用

### 1.1 环境配置

- ROS2 版本要求: `Humble`

- Gazebo 仿真器版本要求: `Fortress`

```sh
cd ros_ws/src

git clone https://github.com/LihanChen2004/rmoss_interfaces.git
git clone https://github.com/LihanChen2004/rmoss_core.git
git clone https://github.com/LihanChen2004/rmoss_gazebo.git
git clone https://github.com/LihanChen2004/rmoss_gz_resources.git --depth=1
git clone https://github.com/gezp/sdformat_tools.git
git clone https://github.com/LihanChen2004/rmul24_gazebo_simulator.git

pip install xmacro
```

### 1.2 启动仿真环境

1. 启动仿真环境

```sh
ros2 launch rmul24_gazebo_simulator develop.launch.py
```

**注意:需要点击 Gazebo 左下角橙红色的 `启动` 按钮**

2. 控制机器人移动

```sh
ros2 run rmoss_gz_base test_chassis_cmd.py --ros-args -r __ns:=/red_standard_robot1/robot_base -p v:=0.3 -p w:=0.3
#根据提示进行输入,支持平移与自旋
```

3. 控制机器人云台

```sh
ros2 run rmoss_gz_base test_gimbal_cmd.py --ros-args -r __ns:=/red_standard_robot1/robot_base
#根据提示进行输入,支持绝对角度控制
```

4. 机器人射击

```sh
ros2 run rmoss_gz_base test_shoot_cmd.py --ros-args -r __ns:=/red_standard_robot1/robot_base
#根据提示进行输入
```

5. 运行裁判系统

```sh
ros2 run rmua19_gazebo_simulator simple_competition_1v1_referee.py
```

弹丸伤害为10,每个机器人HP为500,直到HP为0时,裁判系统输出胜利者,程序退出。(可重新运行开始)

通过解析并处理攻击信息 `/referee_system/attack_info` (包括射击者信息以及击中目标信息)实现裁判功能

## TODO

考试月启动... 2024.6.28~7.12

- [ ] mid360 改名为 livox_mid360

- [ ] TF Tree 都加上命名空间

- [ ] 删除 ignition plugin 中的 `ignition_frame_id`

- [ ] launch 中分离世界生成和机器人生成

## 维护者及开源许可证

Maintainer: Lihan Chen, <[email protected]>

rmul24_gazebo_simulator is provided under Apache License 2.0.
30 changes: 30 additions & 0 deletions config/base_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
/**:
ros__parameters:
world_name: "default"
chassis_controller:
follow_yaw: true
follow_yaw_pid:
p: 5.0
i: 0.0
d: 1.0
imin: -1.0
imax: 1.0
cmdmin: -1000.0
cmdmax: 1000.0
gimbal_controller:
pitch_pid:
p: 11.0
i: 0.0
d: 1.0
imin: -1.0
imax: 1.0
cmdmin: -1000.0
cmdmax: 1000.0
yaw_pid:
p: 11.0
i: 0.0
d: 0.0
imin: -1.0
imax: 1.0
cmdmin: -1000.0
cmdmax: 1000.0
4 changes: 4 additions & 0 deletions config/referee_system_1v1.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
max_hp: 500
initial_projectiles: 200
69 changes: 69 additions & 0 deletions config/ros_gz_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
- ros_topic_name: "/clock"
gz_topic_name: "/clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "ignition.msgs.Clock"
direction: "GZ_TO_ROS"

# PosePublisher
# - ros_topic_name: "/tf"
# gz_topic_name: "/model/<robot_name>/pose"
# ros_type_name: "tf2_msgs/msg/TFMessage"
# gz_type_name: "ignition.msgs.Pose_V"
# direction: "GZ_TO_ROS"

# - ros_topic_name: "/tf_static"
# gz_topic_name: "/model/<robot_name>/pose_static"
# ros_type_name: "tf2_msgs/msg/TFMessage"
# gz_type_name: "ignition.msgs.Pose_V"
# direction: "GZ_TO_ROS"

# - ros_topic_name: "/<robot_name>/odom"
# gz_topic_name: "/<robot_name>/odometry"
# ros_type_name: "nav_msgs/msg/Odometry"
# gz_type_name: "ignition.msgs.Odometry"
# direction: "GZ_TO_ROS"

# Global odometry
- ros_topic_name: "/odom"
gz_topic_name: "/odom"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "ignition.msgs.Odometry"
direction: "GZ_TO_ROS"

# OdometryPublisher publish tf from `odom` to `chassis`, used for navigation2
- ros_topic_name: "/tf"
gz_topic_name: "/odom/tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "ignition.msgs.Pose_V"
direction: "GZ_TO_ROS"

# JointStatePublisher publish
- ros_topic_name: "/<robot_name>/joint_state"
gz_topic_name: "/world/default/model/<robot_name>/joint_state"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "ignition.msgs.Model"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/front_camera/image"
gz_topic_name: "/world/default/model/<robot_name>/link/front_industrial_camera/sensor/front_industrial_camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/rplidar_a2/scan"
gz_topic_name: "/world/default/model/<robot_name>/link/front_rplidar_a2/sensor/front_rplidar_a2/scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/livox/lidar"
gz_topic_name: "/world/default/model/<robot_name>/link/right_mid360/sensor/right_mid360_lidar/scan/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "ignition.msgs.PointCloudPacked"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/livox/imu"
gz_topic_name: "/world/default/model/<robot_name>/link/right_mid360/sensor/right_mid360_imu/imu"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "ignition.msgs.IMU"
direction: "GZ_TO_ROS"
7 changes: 7 additions & 0 deletions env-hooks/gazebo.dsv.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share/@PROJECT_NAME@/resource/models
prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share/@PROJECT_NAME@/resource/worlds
set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
prepend-non-duplicate;SDF_PATH;share/@PROJECT_NAME@/resource/models
prepend-non-duplicate;SDF_PATH;share/@PROJECT_NAME@/resource/worlds
prepend-non-duplicate;IGN_FILE_PATH;share/@PROJECT_NAME@/resource/models
prepend-non-duplicate;IGN_FILE_PATH;share/@PROJECT_NAME@/resource/worlds
Loading

0 comments on commit 28fab61

Please sign in to comment.