git commit -m "first commit"

This commit is contained in:
2026-05-28 10:29:58 +07:00
commit 167c52aeb6
2048 changed files with 740251 additions and 0 deletions

View File

@@ -0,0 +1,35 @@
<!--
******************************************************************************************
* Copyright (c) 2023 Yang Haodong, All Rights Reserved *
* *
* @brief Amcl method module parameter configure. *
* @author Haodong Yang, *
* @version 1.0.0 *
* @date 2022.06.30 *
* @license GNU General Public License (GPL) *
******************************************************************************************
-->
<launch>
<!-- 机器人命名空间 -->
<arg name="robot_namespace" />
<!-- 是否启用命名空间 -->
<arg name="start_ns" default="false" />
<!-- 机器人属性 -->
<arg name="robot_x" />
<arg name="robot_y" />
<arg name="robot_z" />
<node pkg="amcl" type="amcl" name="amcl">
<!-- 加载初始化默认参数 -->
<rosparam file="$(find sim_env)/config/amcl_params.yaml" command="load" />
<param name="initial_pose_x" value="$(arg robot_x)"/>
<param name="initial_pose_y" value="$(arg robot_y)"/>
<param name="initial_pose_z" value="$(arg robot_z)"/>
<!-- 为坐标系添加命名空间 -->
<param name="odom_frame_id" value="$(arg robot_namespace)/odom" if="$(arg start_ns)"/>
<param name="base_frame_id" value="$(arg robot_namespace)/base_footprint" if="$(arg start_ns)"/>
<remap from="static_map" to="/static_map"/>
</node>
</launch>

View File

@@ -0,0 +1,130 @@
<!--
******************************************************************************************
* Copyright (c) 2023 Yang Haodong, All Rights Reserved *
* *
* @brief move base module parameter configure. *
* @author Haodong Yang, *
* @version 1.0.0 *
* @date 2022.06.30 *
* @license GNU General Public License (GPL) *
******************************************************************************************
-->
<launch>
<!-- robot's namespace -->
<arg name="robot_namespace" />
<!-- whether use namespace or not -->
<arg name="start_ns" default="false" />
<!-- robot's type -->
<arg name="robot" default="turtlebot3_waffle" />
<!-- global path planner name -->
<arg name="global_planner" default="a_star" />
<!-- local planner name -->
<arg name="local_planner" default="dwa" />
<!-- move base module -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- global planner plugin -->
<!-- graph search -->
<param name="base_global_planner" value="graph_planner/GraphPlanner"
if="$(eval arg('global_planner')=='a_star'
or arg('global_planner')=='jps'
or arg('global_planner')=='gbfs'
or arg('global_planner')=='dijkstra'
or arg('global_planner')=='d_star'
or arg('global_planner')=='lpa_star'
or arg('global_planner')=='voronoi'
or arg('global_planner')=='d_star_lite')" />
<param name="GraphPlanner/planner_name" value="$(arg global_planner)"
if="$(eval arg('global_planner')=='a_star'
or arg('global_planner')=='jps'
or arg('global_planner')=='gbfs'
or arg('global_planner')=='dijkstra'
or arg('global_planner')=='d_star'
or arg('global_planner')=='lpa_star'
or arg('global_planner')=='voronoi'
or arg('global_planner')=='d_star_lite')" />
<rosparam file="$(find sim_env)/config/planner/graph_planner_params.yaml" command="load"
if="$(eval arg('global_planner')=='a_star'
or arg('global_planner')=='jps'
or arg('global_planner')=='gbfs'
or arg('global_planner')=='dijkstra'
or arg('global_planner')=='d_star'
or arg('global_planner')=='lpa_star'
or arg('global_planner')=='voronoi'
or arg('global_planner')=='d_star_lite')"/>
<!-- sample search -->
<param name="base_global_planner" value="sample_planner/SamplePlanner"
if="$(eval arg('global_planner')=='rrt'
or arg('global_planner')=='rrt_star'
or arg('global_planner')=='informed_rrt'
or arg('global_planner')=='rrt_connect')" />
<param name="SamplePlanner/planner_name" value="$(arg global_planner)"
if="$(eval arg('global_planner')=='rrt'
or arg('global_planner')=='rrt_star'
or arg('global_planner')=='informed_rrt'
or arg('global_planner')=='rrt_connect')" />
<rosparam file="$(find sim_env)/config/planner/sample_planner_params.yaml" command="load"
if="$(eval arg('global_planner')=='rrt'
or arg('global_planner')=='rrt_star'
or arg('global_planner')=='informed_rrt'
or arg('global_planner')=='rrt_connect')"/>
<!-- evolutionary search -->
<param name="base_global_planner" value="evolutionary_planner/EvolutionaryPlanner"
if="$(eval arg('global_planner')=='aco'
or arg('global_planner')=='ga')" />
<param name="EvolutionaryPlanner/planner_name" value="$(arg global_planner)"
if="$(eval arg('global_planner')=='aco'
or arg('global_planner')=='ga')" />
<rosparam file="$(find sim_env)/config/planner/evolutionary_planner_params.yaml" command="load"
if="$(eval arg('global_planner')=='aco'
or arg('global_planner')=='ga')"/>
<!-- local planner plugin -->
<param name="base_local_planner" value="dwa_planner/DWAPlanner"
if="$(eval arg('local_planner')=='dwa')" />
<rosparam file="$(find sim_env)/config/planner/dwa_planner_params.yaml" command="load"
if="$(eval arg('local_planner')=='dwa')" />
<param name="base_local_planner" value="pid_planner/PIDPlanner"
if="$(eval arg('local_planner')=='pid')" />
<rosparam file="$(find sim_env)/config/planner/pid_planner_params.yaml" command="load"
if="$(eval arg('local_planner')=='pid')" />
<!-- loading navigation parameters -->
<rosparam
file="$(eval find('sim_env') + '/config/' + arg('robot') + '/costmap_common_params_'
+ arg('robot') + '.yaml')"
command="load" ns="global_costmap" />
<rosparam
file="$(eval find('sim_env') + '/config/' + arg('robot') + '/costmap_common_params_'
+ arg('robot') + '.yaml')"
command="load" ns="local_costmap" />
<rosparam file="$(find sim_env)/config/costmap/local_costmap_params.yaml" command="load" />
<rosparam file="$(find sim_env)/config/costmap/global_costmap_params.yaml" command="load" />
<rosparam file="$(find sim_env)/config/move_base_params.yaml" command="load" />
<!-- set coordinate transformation namespace -->
<param name="global_costmap/scan/sensor_frame" value="$(arg robot_namespace)/base_scan"
if="$(arg start_ns)" />
<param name="global_costmap/obstacle_layer/scan/sensor_frame"
value="$(arg robot_namespace)/base_scan" if="$(arg start_ns)" />
<param name="global_costmap/global_frame" value="map" />
<param name="global_costmap/robot_base_frame" value="$(arg robot_namespace)/base_footprint"
if="$(arg start_ns)" />
<param name="local_costmap/scan/sensor_frame" value="$(arg robot_namespace)/base_scan"
if="$(arg start_ns)" />
<param name="local_costmap/obstacle_layer/scan/sensor_frame"
value="$(arg robot_namespace)/base_scan" if="$(arg start_ns)" />
<param name="local_costmap/global_frame" value="$(arg robot_namespace)/odom"
if="$(arg start_ns)" />
<param name="local_costmap/robot_base_frame" value="$(arg robot_namespace)/base_footprint"
if="$(arg start_ns)" />
<!-- centralize map -->
<remap from="map" to="/map" />
</node>
</launch>

View File

@@ -0,0 +1,25 @@
<?xml version='1.0' encoding='utf-8'?>
<launch>
<arg name="robot_number" default="1" />
<arg name="robot1_type" value="turtlebot3_waffle" />
<arg name="robot1_global_planner" value="d_star" />
<arg name="robot1_local_planner" value="dwa" />
<arg name="robot1_x_pos" value="0.0" />
<arg name="robot1_y_pos" value="0.0" />
<arg name="robot1_z_pos" value="0.0" />
<arg name="robot1_yaw" value="0.0" />
<include file="$(find sim_env)/launch/app/environment_single.launch.xml">
<arg name="robot" value="$(eval arg('robot' + str(arg('robot_number')) + '_type'))" />
<arg name="global_planner" value="$(eval arg('robot' + str(arg('robot_number')) + '_global_planner'))" />
<arg name="local_planner" value="$(eval arg('robot' + str(arg('robot_number')) + '_local_planner'))" />
<arg name="robot_namespace" value="robot$(arg robot_number)" />
<arg name="start_ns" value="false" />
<arg name="robot_x" value="$(eval arg('robot' + str(arg('robot_number')) + '_x_pos'))" />
<arg name="robot_y" value="$(eval arg('robot' + str(arg('robot_number')) + '_y_pos'))" />
<arg name="robot_z" value="$(eval arg('robot' + str(arg('robot_number')) + '_z_pos'))" />
<arg name="robot_yaw" value="$(eval arg('robot' + str(arg('robot_number')) + '_yaw'))" />
</include>
<include file="$(find sim_env)/launch/include/robots/start_robots.launch.xml" if="$(eval arg('robot_number') &gt; 1)">
<arg name="robot_number" value="$(eval arg('robot_number') - 1)" />
</include>
</launch>