多机器人逻辑 patrolling_sim
patrolling_sim
https://github.com/davidbsp/patrolling_sim/tree/master
该软件包包含多个用于多机器人巡逻的算法的实现,以及可以扩展以实现其他算法的PatrolAgent的一般结构。它扩展了patrolling_sim的先前版本,改进了代码结构,允许轻松集成新算法,改进的导航配置允许机器人以1 m / s的速度移动并避免大多数冲突情况,并更好地管理实验和结果的产生。
用于ROS(Groovy / Hydro / Indigo)的patrolling_sim - catkin版本
主要框架和基本算法:David Portugal(2011-2014),Luca Iocchi(2014-2016)
来源:git https://github.com/davidbsp/patrolling_sim.git(分支:主)
描述
用于ROS的多机器人巡逻包。 由11个运行算法组成:
随机(兰德)
启发式探路者认知认知(HPCC)
尽职尽责(CR)
启发式尽责反应(HCR)
通用图的循环算法(CGG)
广义多级子图巡检算法(MSP)
贪心贝叶斯战略(GBS)
国家交换贝叶斯战略(SEBS)
并行贝叶斯学习策略(CBLS)
动态任务分配贪婪(DTAG)
基于连续单项拍卖(DTAP)的动态任务分配
单个机器人
robot.launch
<?xml version="1.0" encoding="UTF-8" ?> <launch> <arg name="robotname" default="robot_0" /> <arg name="mapname" default="grid" /> <arg name="use_amcl" default="true" /> <arg name="use_move_base" default="true" /> <arg name="use_srrg_localizer" default="false" /> <arg name="use_spqrel_planner" default="false" /> <group ns="$(arg robotname)"> <!-- Run the map server --> <node name="map_server" pkg="map_server" type="map_server" args="$(find patrolling_sim)/maps/$(arg mapname)/$(arg mapname).yaml" /> <!-- Standard ROS navigation modules --> <group if="$(arg use_amcl)"> <!--- AMCL --> <include file="$(find patrolling_sim)/params/amcl/amcl_diff.launch" /> <!-- Override AMCL Frame Params to include prefix --> <param name="/$(arg robotname)/amcl/base_frame_id" value="$(arg robotname)/base_link"/> <param name="/$(arg robotname)/amcl/odom_frame_id" value="$(arg robotname)/odom"/> <param name="/$(arg robotname)/amcl/global_frame_id" value="map"/> <!--common map frame for all robots --> </group> <group if="$(arg use_move_base)"> <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"> <rosparam file="$(find patrolling_sim)/params/move_base/costmap_common_params.yaml" command="load" ns="global_costmap" /> <rosparam file="$(find patrolling_sim)/params/move_base/costmap_common_params.yaml" command="load" ns="local_costmap" /> <rosparam file="$(find patrolling_sim)/params/move_base/local_costmap_params.yaml" command="load" /> <rosparam file="$(find patrolling_sim)/params/move_base/global_costmap_params.yaml" command="load" /> <rosparam file="$(find patrolling_sim)/params/move_base/base_local_planner_params.yaml" command="load" /> <!-- remap from="cmd_vel" to="desired_cmd_vel" / --> <!-- Override MOVE_BASE Frame Params to include prefix --> <param name="global_costmap/laser_scan_sensor/sensor_frame" value="/$(arg robotname)/base_laser_link"/> <param name="global_costmap/laser_scan_sensor/topic" value="/$(arg robotname)/base_scan"/> <param name="global_costmap/robot_base_frame" value="/$(arg robotname)/base_link"/> <param name="local_costmap/global_frame" value="/$(arg robotname)/odom"/> <param name="local_costmap/laser_scan_sensor/sensor_frame" value="/$(arg robotname)/base_laser_link"/> <param name="local_costmap/laser_scan_sensor/topic" value="/$(arg robotname)/base_scan"/> <param name="local_costmap/robot_base_frame" value="/$(arg robotname)/base_link"/> </node> </group> <!-- spqrel_navigation modules from RoCoCo lab Sapienza University of Rome, Italy --> <!--- srrg_localizer --> <group if="$(arg use_srrg_localizer)"> <node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 /map /$(arg robotname)/map 100" /> <node pkg="spqrel_navigation" type="srrg_localizer2d_node" name="srrg_localizer" output="screen"> <param name="global_frame_id" value="/$(arg robotname)/map"/> <param name="base_frame_id" value="/$(arg robotname)/base_link"/> <param name="odom_frame_id" value="/$(arg robotname)/odom"/> <param name="laser_topic" value="/$(arg robotname)/base_scan"/> <param name="use_gui" value="false"/> </node> </group> <!--- spqrel_planner --> <group if="$(arg use_spqrel_planner)"> <node pkg="spqrel_navigation" type="spqrel_planner_node" name="spqrel_planner" output="screen"> <param name="max_range" value="10.0"/> <param name="max_linear_vel" value="1.0"/> <param name="max_angular_vel" value="1.0"/> <param name="global_frame_id" value="/$(arg robotname)/map"/> <param name="base_frame_id" value="/$(arg robotname)/base_link"/> <param name="laser_topic" value="/$(arg robotname)/base_scan"/> <param name="command_vel_topic" value="/$(arg robotname)/cmd_vel"/> <param name="robot_radius" value="0.5"/> <param name="use_gui" value="false"/> </node> </group> srrg <!-- INITIAL POSES FOR LOCALIZER --> <include file="$(find patrolling_sim)/params/amcl/$(arg robotname)_initial_pose.xml" /> </group> </launch>