diff --git "a/docs/2023.12.29 \344\273\277\347\234\237\344\270\234\345\212\250\346\200\201\351\232\234\347\242\215\347\211\251README.gif" "b/.docs/2023.12.29 \344\273\277\347\234\237\344\270\234\345\212\250\346\200\201\351\232\234\347\242\215\347\211\251README.gif"
similarity index 100%
rename from "docs/2023.12.29 \344\273\277\347\234\237\344\270\234\345\212\250\346\200\201\351\232\234\347\242\215\347\211\251README.gif"
rename to ".docs/2023.12.29 \344\273\277\347\234\237\344\270\234\345\212\250\346\200\201\351\232\234\347\242\215\347\211\251README.gif"
diff --git a/docs/FAST_LIO+Nav2.png b/.docs/FAST_LIO+Nav2.png
similarity index 100%
rename from docs/FAST_LIO+Nav2.png
rename to .docs/FAST_LIO+Nav2.png
diff --git a/docs/Gazebo_Simulation.png b/.docs/Gazebo_Simulation.png
similarity index 100%
rename from docs/Gazebo_Simulation.png
rename to .docs/Gazebo_Simulation.png
diff --git a/docs/RMUC_2024_mapping.png b/.docs/RMUC_2024_mapping.png
similarity index 100%
rename from docs/RMUC_2024_mapping.png
rename to .docs/RMUC_2024_mapping.png
diff --git a/.docs/gazebo_RMUL.png b/.docs/gazebo_RMUL.png
new file mode 100644
index 0000000000000000000000000000000000000000..6d7215dccadfea06e5241d24642ec6d92bcfba62
Binary files /dev/null and b/.docs/gazebo_RMUL.png differ
diff --git a/README.md b/README.md
index c927c5cd90de35d36aa11aa0f3037a502b5f60b9..16c35e58ce0f51a3f53317ba1c3dde6d5d6ce58e 100644
--- a/README.md
+++ b/README.md
@@ -10,11 +10,11 @@
|Gazebo 仿真|Fast_LIO + Navigation2|
|:-:|:-:|
-|||
+|||
|Mid360点云仿真 + FAST_LIO 里程计 + 障碍物/地面点云分割 + 三维点云转二维 + Navigation2|
|:-:|
-||
+||
## 二. rm_simulation 话题接口
@@ -66,11 +66,11 @@
## 四. 编译运行
-```sh
+```bash
git clone --recursive https://gitee.com/SMBU-POLARBEAR/pb_rmsimulation --depth=1
```
-```sh
+```bash
cd pb_rmsimulation
./build.sh
```
@@ -92,7 +92,7 @@ cd pb_rmsimulation
3. `localization` (仅 `mode:=nav` 时本参数有效)
- `amcl` - 使用 [AMCL](https://navigation.ros.org/configuration/packages/configuring-amcl.html) 算法定位(经典算法)
- - `slam_toolbox` - 使用 [slam_toolbox](https://github.com/SteveMacenski/slam_toolbox) localization 模式定位(动态场景中性能更好)
+ - `slam_toolbox` - 使用 [slam_toolbox](https://github.com/SteveMacenski/slam_toolbox) localization 模式定位(动态场景中效果更好)
- `icp` - 使用 [ICP_Localization](https://github.com/baiyeweiguang/icp_localization_ros2) 算法定位(性能开销较多)
Tips:
@@ -109,7 +109,7 @@ cd pb_rmsimulation
- 示例:
- 边建图边导航
- ```sh
+ ```bash
ros2 launch rm_bringup bringup_sim.launch.py \
world:=RMUL \
mode:=mapping
@@ -117,7 +117,7 @@ cd pb_rmsimulation
- 已知全局地图导航
- ```sh
+ ```bash
ros2 launch rm_bringup bringup_sim.launch.py \
world:=RMUL \
mode:=nav \
@@ -129,7 +129,7 @@ cd pb_rmsimulation
- 示例:
- 边建图边导航
- ```sh
+ ```bash
ros2 launch rm_bringup bringup_real.launch.py \
world:=YOUR_WORLD_NAME \
mode:=mapping
@@ -143,7 +143,7 @@ cd pb_rmsimulation
- 已知全局地图导航
- ```sh
+ ```bash
ros2 launch rm_bringup bringup_real.launch.py \
world:=YOUR_WORLD_NAME \
mode:=nav \
@@ -154,8 +154,7 @@ cd pb_rmsimulation
### 小工具 - 键盘控制
-```sh
-source install/setup.bash
+```bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard
```
@@ -187,4 +186,8 @@ Mid360 点云仿真:参考了 [livox_laser_simulation](https://github.com/Livo
- Gazebo 无法正常启动?
- 答:执行命令 `source /usr/share/gazebo/setup.sh`;使用 `killall -9 gzserver` 和 `killall -9 gzclient` 确保 Gazebo 后台进程已完全清除
+ 答:执行命令 `source /usr/share/gazebo/setup.sh`。
+
+- Gazebo 没有生成小车?
+
+ 答:执行命令 `killall -9 gzserver` 和 `killall -9 gzclient` 确保 Gazebo 后台进程已完全清除,再重新启动即可。
diff --git a/src/rm_bringup/config/nav2_params.yaml b/src/rm_bringup/config/nav2_params_real.yaml
similarity index 100%
rename from src/rm_bringup/config/nav2_params.yaml
rename to src/rm_bringup/config/nav2_params_real.yaml
diff --git a/src/rm_bringup/config/nav2_params_sim.yaml b/src/rm_bringup/config/nav2_params_sim.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..e957d87686ca343f2d1fba0c6c6e815f472b6739
--- /dev/null
+++ b/src/rm_bringup/config/nav2_params_sim.yaml
@@ -0,0 +1,378 @@
+amcl:
+ ros__parameters:
+ use_sim_time: False
+ alpha1: 0.2
+ alpha2: 0.2
+ alpha3: 0.2
+ alpha4: 0.2
+ alpha5: 0.2
+ base_frame_id: "base_link"
+ beam_skip_distance: 0.5
+ beam_skip_error_threshold: 0.9
+ beam_skip_threshold: 0.3
+ do_beamskip: false
+ global_frame_id: "map"
+ lambda_short: 0.1
+ laser_likelihood_max_dist: 2.0
+ laser_max_range: 100.0
+ laser_min_range: -1.0
+ laser_model_type: "likelihood_field"
+ max_beams: 60
+ max_particles: 2000
+ min_particles: 500
+ odom_frame_id: "odom"
+ pf_err: 0.05
+ pf_z: 0.99
+ recovery_alpha_fast: 0.0
+ recovery_alpha_slow: 0.0
+ resample_interval: 1
+ robot_model_type: "nav2_amcl::OmniMotionModel"
+ save_pose_rate: 0.5
+ sigma_hit: 0.2
+ tf_broadcast: true
+ transform_tolerance: 1.0
+ update_min_a: 0.2
+ update_min_d: 0.25
+ z_hit: 0.5
+ z_max: 0.05
+ z_rand: 0.5
+ z_short: 0.05
+ scan_topic: scan
+
+amcl_map_client:
+ ros__parameters:
+ use_sim_time: False
+
+amcl_rclcpp_node:
+ ros__parameters:
+ use_sim_time: False
+
+bt_navigator:
+ ros__parameters:
+ use_sim_time: False
+ global_frame: map
+ robot_base_frame: base_link
+ odom_topic: /Odometry
+ bt_loop_duration: 10
+ default_server_timeout: 20
+ enable_groot_monitoring: True
+ groot_zmq_publisher_port: 1666
+ groot_zmq_server_port: 1667
+ plugin_lib_names:
+ - nav2_compute_path_to_pose_action_bt_node
+ - nav2_compute_path_through_poses_action_bt_node
+ - nav2_follow_path_action_bt_node
+ - nav2_back_up_action_bt_node
+ - nav2_spin_action_bt_node
+ - nav2_wait_action_bt_node
+ - nav2_clear_costmap_service_bt_node
+ - nav2_is_stuck_condition_bt_node
+ - nav2_goal_reached_condition_bt_node
+ - nav2_goal_updated_condition_bt_node
+ - nav2_initial_pose_received_condition_bt_node
+ - nav2_reinitialize_global_localization_service_bt_node
+ - nav2_rate_controller_bt_node
+ - nav2_distance_controller_bt_node
+ - nav2_speed_controller_bt_node
+ - nav2_truncate_path_action_bt_node
+ - nav2_goal_updater_node_bt_node
+ - nav2_recovery_node_bt_node
+ - nav2_pipeline_sequence_bt_node
+ - nav2_round_robin_node_bt_node
+ - nav2_transform_available_condition_bt_node
+ - nav2_time_expired_condition_bt_node
+ - nav2_distance_traveled_condition_bt_node
+ - nav2_single_trigger_bt_node
+ - nav2_is_battery_low_condition_bt_node
+ - nav2_navigate_through_poses_action_bt_node
+ - nav2_navigate_to_pose_action_bt_node
+ - nav2_remove_passed_goals_action_bt_node
+ - nav2_planner_selector_bt_node
+ - nav2_controller_selector_bt_node
+ - nav2_goal_checker_selector_bt_node
+
+bt_navigator_rclcpp_node:
+ ros__parameters:
+ use_sim_time: False
+
+controller_server:
+ ros__parameters:
+ use_sim_time: False
+ controller_frequency: 5.0
+ min_x_velocity_threshold: 0.001
+ min_y_velocity_threshold: 0.5
+ min_theta_velocity_threshold: 0.001
+ failure_tolerance: 0.3
+ progress_checker_plugin: "progress_checker"
+ goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
+ controller_plugins: ["FollowPath"]
+
+ # Progress checker parameters
+ progress_checker:
+ plugin: "nav2_controller::SimpleProgressChecker"
+ required_movement_radius: 0.5
+ movement_time_allowance: 10.0
+
+ # Goal checker parameters
+ general_goal_checker:
+ stateful: True
+ plugin: "nav2_controller::SimpleGoalChecker"
+ xy_goal_tolerance: 0.25
+ yaw_goal_tolerance: 0.25
+ # DWB parameters
+ FollowPath:
+ plugin: "dwb_core::DWBLocalPlanner"
+ debug_trajectory_details: False
+ min_vel_x: -2.5
+ min_vel_y: -2.5
+ max_vel_x: 2.5
+ max_vel_y: 2.5
+ max_vel_theta: 12.0
+ min_speed_xy: -8.0
+ max_speed_xy: 8.0
+ min_speed_theta: -12.0
+ acc_lim_x: 5.0
+ acc_lim_y: 5.0
+ acc_lim_theta: 15.0
+ decel_lim_x: -5.0
+ decel_lim_y: -5.0
+ decel_lim_theta: -15.0
+ vx_samples: 20
+ vy_samples: 20
+ vtheta_samples: 20
+ sim_time: 0.51
+ linear_granularity: 0.05
+ angular_granularity: 0.025
+ transform_tolerance: 0.2
+ xy_goal_tolerance: 0.25
+ trans_stopped_velocity: 0.25
+ short_circuit_trajectory_evaluation: True
+ stateful: True
+ critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+ BaseObstacle.scale: 0.02
+ PathAlign.scale: 32.0
+ PathAlign.forward_point_distance: 0.1
+ GoalAlign.scale: 24.0
+ GoalAlign.forward_point_distance: 0.1
+ PathDist.scale: 32.0
+ GoalDist.scale: 24.0
+ RotateToGoal.scale: 32.0
+ RotateToGoal.slowing_factor: 5.0
+ RotateToGoal.lookahead_time: -1.0
+
+controller_server_rclcpp_node:
+ ros__parameters:
+ use_sim_time: False
+
+local_costmap:
+ local_costmap:
+ ros__parameters:
+ update_frequency: 20.0
+ publish_frequency: 10.0
+ global_frame: odom
+ robot_base_frame: base_link
+ use_sim_time: False
+ rolling_window: true
+ width: 5
+ height: 5
+ resolution: 0.02
+ robot_radius: 0.2
+ plugins: ["voxel2d_layer", "voxel3d_layer", "inflation_layer"]
+ inflation_layer:
+ plugin: "nav2_costmap_2d::InflationLayer"
+ cost_scaling_factor: 8.0
+ inflation_radius: 0.7
+ voxel2d_layer:
+ plugin: "nav2_costmap_2d::VoxelLayer"
+ enabled: True
+ publish_voxel_map: False
+ origin_z: 0.0
+ z_resolution: 0.05
+ z_voxels: 16
+ max_obstacle_height: 2.0
+ mark_threshold: 0
+ observation_sources: scan
+ scan:
+ topic: /scan
+ obstacle_max_range: 10.0
+ obstacle_min_range: 0.0
+ raytrace_min_range: 0.0
+ raytrace_max_range: 20.0
+ min_obstacle_height: 0.0
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "LaserScan"
+ voxel3d_layer:
+ plugin: "nav2_costmap_2d::VoxelLayer"
+ enabled: True
+ publish_voxel_map: False
+ origin_z: 0.0
+ z_resolution: 0.05
+ z_voxels: 16
+ mark_threshold: 1
+ observation_sources: livox
+ min_obstacle_height: 0.00
+ max_obstacle_height: 2.0
+ livox:
+ topic: /segmentation/obstacle
+ obstacle_max_range: 10.0
+ obstacle_min_range: 0.0
+ raytrace_min_range: 0.0
+ raytrace_max_range: 20.0
+ min_obstacle_height: 0.0
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "PointCloud2"
+ static_layer:
+ map_subscribe_transient_local: True
+ always_send_full_costmap: True
+ local_costmap_client:
+ ros__parameters:
+ use_sim_time: False
+ local_costmap_rclcpp_node:
+ ros__parameters:
+ use_sim_time: False
+
+global_costmap:
+ global_costmap:
+ ros__parameters:
+ update_frequency: 15.0
+ publish_frequency: 10.0
+ global_frame: map
+ robot_base_frame: base_link
+ use_sim_time: False
+ robot_radius: 0.2
+ resolution: 0.02
+ track_unknown_space: true
+ plugins: ["static_layer", "voxel2d_layer", "voxel3d_layer", "inflation_layer"]
+ voxel2d_layer:
+ plugin: "nav2_costmap_2d::ObstacleLayer"
+ enabled: True
+ observation_sources: scan
+ scan:
+ topic: /scan
+ obstacle_max_range: 10.0
+ obstacle_min_range: 0.0
+ raytrace_min_range: 0.0
+ raytrace_max_range: 20.0
+ min_obstacle_height: 0.0
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "LaserScan"
+ voxel3d_layer:
+ plugin: "nav2_costmap_2d::VoxelLayer"
+ enabled: True
+ publish_voxel_map: False
+ origin_z: 0.0
+ z_resolution: 0.05
+ z_voxels: 16
+ mark_threshold: 1
+ observation_sources: livox
+ min_obstacle_height: 0.00
+ max_obstacle_height: 2.0
+ livox:
+ topic: /segmentation/obstacle
+ obstacle_max_range: 10.0
+ obstacle_min_range: 0.0
+ raytrace_min_range: 0.0
+ raytrace_max_range: 20.0
+ min_obstacle_height: 0.0
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "PointCloud2"
+ static_layer:
+ plugin: "nav2_costmap_2d::StaticLayer"
+ map_subscribe_transient_local: True
+ inflation_layer:
+ plugin: "nav2_costmap_2d::InflationLayer"
+ cost_scaling_factor: 8.0
+ inflation_radius: 0.7
+ always_send_full_costmap: True
+ global_costmap_client:
+ ros__parameters:
+ use_sim_time: False
+ global_costmap_rclcpp_node:
+ ros__parameters:
+ use_sim_time: False
+
+map_server:
+ ros__parameters:
+ use_sim_time: False
+ yaml_filename: ""
+
+map_saver:
+ ros__parameters:
+ use_sim_time: False
+ save_map_timeout: 5.0
+ free_thresh_default: 0.25
+ occupied_thresh_default: 0.65
+ map_subscribe_transient_local: True
+
+planner_server:
+ ros__parameters:
+ expected_planner_frequency: 5.0
+ use_sim_time: False
+ planner_plugins: ["GridBased"]
+ GridBased:
+ plugin: "nav2_navfn_planner/NavfnPlanner"
+ tolerance: 0.5
+ use_astar: false
+ allow_unknown: true
+
+# planner_server_rclcpp_node:
+# ros__parameters:
+# use_sim_time: False
+
+recoveries_server:
+ ros__parameters:
+ costmap_topic: local_costmap/costmap_raw
+ footprint_topic: local_costmap/published_footprint
+ cycle_frequency: 10.0
+ recovery_plugins: ["spin", "backup", "wait"]
+ spin:
+ plugin: "nav2_recoveries/Spin"
+ backup:
+ plugin: "nav2_recoveries/BackUp"
+ wait:
+ plugin: "nav2_recoveries/Wait"
+ global_frame: odom
+ robot_base_frame: base_link
+ transform_timeout: 0.1
+ use_sim_time: False
+ simulate_ahead_time: 2.0
+ max_rotational_vel: 20.0
+ min_rotational_vel: 0.4
+ rotational_acc_lim: 10.0
+
+robot_state_publisher:
+ ros__parameters:
+ use_sim_time: False
+
+waypoint_follower:
+ ros__parameters:
+ loop_rate: 20
+ stop_on_failure: false
+ waypoint_task_executor_plugin: "wait_at_waypoint"
+ wait_at_waypoint:
+ plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+ enabled: True
+ waypoint_pause_duration: 200
+
+velocity_smoother:
+ ros__parameters:
+ use_sim_time: True
+ smoothing_frequency: 5.0
+ scale_velocities: False
+ feedback: "CLOSED_LOOP"
+ max_velocity: [2.5, 2.5, 12.0]
+ min_velocity: [-2.5, -2.5, -12.0]
+ max_accel: [5.0, 5.0, 15.0]
+ max_decel: [-5.0, -5.0, -15.0]
+ odom_topic: "Odometry"
+ odom_duration: 0.1
+ deadband_velocity: [0.0, 0.0, 0.0]
+ velocity_timeout: 1.0
\ No newline at end of file
diff --git a/src/rm_bringup/launch/bringup_real.launch.py b/src/rm_bringup/launch/bringup_real.launch.py
index 2c98f14a834553444bc9f3bd9fa8cb393fe8614f..84c74ff6b209a7b9edb3a308c50afccf4dde2582 100644
--- a/src/rm_bringup/launch/bringup_real.launch.py
+++ b/src/rm_bringup/launch/bringup_real.launch.py
@@ -26,7 +26,7 @@ def generate_launch_description():
slam_toolbox_mapping_file_dir = os.path.join(bringup_dir, 'config', 'mapper_params_online_async.yaml')
nav2_map_dir = PathJoinSubstitution([bringup_dir, 'map', world]), ".yaml"
- nav2_params_file_dir = os.path.join(bringup_dir, 'config', 'nav2_params.yaml')
+ nav2_params_file_dir = os.path.join(bringup_dir, 'config', 'nav2_params_real.yaml')
icp_pcd_dir = PathJoinSubstitution([bringup_dir, 'PCD', world]), ".pcd"
icp_node_params_dir = os.path.join(bringup_dir, 'config', 'icp_node_params.yaml')
diff --git a/src/rm_bringup/launch/bringup_sim.launch.py b/src/rm_bringup/launch/bringup_sim.launch.py
index 89db5717656ddc83e4a941e80fea9af4162ae025..ee1be37c974ebb3819e266fc348b7e4368c81d58 100644
--- a/src/rm_bringup/launch/bringup_sim.launch.py
+++ b/src/rm_bringup/launch/bringup_sim.launch.py
@@ -27,7 +27,7 @@ def generate_launch_description():
slam_toolbox_mapping_file_dir = os.path.join(bringup_dir, 'config', 'mapper_params_online_async.yaml')
nav2_map_dir = PathJoinSubstitution([bringup_dir, 'map', world]), ".yaml"
- nav2_params_file_dir = os.path.join(bringup_dir, 'config', 'nav2_params.yaml')
+ nav2_params_file_dir = os.path.join(bringup_dir, 'config', 'nav2_params_sim.yaml')
icp_pcd_dir = PathJoinSubstitution([bringup_dir, 'PCD', world]), ".pcd"
icp_node_params_dir = os.path.join(bringup_dir, 'config', 'icp_node_params.yaml')
diff --git a/src/rm_decision/Nav2_API.md b/src/rm_decision/rm_FSM/Nav2_API.md
similarity index 100%
rename from src/rm_decision/Nav2_API.md
rename to src/rm_decision/rm_FSM/Nav2_API.md
diff --git a/src/rm_decision/README.md b/src/rm_decision/rm_FSM/README.md
similarity index 93%
rename from src/rm_decision/README.md
rename to src/rm_decision/rm_FSM/README.md
index 659a6591aaa0d4a14303ffd0042566c858978b1e..6286392ab705a69746cca2d033979f17508311a3 100644
--- a/src/rm_decision/README.md
+++ b/src/rm_decision/rm_FSM/README.md
@@ -65,14 +65,14 @@
### 启动有限状态机决策
```Shell
-ros2 launch rm_decision pb_auto_fsm_launch.py
+ros2 launch rm_auto_FSM rm_auto_fsm_launch.py
```
### 虚拟裁判系统和视觉部分,发布假消息
- robot_status
- ```
+ ```bash
source install/setup.bash
ros2 topic pub -r 5 /robot_status rm_decision_interfaces/msg/RobotStatus "{
robot_id: 7,
@@ -83,7 +83,7 @@ ros2 launch rm_decision pb_auto_fsm_launch.py
- robot_hp
- ```
+ ```bash
source install/setup.bash
ros2 topic pub -r 5 /robot_hp rm_decision_interfaces/msg/AllRobotHP "{
red_1_robot_hp: 200,
@@ -107,7 +107,7 @@ ros2 launch rm_decision pb_auto_fsm_launch.py
- friend_location
- ```
+ ```bash
source install/setup.bash
ros2 topic pub -r 5 /friend_location rm_decision_interfaces/msg/FriendLocation "{
hero_x: 2.75, hero_y: 0.0,
@@ -117,15 +117,16 @@ ros2 launch rm_decision pb_auto_fsm_launch.py
standard_5_x: 18.75, standard_5_y: 0.0
}"
```
- `hero`: 己方哨兵出生点
- `engineer`: 能量机关(靠己方)
- `standard_3`: 己方环形高地
- `standard_4`: 敌方前哨站
- `standard_5`: 敌方基地
+
+ `hero`: 己方哨兵出生点
+ `engineer`: 能量机关(靠己方)
+ `standard_3`: 己方环形高地
+ `standard_4`: 敌方前哨站
+ `standard_5`: 敌方基地
- armors
- ```
+ ```bash
source install/setup.bash
ros2 topic pub -r 5 /detector/armors rm_decision_interfaces/msg/Armor "{
number: '1',
@@ -139,7 +140,8 @@ ros2 launch rm_decision pb_auto_fsm_launch.py
```
- RFID
- ```
+
+ ```bash
source install/setup.bash
ros2 topic pub -r 5 /rfid rm_decision_interfaces/msg/RFID "{
rfid_patrol_status: 0
diff --git a/src/rm_decision/launch/pb_auto_fsm_launch.py b/src/rm_decision/rm_FSM/launch/rm_auto_fsm_launch.py
similarity index 81%
rename from src/rm_decision/launch/pb_auto_fsm_launch.py
rename to src/rm_decision/rm_FSM/launch/rm_auto_fsm_launch.py
index 918506b39655fcc8c762cd28b851f6de5daa0367..567f1cff884b728db51bbf01b601bcffc8686a90 100644
--- a/src/rm_decision/launch/pb_auto_fsm_launch.py
+++ b/src/rm_decision/rm_FSM/launch/rm_auto_fsm_launch.py
@@ -5,8 +5,8 @@ def generate_launch_description():
# start the demo autonomy task
demo_cmd = Node(
- package='rm_decision',
- executable='pb_auto_fsm',
+ package='rm_auto_FSM',
+ executable='rm_auto_FSM',
emulate_tty=True,
output='screen')
diff --git a/src/rm_decision/media/readme.gif b/src/rm_decision/rm_FSM/media/readme.gif
similarity index 100%
rename from src/rm_decision/media/readme.gif
rename to src/rm_decision/rm_FSM/media/readme.gif
diff --git a/src/rm_decision/package.xml b/src/rm_decision/rm_FSM/package.xml
similarity index 97%
rename from src/rm_decision/package.xml
rename to src/rm_decision/rm_FSM/package.xml
index 1a678dfbe604c332226cfb2606bb7d83cf868d09..23deb78e70dfd4359544f320ac6949e6b0993743 100644
--- a/src/rm_decision/package.xml
+++ b/src/rm_decision/rm_FSM/package.xml
@@ -1,7 +1,7 @@
- rm_decision
+ rm_auto_FSM
0.0.0
A decision package for RMUC/RMYC sentinel robots implemented based on a finite state machine
Lihan Chen
diff --git a/src/rm_decision/pytest.ini b/src/rm_decision/rm_FSM/pytest.ini
similarity index 100%
rename from src/rm_decision/pytest.ini
rename to src/rm_decision/rm_FSM/pytest.ini
diff --git a/src/rm_decision/resource/rm_decision b/src/rm_decision/rm_FSM/resource/rm_auto_FSM
similarity index 100%
rename from src/rm_decision/resource/rm_decision
rename to src/rm_decision/rm_FSM/resource/rm_auto_FSM
diff --git a/src/rm_decision/rm_decision/__init__.py b/src/rm_decision/rm_FSM/rm_auto_FSM/__init__.py
similarity index 100%
rename from src/rm_decision/rm_decision/__init__.py
rename to src/rm_decision/rm_FSM/rm_auto_FSM/__init__.py
diff --git a/src/rm_decision/rm_decision/callback_msg.py b/src/rm_decision/rm_FSM/rm_auto_FSM/callback_msg.py
similarity index 100%
rename from src/rm_decision/rm_decision/callback_msg.py
rename to src/rm_decision/rm_FSM/rm_auto_FSM/callback_msg.py
diff --git a/src/rm_decision/rm_decision/config/goal.yaml b/src/rm_decision/rm_FSM/rm_auto_FSM/config/goal.yaml
similarity index 100%
rename from src/rm_decision/rm_decision/config/goal.yaml
rename to src/rm_decision/rm_FSM/rm_auto_FSM/config/goal.yaml
diff --git a/src/rm_decision/rm_decision/pb_auto_fsm.py b/src/rm_decision/rm_FSM/rm_auto_FSM/rm_auto_FSM.py
similarity index 98%
rename from src/rm_decision/rm_decision/pb_auto_fsm.py
rename to src/rm_decision/rm_FSM/rm_auto_FSM/rm_auto_FSM.py
index 51a5890a1707af0f68e327d8ebfd543fbdb05d78..1ce03c39c73ffd1de4fed1808a68aa69b57594e2 100644
--- a/src/rm_decision/rm_decision/pb_auto_fsm.py
+++ b/src/rm_decision/rm_FSM/rm_auto_FSM/rm_auto_FSM.py
@@ -13,9 +13,9 @@ from rclpy import qos
from geometry_msgs.msg import Twist, PoseStamped
from rm_decision_interfaces.msg import RobotStatus, FriendLocation, AllRobotHP, Armor, RFID
-from rm_decision.callback_msg import CallbackMsg
-from rm_decision.robot_navigator import BasicNavigator
-from rm_decision.utility import Utility
+from rm_auto_FSM.callback_msg import CallbackMsg
+from rm_auto_FSM.robot_navigator import BasicNavigator
+from rm_auto_FSM.utility import Utility
class AutoFSM(Node):
"""
diff --git a/src/rm_decision/rm_decision/robot_navigator.py b/src/rm_decision/rm_FSM/rm_auto_FSM/robot_navigator.py
similarity index 100%
rename from src/rm_decision/rm_decision/robot_navigator.py
rename to src/rm_decision/rm_FSM/rm_auto_FSM/robot_navigator.py
diff --git a/src/rm_decision/rm_decision/utility.py b/src/rm_decision/rm_FSM/rm_auto_FSM/utility.py
similarity index 98%
rename from src/rm_decision/rm_decision/utility.py
rename to src/rm_decision/rm_FSM/rm_auto_FSM/utility.py
index 06b26ff282f5be6bc2296cd7d15f9d7ac3d58d72..415fb277e6c1139b3ba02f5e0645b30a1d6e0611 100644
--- a/src/rm_decision/rm_decision/utility.py
+++ b/src/rm_decision/rm_FSM/rm_auto_FSM/utility.py
@@ -1,7 +1,7 @@
import rclpy
from rclpy.duration import Duration
from geometry_msgs.msg import PoseStamped
-from rm_decision.robot_navigator import TaskResult
+from rm_auto_FSM.robot_navigator import TaskResult
import time
import yaml
diff --git a/src/rm_decision/rm_FSM/setup.cfg b/src/rm_decision/rm_FSM/setup.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..47e0fbc0ff09a996bfa6f5456b0b96de16dccc78
--- /dev/null
+++ b/src/rm_decision/rm_FSM/setup.cfg
@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/rm_auto_FSM
+[install]
+install_scripts=$base/lib/rm_auto_FSM
diff --git a/src/rm_decision/setup.py b/src/rm_decision/rm_FSM/setup.py
similarity index 81%
rename from src/rm_decision/setup.py
rename to src/rm_decision/rm_FSM/setup.py
index a75ec162b84f539852e8dd7fdfc45c2189e18305..bb2c71e32c77704b01a383a4d6381dcdd465c521 100644
--- a/src/rm_decision/setup.py
+++ b/src/rm_decision/rm_FSM/setup.py
@@ -3,7 +3,7 @@ import os
from setuptools import setup
-package_name = 'rm_decision'
+package_name = 'rm_auto_FSM'
setup(
name=package_name,
@@ -19,12 +19,12 @@ setup(
zip_safe=True,
maintainer='LihanChen',
maintainer_email='1120220476@smbu.edu.cn',
- description='A decision package for RMUC/RMYC sentinel robots implemented based on a finite state machine',
+ description='A decision package for RMUC/RMUL sentinel robots implemented based on a finite state machine',
license='MIT',
tests_require=['pytest'],
entry_points={
'console_scripts': [
- 'pb_auto_fsm = rm_decision.pb_auto_fsm:main',
+ 'rm_auto_FSM = rm_auto_FSM.rm_auto_FSM:main',
],
},
)
diff --git a/src/rm_decision/test/test_copyright.py b/src/rm_decision/rm_FSM/test/test_copyright.py
similarity index 100%
rename from src/rm_decision/test/test_copyright.py
rename to src/rm_decision/rm_FSM/test/test_copyright.py
diff --git a/src/rm_decision/test/test_flake8.py b/src/rm_decision/rm_FSM/test/test_flake8.py
similarity index 100%
rename from src/rm_decision/test/test_flake8.py
rename to src/rm_decision/rm_FSM/test/test_flake8.py
diff --git a/src/rm_decision/test/test_line_iterator.py b/src/rm_decision/rm_FSM/test/test_line_iterator.py
similarity index 98%
rename from src/rm_decision/test/test_line_iterator.py
rename to src/rm_decision/rm_FSM/test/test_line_iterator.py
index d50b1ad4243ecb026ac42d7452776a11ea8263f6..9c07e4cf9ea17ea82892e151e82d5d15dcb6bee2 100644
--- a/src/rm_decision/test/test_line_iterator.py
+++ b/src/rm_decision/rm_FSM/test/test_line_iterator.py
@@ -14,7 +14,7 @@
import unittest
from cmath import sqrt
-from rm_decision.line_iterator import LineIterator
+from rm_auto_FSM.line_iterator import LineIterator
class TestLineIterator(unittest.TestCase):
diff --git a/src/rm_decision/test/test_pep257.py b/src/rm_decision/rm_FSM/test/test_pep257.py
similarity index 100%
rename from src/rm_decision/test/test_pep257.py
rename to src/rm_decision/rm_FSM/test/test_pep257.py
diff --git a/src/rm_decision/setup.cfg b/src/rm_decision/setup.cfg
deleted file mode 100644
index 7fc6b7e06ab379f0a96430b400dee062e7789057..0000000000000000000000000000000000000000
--- a/src/rm_decision/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script_dir=$base/lib/rm_decision
-[install]
-install_scripts=$base/lib/rm_decision
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 f0c8c97c08a666d216dc7671a3db1839da36b12e..650e6bcad7cde6c949ba2d29fb3ca748f0e5aa77 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
@@ -33,8 +33,8 @@ def get_world_config(world_type):
'y': '3.35',
'z': '1.16',
'yaw': '0.0',
- 'world_path': 'RMUL2024_world/RMUL2024_world.world'
- # 'world_path': 'RMUL2024_world/RMUL2024_world_dynamic_obstacles.world'
+ # 'world_path': 'RMUL2024_world/RMUL2024_world.world'
+ 'world_path': 'RMUL2024_world/RMUL2024_world_dynamic_obstacles.world'
}
}
return world_configs.get(world_type, None)