diff --git a/Code/MowingRobot/PIBot_ROS/Image/ROS_Using (3).png b/Code/MowingRobot/PIBot_ROS/Image/ROS_Using (3).png
deleted file mode 100644
index 412438e..0000000
Binary files a/Code/MowingRobot/PIBot_ROS/Image/ROS_Using (3).png and /dev/null differ
diff --git a/Code/MowingRobot/PIBot_ROS/README.md b/Code/MowingRobot/PIBot_ROS/README.md
deleted file mode 100644
index e35b7fb..0000000
--- a/Code/MowingRobot/PIBot_ROS/README.md
+++ /dev/null
@@ -1,93 +0,0 @@
-# `PIBot_ROS`使用说明
-
-> `pibot`是银星合作时购买的小车底盘。其包含直流电机控制、里程计、IMU和上位机通讯等功能。
-
-## 1、远程连接`RK3588`板子
-
- 我们是通过`RK3588 & RK3566`等高性能的主板控制`PIBot`下位机(`STM32`控制板)。如果直接采用`HDMI`线和`USB`鼠标和键盘进行控制非常的不便; 采用`VNC`等远程桌面的方式对性能的损耗较大,所以采用远程ssh连接一种较好的方式。这里,**我们采用的`vscode`进行ssh远程连接**, 其具有远程图形显示功能以及其他强大的功能。
-
- `ssh`连接需要知道目标机器的`ip`地址。理论上如果知道开发板的外网`IP`地址,那么就可以在任意位置连接开发板。由于外网固定`IP`难以获取,所以这里我们**采用局域网ssh连接**。由于`windows`平台的渲染窗口和`linux`不兼容,所以**windows平台的vscode是不支持ssh窗口显示的,需要开启虚拟机或者`linux`主机下面的`vscode`才可以显示窗口**。我们在虚拟机`ubuntu`里面使用`vscode`远程`ssh`连接`RK3588`和虚拟机需要用同个网络,远程连接[教程](http://www.autolabor.com.cn/book/ROSTutorials/di-9-zhang-ji-qi-ren-dao-822a28-shi-4f5329/92-vscodeyuan-cheng-kai-fa.html):
-
-1. `ip`查询方式终端: 在小车终端里输入 `ifconfig`查看小车的ip地址
-2. 将教程里步骤三内容改为:
-
-3. `ssh -X firefly@ip` (-X 为远程显示图形界面需要)
-4. 密码为:`firefly`
-
-5. 连接上后选择需要打开的文件夹
-
-
-## 2、小车驱动编译
-
-#### 2.1 驱动代码位置
-
- `PIBot`的ROS支持包的位置在[仓库]([RobotKernal-UESTC](http://logzhan.ticp.io:30000/logzhan/RobotKernal-UESTC))中,其路径为`Code\RK3588\PIbot_ROS`中。我们解压后可以把`PIBot_ROS`移动到`~/`位置,并重新命名为`pibot_ros`(命名可以按照个人习惯),下面的教程以`pibot_ros`为例。
-
-#### 2.2 3588上编译问题(主要是全覆盖部分)
-
- `PIBot_ROS/ros_ws/src/ipa_coverage_planning`(全覆盖部分的代码)
-
-```shell
-# 进入到ROS的工作空间
-cd pibot_ros/ros_ws
-# 在pibot_ros/ros_ws路径下执行catkin_make
-# ~:/pibot_ros/ros_ws$ catkin_make
-catkin_make
-```
-
-#### 2.3 根据出现的报错缺少的库问题解决
-
-```shell
-# noetic 是ubuntu20.04版本名,其他版本需要更换名字
-sudo apt-get install ros-noetic-xxx
-# 例如:sudo apt-get install ros-noetic-opengm
-sudo apt-get install ros-noetic-libdlib
-sudo apt-get install ros-noetic-cob-navigation
-sudo apt-get install coinor-*
-```
-
-可参考内容:
-
-> [全覆盖规划算法Coverage Path Planning开源代码ipa_coverage_planning编译-CSDN博客](https://blog.csdn.net/ktigerhero3/article/details/121562049)
->
-> [ROS全覆盖规划算法 Coverage Path Planning 采坑-CSDN博客](https://blog.csdn.net/weixin_42179076/article/details/121164350)
-
-## 3、使用说明
-
-#### 3.1 导航的启动
-
- `PIBot_ROS`的文件解压或重新命名可以按照个人习惯即可,这里以解压后命名为`pibot_ros`为例,介绍命令启动导航。
-
-```shell
-# 进入到pibot_ros的工作空间
-cd ~/pibot_ros/ros_ws
-# 配置环境变量
-source ./devel/setup.bash
-# 启动导航文件
-# 格式 roslaunch package_name launch_file_name
-roslaunch pibot_navigation nav.launch
-```
-
-#### 3.2 更改导航地图
-
- 根据导航需求更改导航地图,地图路径在下图左下角位置`pgm`为地图格式 `yaml`为配置文件:
-
-
-
-#### 3.3 小车控制和可视化
-
- 小车的控制和可视化功能需要**开启两个新的终端,分别在终端输入命令**:
-
-```shell
-# 小车的键盘控制,在任意路径执行:
-pibot_control
-```
-
-```shell
-# 导航可视化,在任意路径执行:
-pibot_view (需要设置从主机 记不清 后面再补充)
-```
-
- 在这上面可以在地图上给出目标点进行单点导航。
-
-#### 3.4、全覆盖路径规划的使用
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/README.md b/Code/MowingRobot/PIBot_ROS/ros_ws/src/README.md
deleted file mode 100644
index 23fe7be..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/README.md
+++ /dev/null
@@ -1,6 +0,0 @@
-## ROS包功能说明:
-
-> 更新时间:2024/02/04@詹力
-
-`ipa_coverage_planning` :新添加的全覆盖路径规划算法,这部分代码是原来`pibot`没有的。详细内容见包里面的`README.md`文档。
-
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.gitignore b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.gitignore
deleted file mode 100644
index 5243d90..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.gitignore
+++ /dev/null
@@ -1,48 +0,0 @@
-# default .gitignore file for ipa320 repositories
-# master file can be found in https://github.com/ipa320/care-o-bot/blob/indigo_dev/.gitignore
-
-build/
-bin/
-lib/
-
-# generated docs
-*.dox
-*.wikidoc
-
-# eclipse
-.project
-.cproject
-
-# qcreator
-qtcreator-*
-*.user
-
-# Emacs
-.#*
-
-# VI/VIM
-*.swp
-
-# python files
-*.pcd
-*.pyc
-*.pco
-
-# temporary files
-*~
-
-# merge conflict files
-*.orig
-*BACKUP*
-*BASE*
-*LOCAL*
-*REMOTE*
-
-# Catkin custom files
-CATKIN_IGNORE
-
-# result files
-*.map
-
-# Kdev
-*.kdev4
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall
deleted file mode 100644
index 1bb8bf6..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall
+++ /dev/null
@@ -1 +0,0 @@
-# empty
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall.melodic b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall.melodic
deleted file mode 100644
index 0bce297..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.rosinstall.melodic
+++ /dev/null
@@ -1,8 +0,0 @@
-- git:
- local-name: cob_extern
- uri: https://github.com/ipa320/cob_extern.git
- version: indigo_dev
-- git:
- local-name: cob_perception_common
- uri: https://github.com/ipa320/cob_perception_common.git
- version: indigo_dev
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.yml b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.yml
deleted file mode 100644
index 4babe29..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/.travis.yml
+++ /dev/null
@@ -1,30 +0,0 @@
-language: generic
-services:
- - docker
-
-notifications:
- email:
- on_success: change
- on_failure: always
-env:
- global:
- - ROS_REPO=ros
- matrix:
- - ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=file
- - ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=debian
- - ROS_DISTRO=melodic UPSTREAM_WORKSPACE=file
- - ROS_DISTRO=melodic UPSTREAM_WORKSPACE=debian
- - ROS_DISTRO=noetic UPSTREAM_WORKSPACE=file
- - ROS_DISTRO=noetic UPSTREAM_WORKSPACE=debian
-
-matrix:
- allow_failures:
- - env: ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=file
- - env: ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=debian
- - env: ROS_DISTRO=melodic UPSTREAM_WORKSPACE=debian
- - env: ROS_DISTRO=noetic UPSTREAM_WORKSPACE=debian
-install:
- - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
-script:
- - .ci_config/travis.sh
-# - ./travis.sh # Enable this when you have a package-local script
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/README.md b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/README.md
deleted file mode 100644
index 62ee1ac..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/README.md
+++ /dev/null
@@ -1,42 +0,0 @@
-# ipa_coverage_planning
-> 更新 : 林跃杭、詹力 2024/02/04
->
-> 更新日志:2024/01/31@林跃杭: 在代码中订阅小车控制服务,通过摄像头结点传输的障碍物信息,执行简单的90°的避障行为。
-
-### 一、概述
-
-#### 1.1 代码功能
-
- 机器人全覆盖路径规划算法,这个算法的来源仓库地址: [GitHub](https://github.com/ipa320/ipa_coverage_planning)。机器人的全覆盖算法可以用于割草机器人的草坪全覆盖,这个路径规划库在`pibot_ros`的原始仓库是没有提供的。
-
- 全路径规划算法分为服务端和客户端,服务端可以理解为一个路径规划器,我们把地图提供给服务端,服务端给出全覆盖规划的结果。服务端有一个地图读取数据功能,如果这部分读取的修改为固定值,那么实际上是不需要客户端的。
-
-#### 1.3 ROS 版本支持
-
-| | Indigo | Jade | Kinetic | Melodic | Noetic |
-|:-------:|:------:|:----:|:-------:|:-------:|:-------:|
-| Branch | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`melodic_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/melodic_dev) |[`noetic_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/noetic_dev) |
-| Status | not supported | not supported | EOL | supported | supported |
-| Version | [version](http://repositories.ros.org/status_page/ros_indigo_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_jade_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_kinetic_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_melodic_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_noetic_default.html?q=ipa_coverage_planning)
-
-
-## 二、快速开始
-
-1. 初始化机器人并启动`turtlebot3`的仿真。在使用`pibot`底盘时
-
-1. 开始房间探索行为服务端
-
- ```shell
- roslaunch ipa_room_exploration room_exploration_action_server.launch
- ```
-
- 3.开始房间探索行为客户端
-
-```shell
-roslaunch ipa_room_exploration room_exploration_client.launch robot_env:=your-robot-env use_test_maps:=false
-```
-
-### 三、参考文献
-
-- R. Bormann, F. Jordan, W. Li, J. Hampp, and M. Hägele. Room Segmentation: Survey, Implementation, and Analysis. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), 2016. https://ieeexplore.ieee.org/abstract/document/7487234 , https://publica.fraunhofer.de/entities/publication/0bf23149-75d5-4601-bfce-992d91698862/details
-- R. Bormann, F. Jordan, J. Hampp, and M. Hägele. Indoor coverage path planning: Survey, implementation, analysis. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), pages 1718–1725, May 2018. https://ieeexplore.ieee.org/abstract/document/8460566 , https://publica.fraunhofer.de/entities/publication/f537c15d-4cbe-4672-9d86-6e756a9ce71b/details
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CHANGELOG.rst b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CHANGELOG.rst
deleted file mode 100644
index f8a3879..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CHANGELOG.rst
+++ /dev/null
@@ -1,13 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package ipa_building_msgs
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-0.2.0 (2017-02-09)
-------------------
-* added a srv folder
-* added a srv for ipa_room_exploration/coverage_check_server
-* Contributors: Florian Jordan
-
-0.0.1 (2016-08-06)
-------------------
-* package set up with first set of msgs
-* Contributors: Florian Jordan, Richard Bormann
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CMakeLists.txt b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CMakeLists.txt
deleted file mode 100644
index 0529155..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/CMakeLists.txt
+++ /dev/null
@@ -1,79 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(ipa_building_msgs)
-
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS
- actionlib
- actionlib_msgs
- genmsg
- geometry_msgs
- message_generation
- sensor_msgs
- std_msgs
-)
-
-#######################################
-## Declare ROS messages and services ##
-#######################################
-
-## Add the Files for actionlib
-add_action_files(
- DIRECTORY action
- FILES
- MapSegmentation.action
- FindRoomSequenceWithCheckpoints.action
- RoomExploration.action
-)
-
-## Generate messages in the 'msg' folder
-add_message_files(
- DIRECTORY
- msg
- FILES
- RoomInformation.msg
- RoomSequence.msg
- dis_info.msg
- dis_info_array.msg
-)
-
-## Generate services in the 'srv' folder
-add_service_files(
- DIRECTORY
- srv
- FILES
- CheckCoverage.srv
- ExtractAreaMapFromLabeledMap.srv
-)
-
-## Generate added messages and services with any dependencies listed here
-generate_messages(
- DEPENDENCIES
- actionlib_msgs
- geometry_msgs
- sensor_msgs
- std_msgs
-)
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-catkin_package(
- CATKIN_DEPENDS
- actionlib_msgs
- geometry_msgs
- message_runtime
- sensor_msgs
- std_msgs
-)
-
-include_directories(
- ${catkin_INCLUDE_DIRS}
-)
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/FindRoomSequenceWithCheckpoints.action b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/FindRoomSequenceWithCheckpoints.action
deleted file mode 100644
index b436771..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/FindRoomSequenceWithCheckpoints.action
+++ /dev/null
@@ -1,17 +0,0 @@
-# goal definition
-sensor_msgs/Image input_map # floor plan map [mono8 format], 0=obstacle or unknown, 255=free space
-float32 map_resolution # the resolution of the map in [meter/cell]
-geometry_msgs/Pose map_origin # the origin of the map in [meter]
-ipa_building_msgs/RoomInformation[] room_information_in_pixel # room data (min/max coordinates, center coordinates) measured in pixels
-float64 robot_radius # the robot footprint radius [m], used for excluding areas from path planning that could not be visited by the robot
-geometry_msgs/Pose robot_start_coordinate # current robot location (used to determine the closest checkpoint in the sequence of checkpoints) [in meter]
-
----
-
-# result definition
-ipa_building_msgs/RoomSequence[] checkpoints # sequence of checkpoints, should be ordered in optimized traveling salesman sequence
- # (checkpoint = a clique of rooms close [in terms of robot driving distance] to each other,
- # and a central [in terms of rooms in the group] checkpoint location)
-sensor_msgs/Image sequence_map # map that has the calculated sequence drawn in
----
-#feedback definition
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/MapSegmentation.action b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/MapSegmentation.action
deleted file mode 100644
index 9f443ce..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/MapSegmentation.action
+++ /dev/null
@@ -1,39 +0,0 @@
-# Map Segmentation action
-# Provides interface to get the segmented map
-
-# goal definition
-sensor_msgs/Image input_map # the action server need a map as a input image to segment it, IMPORTANT: The algorithm needs a black and white 8bit single-channel image (format 8UC1), which is 0 (black) for obstacles and 255 (white) for free space
-float32 map_resolution # the resolution of the map in [meter/cell]
-geometry_msgs/Pose map_origin # the origin of the map in [meter]
-bool return_format_in_pixel # return room data (see below) in [pixel]
-bool return_format_in_meter # return room data (see below) in [meter]
-float32 robot_radius # in [meter]; if this variable is set to a value greater than 0, the room centers are chosen at locations that are reachable from neighboring rooms (i.e. not inside the legs of a table surrounded by chairs)
-int32 room_segmentation_algorithm # optionally overrides the parameterized segmentation method (if -1 it just takes the preset)
- # 0 = take the preset (parameterized) method
- # 1 = MorphologicalSegmentation
- # 2 = DistanceSegmentation
- # 3 = VoronoiSegmentation
- # 4 = SemanticSegmentation
- # 5 = RandomFieldSegmentation
- # 99 = PassThrough (just get a pre-segmented map into the right output format)
-
----
-
-# result definition
-sensor_msgs/Image segmented_map # the action server returns a map segmented into rooms which carry the segment number in every pixel cell, format 32SC1, room labels from 1 to N, room with label i -> access to room_information_in_pixel[i-1]
-float32 map_resolution # the resolution of the segmented map in [meter/cell]
-geometry_msgs/Pose map_origin # the origin of the segmented map in [meter]
-# for the following data: value in pixel can be obtained when the value of [return_format_in_pixel] from goal definition is true
-# the computed room centers are not the centroids of the room cells (which could be located outside of the rooms)
-# but accessible map pixels located within the center of the largest free space in the room
-ipa_building_msgs/RoomInformation[] room_information_in_pixel # room data (min/max coordinates, center coordinates) measured in pixels
-# for the following data: value in meter can be obtained when the value of [return_format_in_meter] from goal definition is true
-# the computed room centers are not the centroids of the room cells (which could be located outside of the rooms)
-# but accessible map pixels located within the center of the largest free space in the room
-ipa_building_msgs/RoomInformation[] room_information_in_meter # room data (min/max coordinates, center coordinates) measured in meters
-# if wanted the 5th algorithm (vrf) can return single points labeled as a doorway
-geometry_msgs/Point32[] doorway_points
-
----
-
-#feedback definition
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/RoomExploration.action b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/RoomExploration.action
deleted file mode 100644
index 3e9e029..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/action/RoomExploration.action
+++ /dev/null
@@ -1,24 +0,0 @@
-# Room Exploration action
-# sends an occupancy grid map of a room to the server, which plans a path trough it to cover or inspect the whole room by a device or camera
-
-# goal definition
-sensor_msgs/Image input_map # the action server needs a map as a input image to segment it,
- # IMPORTANT: The algorithm needs a black and white 8bit single-channel image (format 8UC1), which is 0 (black) for obstacles and 255 (white) for free space
- # todo: the image needs to be vertically mirrored compared to the map in RViz for using right coordinate systems
- # OccupancyGrid map = origin lower left corner, image = origin upper left corner
- # todo: take the OccupanyGrid message here instead to avoid confusion and deal with map coordinates in server
-float32 map_resolution # the resolution of the map in [meter/cell]
-geometry_msgs/Pose map_origin # the origin of the map in [meter], NOTE: rotations are not supported for now
-float32 robot_radius # effective robot radius, taking the enlargement of the costmap into account, in [meter]
-float32 coverage_radius # radius that is used to plan the coverage planning for the robot and not the field of view, assuming that the part that needs to cover everything (e.g. the cleaning part) can be represented by a fitting circle (e.g. smaller than the actual part to ensure coverage), in [meter]
-geometry_msgs/Point32[] field_of_view # the 4 points that define the field of view of the robot, relatively to the robot coordinate system (with x pointing forwards and y pointing to the left), in [meter]
-geometry_msgs/Point32 field_of_view_origin # the mounting position of the camera spanning the field of view, relative to the robot center (x-axis points to robot's front side, y-axis points to robot's left side, z-axis upwards), in [meter]
-geometry_msgs/Pose2D starting_position # starting pose of the robot in the room coordinate system [meter,meter,rad]
-int32 planning_mode # 1 = plans a path for coverage with the robot footprint, 2 = plans a path for coverage with the robot's field of view
-
----
-# result definition
-geometry_msgs/Pose2D[] coverage_path # when the server should return the coverage path, this is done returning the points in an array that shows the order of visiting
-geometry_msgs/PoseStamped[] coverage_path_pose_stamped # (same content as coverage_path but different format) when the server should return the coverage path, this is done returning the points in an array that shows the order of visiting
----
-# feedback definition
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomInformation.msg b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomInformation.msg
deleted file mode 100644
index 5ee2539..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomInformation.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-geometry_msgs/Polygon room_min_max # first point provides the minimum (x,y)-coordinate values of the rooms, second point provides the maximum (x,y)-coordinate values of the rooms
-geometry_msgs/Point32 room_center # provides the (x,y)-coordinate values of the room centers
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomSequence.msg b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomSequence.msg
deleted file mode 100644
index 87439d1..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/RoomSequence.msg
+++ /dev/null
@@ -1,5 +0,0 @@
-uint32[] room_indices # indices of those rooms that belong to one group (connected to a checkpoint,
- # i.e. the clique of rooms close [in terms of robot driving distance] to each other),
- # indices should be ordered in optimized traveling salesman sequence
-geometry_msgs/Point32 checkpoint_position_in_pixel # provides the (x,y)-coordinates of the checkpoint location for this group of rooms [in pixel]
-geometry_msgs/Point32 checkpoint_position_in_meter # provides the (x,y)-coordinates of the checkpoint location for this group of rooms [in meter]
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/dis_info_array.msg b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/dis_info_array.msg
deleted file mode 100644
index 77a722d..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/msg/dis_info_array.msg
+++ /dev/null
@@ -1 +0,0 @@
-ipa_building_msgs/dis_info[] dis
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/package.xml b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/package.xml
deleted file mode 100644
index 2162e5a..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/package.xml
+++ /dev/null
@@ -1,27 +0,0 @@
-
-
- ipa_building_msgs
- 0.2.0
-
-
- This package contains common message type definitions for building navigation tasks such as floor plan segmentation into rooms or the optimal trajectory through rooms of a building.
-
-
- LGPL for academic and non-commercial use; for commercial use, please contact Fraunhofer IPA
-
- Richard Bormann
- Richard Bormann
-
- catkin
-
- message_generation
- message_runtime
-
- actionlib
- actionlib_msgs
- geometry_msgs
- sensor_msgs
- std_msgs
-
-
-
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/CheckCoverage.srv b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/CheckCoverage.srv
deleted file mode 100644
index 76b6762..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/CheckCoverage.srv
+++ /dev/null
@@ -1,12 +0,0 @@
-sensor_msgs/Image input_map # the action server need a map as a input image to segment it, IMPORTANT: The algorithm needs a black and white 8bit single-channel image, which is 0 (black) for obstacles and 255 (white) for free space
-float32 map_resolution # resolution of the given map, in [meter/cell]
-geometry_msgs/Pose map_origin # the origin of the map, in [meter]
-geometry_msgs/Pose2D[] path # check the coverage along this path of the robot center, in the world frame in [meter]
-geometry_msgs/Point32[] field_of_view # the points that define the field of view of the robot, relative to the robot center (x-axis points to robot's front side, y-axis points to robot's left side, z-axis upwards), in [meter]
-geometry_msgs/Point32 field_of_view_origin # the mounting position of the camera spanning the field of view, relative to the robot center (x-axis points to robot's front side, y-axis points to robot's left side, z-axis upwards), in [meter]
-float32 coverage_radius # radius that is used to plan the coverage planning for the robot and not the field of view, assuming that the part that needs to cover everything (e.g. the cleaning part) can be represented by a fitting circle (e.g. smaller than the actual part to ensure coverage), in [meter]
-bool check_for_footprint # determine, if the coverage check should be done for the footprint or the field of view
-bool check_number_of_coverages # if set, the server returns a map that shows how often one pixel has been covered during the path, return format: 32bit single-channel image
----
-sensor_msgs/Image coverage_map # the map that has the covered areas drawn in, with a value of 255, an 8bit single-channel image
-sensor_msgs/Image number_of_coverage_image # the image that carries for each pixel the number of coverages when executing the path, 32bit single-channel image
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/ExtractAreaMapFromLabeledMap.srv b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/ExtractAreaMapFromLabeledMap.srv
deleted file mode 100644
index 401834a..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_msgs/srv/ExtractAreaMapFromLabeledMap.srv
+++ /dev/null
@@ -1,14 +0,0 @@
-# The request message provides a segmented map which consists of cells with label 0 for inaccessible areas and other number from 1 to N
-# for labeling membership with one of the N segmented areas.
-# The return message shall deliver the same map but with only one area (segment_of_interest) labeled as 255 and the remainder labeled
-# as inaccessible with 0.
-
-sensor_msgs/Image segmented_map # a map segmented into N areas which carry the respective segment number in every pixel cell,
- # format 32SC1, room labels from 1 to N, 0 represents inaccessible cells (e.g. walls)
-int32 segment_of_interest # the specific area label of the area of which a map shall be created
-
----
-
-sensor_msgs/Image segmented_area # a map that only contains the area which is labeled with segment_of_interest in segmented_map,
- # the parts of that area are labeled as 255 in this map and the remainder is labeled as inaccessible with 0
- # data type is a 8bit single-channel image (format 8UC1)
\ No newline at end of file
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/CMakeLists.txt b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/CMakeLists.txt
deleted file mode 100644
index c9fbd4f..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/CMakeLists.txt
+++ /dev/null
@@ -1,202 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(ipa_building_navigation)
-
-# build with c++11
-add_compile_options(-std=c++11)
-
-set(catkin_RUN_PACKAGES
- actionlib
- cv_bridge
- geometry_msgs
- ipa_building_msgs
- roscpp
- roslib
- sensor_msgs
- visualization_msgs
-)
-
-set(catkin_BUILD_PACKAGES
- ${catkin_RUN_PACKAGES}
- dynamic_reconfigure
-)
-
-## Find catkin macros and libraries
-find_package(catkin REQUIRED COMPONENTS
- ${catkin_BUILD_PACKAGES}
-)
-
-generate_dynamic_reconfigure_options(
- cfg/BuildingNavigation.cfg
-)
-
-find_package(OpenCV REQUIRED)
-find_package(Boost REQUIRED COMPONENTS system thread chrono)
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-# important: common/include needs to be here if you have such a directory
-catkin_package(
-INCLUDE_DIRS
- common/include
- ros/include
-LIBRARIES
- ${PROJECT_NAME}
- tsp_solvers
-CATKIN_DEPENDS
- ${catkin_RUN_PACKAGES}
-DEPENDS
-# libconcorde_tsp_solver
- OpenCV
- Boost
-)
-
-
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-# include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
-# important: common/include also needs to be here if you have it
-include_directories(
- common/include
- ros/include
- ${catkin_INCLUDE_DIRS}
- ${OpenCV_INCLUDE_DIRS}
- ${Boost_INCLUDE_DIRS}
-)
-
-# TSP library
-add_library(tsp_solvers
- common/src/A_star_pathplanner.cpp
- common/src/node.cpp
- common/src/nearest_neighbor_TSP.cpp
- common/src/genetic_TSP.cpp
- common/src/concorde_TSP.cpp
-)
-target_link_libraries(tsp_solvers
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
- ${Boost_LIBRARIES}
-)
-add_dependencies(tsp_solvers
- ${catkin_EXPORTED_TARGETS}
- ${${PROJECT_NAME}_EXPORTED_TARGETS}
-)
-
-# package library
-add_library(${PROJECT_NAME} STATIC
- common/src/maximal_clique_finder.cpp
- common/src/set_cover_solver.cpp
- common/src/trolley_position_finder.cpp
-)
-target_link_libraries(${PROJECT_NAME}
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
- ${Boost_LIBRARIES}
-)
-add_dependencies(${PROJECT_NAME}
- ${catkin_EXPORTED_TARGETS}
- ${${PROJECT_NAME}_EXPORTED_TARGETS}
-)
-
-# action provider
-add_executable(room_sequence_planning_server
- ros/src/room_sequence_planning_action_server.cpp
- )
-target_link_libraries(room_sequence_planning_server
- tsp_solvers
- ${PROJECT_NAME}
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
- ${Boost_LIBRARIES}
-)
-add_dependencies(room_sequence_planning_server
- ${catkin_EXPORTED_TARGETS}
- ${${PROJECT_NAME}_EXPORTED_TARGETS}
- ${PROJECT_NAME}_gencfg
-)
-
-# client for testing purpose
-add_executable(room_sequence_planning_client ros/src/room_sequence_planning_action_client.cpp)
-target_link_libraries(room_sequence_planning_client
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
-)
-add_dependencies(room_sequence_planning_client ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
-
-# client for testing purpose
-add_executable(room_sequence_planning_evaluation
- ros/src/room_sequence_planning_evaluation.cpp
- common/src/A_star_pathplanner.cpp
- common/src/node.cpp
-)
-target_link_libraries(room_sequence_planning_evaluation
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
-)
-add_dependencies(room_sequence_planning_evaluation ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
-
-# evaluation
-add_executable(TSP_evaluation
- ros/src/boosttest.cpp
-)
-target_link_libraries(TSP_evaluation
- tsp_solvers
- ${catkin_LIBRARIES}
- ${OpenCV_LIBRARIES}
-)
-add_dependencies(TSP_evaluation ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
-
-#tester for different functions
-#add_executable(a_star_tester ros/src/tester.cpp common/src/A_star_pathplanner.cpp common/src/node.cpp common/src/nearest_neighbor_TSP.cpp common/src/genetic_TSP.cpp common/src/concorde_TSP.cpp common/src/maximal_clique_finder.cpp common/src/set_cover_solver.cpp common/src/trolley_position_finder.cpp)
-#target_link_libraries(a_star_tester ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${Boost_LIBRARIES})
-#add_dependencies(a_star_tester ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
-
-
-#############
-## Install ##
-#############
-# Mark executables and/or libraries for installation
-install(TARGETS ${PROJECT_NAME} tsp_solvers room_sequence_planning_server room_sequence_planning_client #a_star_tester tester
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-)
-
-#uncomment this if you have a common-directory with header-files
-install(DIRECTORY common/include/${PROJECT_NAME}/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
- FILES_MATCHING PATTERN "*.h"
- PATTERN ".svn" EXCLUDE
-)
-
-#uncomment this if you have header-files in your project
-install(DIRECTORY ros/include/${PROJECT_NAME}/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
- FILES_MATCHING PATTERN "*.h"
- PATTERN ".svn" EXCLUDE
-)
-
-#install(DIRECTORY scripts
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# PATTERN ".svn" EXCLUDE
-#)
-
-##uncomment this if you use launch and yaml files
-install(DIRECTORY ros/launch
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/ros
- PATTERN ".svn" EXCLUDE
-)
-
-#install(DIRECTORY common/files
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/common
-# PATTERN ".svn" EXCLUDE
-#)
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/cfg/BuildingNavigation.cfg b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/cfg/BuildingNavigation.cfg
deleted file mode 100644
index cb41b52..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/cfg/BuildingNavigation.cfg
+++ /dev/null
@@ -1,42 +0,0 @@
-#!/usr/bin/env python
-PACKAGE = "ipa_building_navigation"
-
-from dynamic_reconfigure.parameter_generator_catkin import *
-
-gen = ParameterGenerator()
-
-# TSP solver
-tsp_enum = gen.enum([ gen.const("NearestNeighbor", int_t, 1, "Use the nearest neighbor TSP algorithm."),
- gen.const("GeneticSolver", int_t, 2, "Use the genetic TSP algorithm."),
- gen.const("ConcordeSolver", int_t, 3, "Use the Concorde TSP algorithm.")],
- "TSP solver")
-gen.add("tsp_solver", int_t, 0, "TSP solver", 3, 1, 3, edit_method=tsp_enum)
-
-# problem setting
-problem_setting_enum = gen.enum([ gen.const("SimpleOrderPlanning", int_t, 1, "Plan the optimal order of a simple set of locations."),
- gen.const("CheckpointBasedPlanning", int_t, 2, "Two-stage planning that creates local cliques of locations (= checkpoints) and determines the optimal order through the members of each clique as well as the optimal order through the cliques.")],
- "Problem setting of the sequence planning problem")
-gen.add("problem_setting", int_t, 0, "Problem setting of the sequence planning problem", 2, 1, 2, edit_method=problem_setting_enum)
-
-
-# checkpoint-based sequence planning specifics
-trolley_placement_method_enum = gen.enum([ gen.const("DragTrolleyWhenNecessary", int_t, 1, "Drag the trolley if it is too far away from next room."),
- gen.const("PrecomputeRoomGroupsAndCorrespondingTrolleyPosition", int_t, 2, "Put rooms together in groups and calculate a corresponding trolley positions.")],
- "Trolley placement method (only applies to CheckpointBasedPlanning problem)")
-gen.add("planning_method", int_t, 0, "Trolley placement method (only applies to CheckpointBasedPlanning problem)", 2, 1, 2, edit_method=trolley_placement_method_enum)
-
-gen.add("max_clique_path_length", double_t, 0, "Max A* path length between two rooms that are assigned to the same clique, in [m] (only applies to CheckpointBasedPlanning problem)", 12.0, 0.0)
-
-gen.add("maximum_clique_size", int_t, 0, "Maximal number of nodes belonging to one trolley clique (only applies to CheckpointBasedPlanning problem)", 9001, 0)
-
-
-# general settings
-gen.add("map_downsampling_factor", double_t, 0, "The map may be downsampled during computations (e.g. of A* path lengths) in order to speed up the algorithm, if set to 1 the map will have original size, if set to 0 the algorithm won't work", 0.25, 0.00001, 1.0)
-
-gen.add("check_accessibility_of_rooms", bool_t, 0, "Tells the sequence planner if it should check the given room centers for accessibility from the starting position", True)
-
-gen.add("return_sequence_map", bool_t, 0, "Tells the server if the map with the sequence drawn in should be returned", False)
-
-gen.add("display_map", bool_t, 0, "Show the resulting map with paths (only if return_sequence_map=true)", False)
-
-exit(gen.generate(PACKAGE, "room_sequence_planning_action_server", "BuildingNavigation"))
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/A_star_pathplanner.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/A_star_pathplanner.h
deleted file mode 100644
index cd75565..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/A_star_pathplanner.h
+++ /dev/null
@@ -1,62 +0,0 @@
-// Astar.cpp
-// http://en.wikipedia.org/wiki/A*
-// Compiler: Dev-C++ 4.9.9.2
-// FB - 201012256
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This class provides an AStar pathplanner, which calculates the pathlength from one cv::Point to another. It was taken from
-// http://code.activestate.com/recipes/577457-a-star-shortest-path-algorithm/ and slightly changed (to use it with openCV).
-//It needs node.h to work, which gives an implementation of nodes of the graph.
-//
-//!!!!!!!!!Important!!!!!!!!!!!!!
-//It downsamples the map mith the given factor (0 < factor < 1) so the map gets reduced and calculationtime gets better.
-//If it is set to 1 the map will have original size, if it is 0 the algorithm won't work, so make sure to not set it to 0.
-//The algorithm also needs the Robot radius [m] and the map resolution [m²/pixel] to calculate the needed
-//amount of erosions to include the radius in the planning.
-//
-
-class AStarPlanner
-{
-protected:
- int n;
- int m;
-
- std::string route_;
-
- std::string pathFind(const int& xStart, const int& yStart, const int& xFinish, const int& yFinish, const cv::Mat& map);
-
-public:
- AStarPlanner();
-
- void drawRoute(cv::Mat& map, const cv::Point start_point, const std::string& route, double step_length);
-
- void getRoute(const cv::Point start_point, const std::string& route, double step_length, std::vector& route_points);
-
- // computes the path length between start point and end point
- double planPath(const cv::Mat& map, const cv::Point& start_point, const cv::Point& end_point,
- const double downsampling_factor, const double robot_radius, const double map_resolution,
- const int end_point_valid_neighborhood_radius=0, std::vector* route=NULL);
-
- // computes the path length between start point and end point, tries first with a downsampled map for fast computation and uses the original map if the first try was not successful
- // if end_point_valid_neighborhood_radius [measured in cell size of downsampled_map] is set greater than 0, then it is sufficient to find a path to a cell within that neighborhood radius to end_point for a success
- double planPath(const cv::Mat& map, const cv::Mat& downsampled_map, const cv::Point& start_point, const cv::Point& end_point, const double downsampling_factor,
- const double robot_radius, const double map_resolution, const int end_point_valid_neighborhood_radius=0, cv::Mat* draw_path_map=NULL,
- std::vector* route=NULL);
-
- void downsampleMap(const cv::Mat& map, cv::Mat& downsampled_map, const double downsampling_factor, const double robot_radius, const double map_resolution);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/concorde_TSP.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/concorde_TSP.h
deleted file mode 100644
index 2bb1336..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/concorde_TSP.h
+++ /dev/null
@@ -1,92 +0,0 @@
-#include "ros/ros.h"
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-#include
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
-//regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This class applies an object to solve a given TSP problem using the concorde TSP solver. This solver can be downloaded at:
-// http://www.math.uwaterloo.ca/tsp/concorde.html
-//A short explanation on how to build the solver is given at:
-// http://www.math.uwaterloo.ca/tsp/concorde/DOC/README.html
-//If you have build the solver navigate to the./TSP folder and type " ./concorde -h " to see how to use this solver. This class
-//uses the concorde solver by using a systemcall.
-//Make sure you have a "/common/files/TSP_order.txt" and a "/common/files/TSPlib_file.txt" file. These files are used to tell
-//concorde the current problem and save the output of it.
-//
-//It needs a symmetrical matrix of pathlenghts between the nodes and the starting-point index in this matrix.
-//If the path from one node to another doesn't exist or the path is from one node to itself, the entry in the matrix must
-//be 0 or smaller. so the format for this matrix is:
-// row: node to start from, column: node to go to
-// --- ---
-// | 0.0 1.0 3.5 5.8 1.2 |
-// | 1.0 0.0 2.4 3.3 9.0 |
-// | 3.5 2.4 0.0 7.7 88.0|
-// | 5.8 3.3 7.7 0.0 0.0 |
-// | 1.2 9.0 88.0 0.0 0.0 |
-// --- ---
-
-class ConcordeTSPSolver
-{
-protected:
-
- //Astar pathplanner to find the pathlengths from cv::Point to cv::Point
- AStarPlanner pathplanner_;
-
- //Function to create neccessary TSPlib file to tell concorde what the problem is.
- void writeToFile(const cv::Mat& pathlength_matrix, const std::string& tsp_lib_filename, const std::string& tsp_order_filename);
-
- //Function to read the saved TSP order.
- std::vector readFromFile(const std::string& tsp_order_filename);
-
- void distance_matrix_thread(DistanceMatrix& distance_matrix_computation, cv::Mat& distance_matrix,
- const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, AStarPlanner& path_planner);
-
- bool abort_computation_;
- std::string unique_file_identifier_;
-
-public:
- //Constructor
- ConcordeTSPSolver();
-
- void abortComputation();
-
- //Functions to solve the TSP. It needs a distance matrix, that shows the pathlengths between two nodes of the problem.
- //This matrix has to be symmetrical or else the TSPlib must be changed. The int shows the index in the Matrix.
- //There are two functions for different cases:
- // 1. The distance matrix already exists
- // 2. The distance matrix has to be computed and maybe returned
-
- //with given distance matrix
- std::vector solveConcordeTSP(const cv::Mat& path_length_Matrix, const int start_Node);
-
- // compute distance matrix and maybe return it
- // this version does not exclude infinite paths from the TSP ordering
- std::vector solveConcordeTSP(const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, const int start_Node, cv::Mat* distance_matrix = 0);
-
- // compute TSP from a cleaned distance matrix (does not contain any infinity paths) that has to be computed
- std::vector solveConcordeTSPClean(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, const int start_node);
-
- // compute TSP with pre-computed cleaned distance matrix (does not contain any infinity paths)
- std::vector solveConcordeTSPWithCleanedDistanceMatrix(const cv::Mat& distance_matrix,
- const std::map& cleaned_index_to_original_index_mapping, const int start_node);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/contains.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/contains.h
deleted file mode 100644
index ab75a53..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/contains.h
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "ros/ros.h"
-#include
-#include
-#include
-#include
-#include
-#include
-
-#pragma once
-
-//This function searches for the given element in the given vector and returns true if it is in it or false if not
-template
-bool inline contains(std::vector vector, T element)
-{
- //this functions checks, if the given element is in the given vector (in this case for int elements)
- if (!vector.empty())
- {
- return vector.end() != std::find(vector.begin(), vector.end(), element);
- }
- else
- {
- return false;
- }
-}
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/distance_matrix.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/distance_matrix.h
deleted file mode 100644
index 29b79f8..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/distance_matrix.h
+++ /dev/null
@@ -1,261 +0,0 @@
-
-
-#pragma once
-
-#include
-#include
-#include
-
-#include
-
-class DistanceMatrix
-{
-protected:
-
- bool abort_computation_;
-
-public:
-
- DistanceMatrix()
- : abort_computation_(false)
- {
- }
-
- void abortComputation()
- {
- abort_computation_ = true;
- }
-
- //Function to construct the symmetrical distance matrix from the given points. The rows show from which node to start and
- //the columns to which node to go. If the path between nodes doesn't exist or the node to go to is the same as the one to
- //start from, the entry of the matrix is 0.
- // REMARK: paths is a pointer that points to a 3D vector that has dimensionality NxN in the outer vectors to store
- // the paths in a matrix manner
- void constructDistanceMatrix(cv::Mat& distance_matrix, const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, AStarPlanner& path_planner,
- std::vector > >* paths=NULL)
- {
- std::cout << "DistanceMatrix::constructDistanceMatrix: Constructing distance matrix..." << std::endl;
- Timer tim;
-
- //create the distance matrix with the right size
- distance_matrix.create((int)points.size(), (int)points.size(), CV_64F);
-
- // hack: speed up trick
- if (points.size()>500)
- downsampling_factor *= 0.5;
-
- // reduce image size already here to avoid resizing in the planner each time
- const double one_by_downsampling_factor = 1./downsampling_factor;
- cv::Mat downsampled_map;
- path_planner.downsampleMap(original_map, downsampled_map, downsampling_factor, robot_radius, map_resolution);
-
- if (points.size()>500)
- std::cout << "0 10 20 30 40 50 60 70 80 90 100" << std::endl;
-// int a=0, b=0;
- for (int i = 0; i < points.size(); i++)
- {
- //std::cout << " a=" << a << " b=" << b << std::endl;
- if (points.size()>500 && i%(std::max(1,(int)points.size()/100))==0)
- std::cout << "." << std::flush;
- //cv::Point current_center = downsampling_factor * points[i];
- for (int j = 0; j < points.size(); j++)
- {
- if (j != i)
- {
- if (j > i) //only compute upper right triangle of matrix, rest is symmetrically added
- {
- if (abort_computation_==true)
- return;
-
- // try first with direct connecting line (often sufficient and a significant speedup over A*)
- cv::LineIterator it(original_map, points[i], points[j]);
- bool direct_connection = true;
- for (int k=0; k(i, j) = length;
- distance_matrix.at(j, i) = length; //symmetrical-Matrix --> saves half the computation time
- if (paths!=NULL)
- {
- // store path
- cv::LineIterator it2(original_map, points[i], points[j]);
- std::vector current_path(it2.count);
- for (int k=0; kat(i).at(j) = current_path;
- paths->at(j).at(i) = current_path;
- }
-// ++a;
- }
- else
- {
- // A* path planner
- if(paths!=NULL)
- {
- std::vector current_path;
- double length = path_planner.planPath(original_map, downsampled_map, points[i], points[j], downsampling_factor, 0., map_resolution, 0, NULL, ¤t_path);
- distance_matrix.at(i, j) = length;
- distance_matrix.at(j, i) = length; //symmetrical-Matrix --> saves half the computation time
-
- // remap path points to original map size
- for(std::vector::iterator point=current_path.begin(); point!=current_path.end(); ++point)
- {
- point->x = point->x/downsampling_factor;
- point->y = point->y/downsampling_factor;
- }
-
- paths->at(i).at(j) = current_path;
- paths->at(j).at(i) = current_path;
- }
- else
- {
- double length = path_planner.planPath(original_map, downsampled_map, points[i], points[j], downsampling_factor, 0., map_resolution);
- distance_matrix.at(i, j) = length;
- distance_matrix.at(j, i) = length; //symmetrical-Matrix --> saves half the computation time
-
- }
-// ++b;
- }
- }
- }
- else
- {
- distance_matrix.at(i, j) = 0;
- }
- }
- }
-
- std::cout << "\nDistance matrix created in " << tim.getElapsedTimeInMilliSec() << " ms" << std::endl;// "\nDistance matrix:\n" << distance_matrix << std::endl;
- }
-
- // check whether distance matrix contains infinite path lengths and if this is true, create a new distance matrix with maximum size clique of reachable points
- // cleaned_index_to_original_index_mapping --> maps the indices of the cleaned distance_matrix to the original indices of the original distance_matrix
- void cleanDistanceMatrix(const cv::Mat& distance_matrix, cv::Mat& distance_matrix_cleaned, std::map& cleaned_index_to_original_index_mapping)
- {
- // standard: use a 1:1 mapping (input = output)
- cleaned_index_to_original_index_mapping.clear();
- for (int i=0; i remove_entry(distance_matrix.rows, false); // keeps track on which entries of distance_matrix need to be removed
-
- // loop until all lines are marked, which need to be removed
- cv::Mat distance_matrix_temp = distance_matrix.clone();
- while (true)
- {
- // count infinite entries in each row of distance matrix
- std::vector infinite_length_entries(distance_matrix_temp.rows, 0);
- for (int i=0; i(i,j)>max_length)
- infinite_length_entries[i]++;
-
- // sort rows by their number of infinite entries
- std::multimap number_infinite_entries_to_row_index_mapping; // maps number of infinite entries to the corresponding row index
- for (size_t i=0; i(infinite_length_entries[i], (int)i));
-
- // if any row has at least one infinite entry, mark the row with most infinity entries for deletion
- bool mark_line = false;
- int mark_index = -1;
- std::multimap::reverse_iterator number_infinite_entries_to_row_index_mapping_last = number_infinite_entries_to_row_index_mapping.rbegin();
- if (number_infinite_entries_to_row_index_mapping_last->first > 0)
- {
- mark_line = true;
- mark_index = number_infinite_entries_to_row_index_mapping_last->second;
- remove_entry[mark_index] = true;
- }
- if (mark_line == true)
- {
- for (int j=0; j(mark_index, j) = -1.;
- for (int i=0; i(i, mark_index) = -1.;
- }
- else
- break;
- }
-
- // count entries to remove
- int number_entries_to_be_removed = 0;
- for (size_t i=0; i 0)
- {
- std::cout << " DistanceMatrix::cleanDistanceMatrix: Need to remove " << number_entries_to_be_removed << " elements out of " << distance_matrix.rows << " elements from the distance matrix." << std::endl;
-
- // setup new distance_matrix
- const int new_size = distance_matrix.rows - number_entries_to_be_removed;
- if (new_size == 0)
- {
- std::cout << " DistanceMatrix::cleanDistanceMatrix: Warning: Would need to remove all elements of distance_matrix. Aborting." << std::endl;
- return;
- }
- distance_matrix_cleaned.create(new_size, new_size, CV_64F);
- cleaned_index_to_original_index_mapping.clear();
-
- // fill new distance_matrix
- int new_index = 0;
- for (size_t i=0; i(new_index, new_j) = distance_matrix.at(i,j);
- new_j++;
- }
- }
- new_index++;
- }
- }
- if (new_index != new_size)
- std::cout << "##################################################\nDistanceMatrix::cleanDistanceMatrix: Warning: new_index != new_size.\n##################################################" << std::endl;
- }
- }
-
- // calculate the distance matrix and check whether distance matrix contains infinite path lengths and if this is true,
- // create a new distance matrix with maximum size clique of reachable points
- // start_node --> provide the original start node to the function, it writes the new start node mapped to the new coordinates into it
- // cleaned_index_to_original_index_mapping --> maps the indices of the cleaned distance_matrix to the original indices of the original distance_matrix
- void computeCleanedDistanceMatrix(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, AStarPlanner& path_planner,
- cv::Mat& distance_matrix, std::map& cleaned_index_to_original_index_mapping, int& start_node)
- {
- std::cout << "DistanceMatrix::computeCleanedDistanceMatrix: Constructing distance matrix..." << std::endl;
- // calculate the distance matrix
- cv::Mat distance_matrix_raw;
- constructDistanceMatrix(distance_matrix_raw, original_map, points, downsampling_factor, robot_radius, map_resolution, path_planner);
-
- // check whether distance matrix contains infinite path lengths and if this is true, create a new distance matrix with maximum size clique of reachable points
- cleanDistanceMatrix(distance_matrix_raw, distance_matrix, cleaned_index_to_original_index_mapping);
-
- // re-assign the start node to cleaned indices (use 0 if the original start node was removed from distance_matrix_cleaned)
- int new_start_node = 0;
- for (std::map::iterator it=cleaned_index_to_original_index_mapping.begin(); it!=cleaned_index_to_original_index_mapping.end(); ++it)
- if (it->second == start_node)
- new_start_node = it->first;
- start_node = new_start_node;
- }
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/genetic_TSP.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/genetic_TSP.h
deleted file mode 100644
index e2a24e2..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/genetic_TSP.h
+++ /dev/null
@@ -1,91 +0,0 @@
-#include "ros/ros.h"
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This class provides a solution for the TSP by taking the nearest-neighbor path and applying a genetic algorithm on it.
-//It needs a symmetrical matrix of pathlenghts between the nodes and the starting-point index in this matrix.
-//If the path from one node to another doesn't exist or the path is from one node to itself, the entry in the matrix must
-//be 0 or smaller. so the format for this matrix is:
-// row: node to start from, column: node to go to
-// --- ---
-// | 0.0 1.0 3.5 5.8 1.2 |
-// | 1.0 0.0 2.4 3.3 9.0 |
-// | 3.5 2.4 0.0 7.7 88.0|
-// | 5.8 3.3 7.7 0.0 0.0 |
-// | 1.2 9.0 88.0 0.0 0.0 |
-// --- ---
-
-class GeneticTSPSolver
-{
-protected:
-
- //Astar pathplanner to find the pathlengths from cv::Point to cv::Point
- AStarPlanner pathplanner_;
-
- //function to get the length of a given path
- double getPathLength(const cv::Mat& path_length_Matrix, std::vector given_path);
-
- //function to mutate (randomly change) a given Parent-path
- std::vector mutatePath(const std::vector& parent_path);
-
- //function that selects the best path from the given paths
- std::vector getBestPath(const std::vector > paths, const cv::Mat& pathlength_Matrix, bool& changed);
-
- void distance_matrix_thread(DistanceMatrix& distance_matrix_computation, cv::Mat& distance_matrix,
- const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, AStarPlanner& path_planner);
-
- bool abort_computation_;
-
- //indicates how many generations shall be at least taken in order to optimize the given path
- int min_number_of_generations_;
-
- //indicates the amount of generations for which the path shouldn't have changed in order to stop the
- //optimization
- int const_generations_number_;
-
-public:
- //constructor
- GeneticTSPSolver(int min_number_of_gens=2300, int const_generations=100);
-
- void abortComputation();
-
- //Solving-algorithms for the given TSP. It returns a vector of int, which is the order from this solution. The int shows
- //the index in the Matrix. There are two functions for different cases:
- // 1. The distance matrix already exists
- // 2. The distance matrix has to be computet and maybe returned
-
- //with given distance matrix
- std::vector solveGeneticTSP(const cv::Mat& path_length_Matrix, const int start_Node);
-
-
- // compute distance matrix and maybe returning it
- // this version does not exclude infinite paths from the TSP ordering
- std::vector solveGeneticTSP(const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, const int start_Node, cv::Mat* distance_matrix=0);
-
- // compute TSP from a cleaned distance matrix (does not contain any infinity paths) that has to be computed
- std::vector solveGeneticTSPClean(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, const int start_node);
-
- // compute TSP with pre-computed cleaned distance matrix (does not contain any infinity paths)
- std::vector solveGeneticTSPWithCleanedDistanceMatrix(const cv::Mat& distance_matrix,
- const std::map& cleaned_index_to_original_index_mapping, const int start_node);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/maximal_clique_finder.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/maximal_clique_finder.h
deleted file mode 100644
index d1fcff3..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/maximal_clique_finder.h
+++ /dev/null
@@ -1,69 +0,0 @@
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-#include
-
-#include
-#include
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This algorithm provides a class that finds all maximal cliques in a given graph. It uses the Bron-Kerbosch Implementation
-//in Boost to do this. As input a symmetrical distance-Matrix is needed that shows the pathlenghts from one node to another.
-//If the path from one node to another doesn't exist, the entry in the matrix must be 0 or smaller. so the format for this
-//Matrix is:
-// row: node to start from, column: node to go to
-// --- ---
-// | 0.0 1.0 3.5 5.8 1.2 |
-// | 1.0 0.0 2.4 3.3 9.0 |
-// | 3.5 2.4 0.0 7.7 88.0|
-// | 5.8 3.3 7.7 0.0 0.0 |
-// | 1.2 9.0 88.0 0.0 0.0 |
-// --- ---
-//It also needs a maximal pathlength that shows the algorithm when the paths are too long and should not be included in the
-//Graph. This is neccessary because we assume that you can reach every node from the others and with a Graph in which all
-//nodes are connected the only maximal clique are the nodes itself. For example the previous matrix gets
-// maxval = 7.0
-// --- ---
-// | 0.0 1.0 3.5 5.8 1.2 |
-// | 1.0 0.0 2.4 3.3 0.0 |
-// | 3.5 2.4 0.0 0.0 0.0 |
-// | 5.8 3.3 0.0 0.0 0.0 |
-// | 1.2 0.0 0.0 0.0 0.0 |
-// --- ---
-//
-//The nodes in the graph are named after their position in the distance-Matrix and the cliques are
-// std::vector variables so you can easily acces the right nodes in the matrix outside this class.
-
-class cliqueFinder
-{
-protected:
- //function that allows to add a Vertex with a name to a boost::Graph. See boosts helper.hpp ( http://www.boost.org/doc/libs/1_47_0/libs/graph/example/helper.hpp ) for explanation
- template
- typename boost::graph_traits::vertex_descriptor addNamedVertex(Graph& g, NameMap nm, const std::string& name, VertexMap& vm);
-
- //function to create a graph out of the given distanceMatrix
- template
- void createGraph(Graph& graph, cv::Mat& distance_Matrix);
-
- //function to set too long paths in the distance_matrix to zero
- void cutTooLongEdges(cv::Mat& complete_distance_matrix, double maxval);
-
-public:
- cliqueFinder();
-
- std::vector > getCliques(const cv::Mat& distance_matrix, double maxval);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/nearest_neighbor_TSP.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/nearest_neighbor_TSP.h
deleted file mode 100644
index 45ff13a..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/nearest_neighbor_TSP.h
+++ /dev/null
@@ -1,69 +0,0 @@
-#include "ros/ros.h"
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This class provides a solution for the TSP by taking the nearest neighbor from the current Point as next Point.
-//It needs a symmetrical matrix of pathlenghts between the nodes and the starting-point index in this matrix.
-//If the path from one node to another doesn't exist or the path is from one node to itself, the entry in the matrix must
-//be 0 or smaller. so the format for this matrix is:
-// row: node to start from, column: node to go to
-// --- ---
-// | 0.0 1.0 3.5 5.8 1.2 |
-// | 1.0 0.0 2.4 3.3 9.0 |
-// | 3.5 2.4 0.0 7.7 88.0|
-// | 5.8 3.3 7.7 0.0 0.0 |
-// | 1.2 9.0 88.0 0.0 0.0 |
-// --- ---
-
-class NearestNeighborTSPSolver
-{
-protected:
-
- //Astar pathplanner to find the pathlengths from cv::Point to cv::Point
- AStarPlanner pathplanner_;
-
-// //Function to construct the distance matrix, showing the pathlength from node to node
-// void NearestNeighborTSPSolver::constructDistanceMatrix(cv::Mat& distance_matrix, const cv::Mat& original_map,
-// const std::vector& points, double downsampling_factor, double robot_radius, double map_resolution);
-
-public:
- //constructor
- NearestNeighborTSPSolver();
-
- //Solving-algorithms for the given TSP. It returns a vector of int, which is the order from this solution. The int shows
- //the index in the Matrix. There are two functions for different cases:
- // 1. The distance matrix already exists
- // 2. The distance matrix has to be computed and maybe returned
-
- //with given distance matrix
- std::vector solveNearestTSP(const cv::Mat& path_length_matrix, const int start_node); //with given distance matrix
-
- // compute TSP and distance matrix without cleaning it
- // this version does not exclude infinite paths from the TSP ordering
- std::vector solveNearestTSP(const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, const int start_node, cv::Mat* distance_matrix=0);
-
- // compute TSP from a cleaned distance matrix (does not contain any infinity paths) that has to be computed
- std::vector solveNearestTSPClean(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, const int start_node);
-
- // compute TSP with pre-computed cleaned distance matrix (does not contain any infinity paths)
- std::vector solveNearestTSPWithCleanedDistanceMatrix(const cv::Mat& distance_matrix,
- const std::map& cleaned_index_to_original_index_mapping, const int start_node);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/node.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/node.h
deleted file mode 100644
index 181b53b..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/node.h
+++ /dev/null
@@ -1,40 +0,0 @@
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-//This is th object to reperesent a node in a Graph. It is used by A_star_pathplanner.cpp and was applied from:
-// http://code.activestate.com/recipes/577457-a-star-shortest-path-algorithm/
-//In the estimate() function the distance from the node to the goal is calculated. Uncomment there which distance calculation
-//you want to use (Euclidean, Manhattan or Chebyshev). Euclidean is more precisly but could slow the planner a little bit on
-//long paths.
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-class NodeAstar
-{
-protected:
- // current position
- int xPos_;
- int yPos_;
- // total distance already travelled to reach the node
- int level_;
- // priority=level+remaining distance estimate
- int priority_; // smaller: higher priority
-
-public:
- NodeAstar(int xp, int yp, int d, int p);
- int getxPos() const;
- int getyPos() const;
- int getLevel() const;
- int getPriority() const;
- void updatePriority(const int& xDest, const int& yDest);
- void nextLevel(const int& i); // i: direction
- const int& estimate(const int& xDest, const int& yDest) const;
-
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/set_cover_solver.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/set_cover_solver.h
deleted file mode 100644
index aaf1ca3..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/set_cover_solver.h
+++ /dev/null
@@ -1,72 +0,0 @@
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-#include
-#include
-#include
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
-//regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This algorithm provides a class to solve the set-cover problem for given cliques. This is done by using the greedy-search
-//algorithm, which takes the clique with most unvisited nodes before the other nodes and removes the nodes in it from the
-//unvisited. It repeats this step until no more node hasn't been visited. It then merges cliques together that have at least
-//one node in common.
-//
-//!!!!!!!!!!!!!!!!Important!!!!!!!!!!!!!!!!!
-//Make sure that the cliques cover all nodes in the graph or else this algorithm runs into an endless loop. For best results
-//take the cliques from a maximal-clique finder like the Bron-Kerbosch algorithm.
-
-class SetCoverSolver
-{
-protected:
-
- //Astar pathplanner to find the pathlengths from cv::Point to cv::Point
- AStarPlanner pathplanner_;
-
- //This object finds all maximal cliques in the given Graph. It needs a symmetrical distance matrix shwoing the pathlength
- //from one node to another and a miximal pathlength to cut edges that are larger than this value. See maximal_clique_finder.h
- //for further information.
- cliqueFinder maximal_clique_finder;
-
- //function to merge groups together, which have at least one node in common
- std::vector > mergeGroups(const std::vector >& found_groups);
-
-// //Function to construct the distance matrix, showing the pathlength from node to node
-// void constructDistanceMatrix(cv::Mat& distance_matrix, const cv::Mat& original_map, const std::vector& points,
-// double downsampling_factor, double robot_radius, double map_resolution);
-
-public:
- //Constructor
- SetCoverSolver();
-
- //algorithms to solve the set cover problem. There are three functions for different cases:
- // 1. The cliques already have been found
- // 2. The distance matrix already exists
- // 3. The distance matrix has to be computed and may be returned
-
- //cliques are given
- std::vector > solveSetCover(std::vector >& given_cliques, const int number_of_nodes,
- const int max_number_of_clique_members, const cv::Mat& distance_matrix);
-
- //the distance matrix is given
- std::vector > solveSetCover(const cv::Mat& distance_matrix, const std::vector& points,
- const int number_of_nodes, double maximal_pathlength, const int max_number_of_clique_members);
-
- //the distance matrix has to be computed and may be returned
- std::vector > solveSetCover(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, double maximal_pathlength, const int max_number_of_clique_members, cv::Mat* distance_matrix=0);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/timer.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/timer.h
deleted file mode 100644
index 552d5f5..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/timer.h
+++ /dev/null
@@ -1,183 +0,0 @@
-/*
- * timer.h
- *
- * Created on: May 13, 2013
- * Author: rmb-ce
- */
-
-// from: http://snipplr.com/view/40650/timer-class-for-both-unixlinuxmac-and-windows-system/
-
-//////////////////
-// How to Use ////
-//////////////////
-
-//#include
-//#include "timer.h"
-//using namespace std;
-
-//int main()
-//{
-// Timer timer;
-//
-// // start timer
-// timer.start();
-//
-// // do something
-// ...
-//
-// // stop timer
-// timer.stop();
-//
-// // print the elapsed time in millisec
-// cout << timer.getElapsedTimeInMilliSec() << " ms.\n";
-//
-// return 0;
-//}
-
-
-//////////////////////////////////////////////////////////////////////////////
-// Timer.h
-// =======
-// High Resolution Timer.
-// This timer is able to measure the elapsed time with 1 micro-second accuracy
-// in both Windows, Linux and Unix system
-//
-// AUTHOR: Song Ho Ahn (song.ahn@gmail.com)
-// CREATED: 2003-01-13
-// UPDATED: 2006-01-13
-//
-// Copyright (c) 2003 Song Ho Ahn
-//////////////////////////////////////////////////////////////////////////////
-
-#ifndef TIMER_H_DEF
-#define TIMER_H_DEF
-
-#ifdef WIN32 // Windows system specific
-//#include
-#else // Unix based system specific
-#include
-#endif
-
-#include
-
-
-class Timer
-{
-public:
-// default constructor
- Timer()
- {
-#ifdef WIN32
- QueryPerformanceFrequency(&frequency);
- startCount.QuadPart = 0;
- endCount.QuadPart = 0;
-#else
- startCount.tv_sec = startCount.tv_usec = 0;
- endCount.tv_sec = endCount.tv_usec = 0;
-#endif
-
- stopped = 0;
- startTimeInMicroSec = 0;
- endTimeInMicroSec = 0;
-
- start();
- }
-
- // default destructor
- ~Timer()
- {
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // start timer.
- // startCount will be set at this point.
- ///////////////////////////////////////////////////////////////////////////////
- void start()
- {
- stopped = 0; // reset stop flag
-#ifdef WIN32
- QueryPerformanceCounter(&startCount);
-#else
- gettimeofday(&startCount, NULL);
-#endif
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // stop the timer.
- // endCount will be set at this point.
- ///////////////////////////////////////////////////////////////////////////////
- void stop()
- {
- stopped = 1; // set timer stopped flag
-
-#ifdef WIN32
- QueryPerformanceCounter(&endCount);
-#else
- gettimeofday(&endCount, NULL);
-#endif
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // same as getElapsedTimeInSec()
- ///////////////////////////////////////////////////////////////////////////////
- double getElapsedTime()
- {
- return this->getElapsedTimeInSec();
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // divide elapsedTimeInMicroSec by 1000000
- ///////////////////////////////////////////////////////////////////////////////
- double getElapsedTimeInSec()
- {
- return this->getElapsedTimeInMicroSec() * 0.000001;
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // divide elapsedTimeInMicroSec by 1000
- ///////////////////////////////////////////////////////////////////////////////
- double getElapsedTimeInMilliSec()
- {
- return this->getElapsedTimeInMicroSec() * 0.001;
- }
-
- ///////////////////////////////////////////////////////////////////////////////
- // compute elapsed time in micro-second resolution.
- // other getElapsedTime will call this first, then convert to correspond resolution.
- ///////////////////////////////////////////////////////////////////////////////
- double getElapsedTimeInMicroSec()
- {
-#ifdef WIN32
- if(!stopped)
- QueryPerformanceCounter(&endCount);
-
- startTimeInMicroSec = startCount.QuadPart * (1000000.0 / frequency.QuadPart);
- endTimeInMicroSec = endCount.QuadPart * (1000000.0 / frequency.QuadPart);
-#else
- if (!stopped)
- gettimeofday(&endCount, NULL);
-
- startTimeInMicroSec = (startCount.tv_sec * 1000000.0) + startCount.tv_usec;
- endTimeInMicroSec = (endCount.tv_sec * 1000000.0) + endCount.tv_usec;
-#endif
-
- return endTimeInMicroSec - startTimeInMicroSec;
- }
-
-protected:
-
-private:
- double startTimeInMicroSec; // starting time in micro-second
- double endTimeInMicroSec; // ending time in micro-second
- int stopped; // stop flag
-#ifdef WIN32
- LARGE_INTEGER frequency; // ticks per second
- LARGE_INTEGER startCount;//
- LARGE_INTEGER endCount;//
-#else
- timeval startCount; //
- timeval endCount; //
-#endif
-};
-
-#endif // TIMER_H_DEF
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/trolley_position_finder.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/trolley_position_finder.h
deleted file mode 100644
index 2ab9f91..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/trolley_position_finder.h
+++ /dev/null
@@ -1,58 +0,0 @@
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-#include
-
-#include
-
-#pragma once //make sure this header gets included only one time when multiple classes need it in the same project
- //regarding to https://en.wikipedia.org/wiki/Pragma_once this is more efficient than #define
-
-//This object provides an algorithm to search for the best trolley position for a group of points. A trolley position is
-//the Point where the trolley of a robot should be placed during the cleaning of the group. This is done by searching in the
-//bounding box of these points for the point which minimizes the pathlength to every group member. If the goup has only two
-//members the algorithm chooses a Point on the optimal path between these two Points that is in the middlest of this path.
-//This algorithm needs as input:
-// 1. The original occupancy gridmap to get the pathlength between two Points.
-// 2. A vector of found groups. This vector stores the group as integer that show the Position of the node in the
-// roomcenters vector. To find the groups it is good to find all maximal cliques in the graph and then applying
-// a set Cover solver on these.
-// 3. A vector of roomcenters that stores the centers of each room. This algorithm was implemented for planning
-// the order of cleaning rooms so this variable is called room_centers, but it can store every cv::Point with that
-// you want to find the best trolley position.
-// 4. A downsampling factor to reduce the size of the map. This is used by the A_star_pathplanner to heavily reduce
-// calculationtime. It has to be (0, 1]. If it is 1 the map will be took as it is.
-// 5. The Radius of the robot and the map resolution to make sure the A_star pathplanner stays in enough distance to the
-// walls and obstacles. (See A_star_pathplanner.cpp for further information)
-
-class TrolleyPositionFinder
-{
-protected:
-
- AStarPlanner path_planner_; //Object to plan a path from Point A to Point B in a given gridmap
-
- //Function to find a trolley position for one group
- cv::Point findOneTrolleyPosition(const std::vector group_points, const cv::Mat& original_map,
- const double downsampling_factor, const double robot_radius, const double map_resolution);
-
-public:
-
- //constructor
- TrolleyPositionFinder();
-
- //Function to find a trolley position for each group by using the findOneTrolleyPosition function
- std::vector findTrolleyPositions(const cv::Mat& original_map, const std::vector >& found_groups,
- const std::vector& room_centers, const double downsampling_factor, const double robot_radius,
- const double map_resolution);
-};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solver_defines.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solver_defines.h
deleted file mode 100644
index 4ce6a45..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solver_defines.h
+++ /dev/null
@@ -1,63 +0,0 @@
-/*!
- *****************************************************************
- * \file
- *
- * \note
- * Copyright (c) 2017 \n
- * Fraunhofer Institute for Manufacturing Engineering
- * and Automation (IPA) \n\n
- *
- *****************************************************************
- *
- * \note
- * Project name: Care-O-bot
- * \note
- * ROS stack name: autopnp
- * \note
- * ROS package name: ipa_building_navigation
- *
- * \author
- * Author: Richard Bormann
- * \author
- * Supervised by: Richard Bormann
- *
- * \date Date of creation: 03.2017
- *
- * \brief
- *
- *
- *****************************************************************
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer. \n
- * - Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution. \n
- * - Neither the name of the Fraunhofer Institute for Manufacturing
- * Engineering and Automation (IPA) nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission. \n
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License LGPL as
- * published by the Free Software Foundation, either version 3 of the
- * License, or (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU Lesser General Public License LGPL for more details.
- *
- * You should have received a copy of the GNU Lesser General Public
- * License LGPL along with this program.
- * If not, see .
- *
- ****************************************************************/
-
-#pragma once
-
-
-enum TSPSolvers {TSP_NEAREST_NEIGHBOR=1, TSP_GENETIC=2, TSP_CONCORDE=3};
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solvers.h b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solvers.h
deleted file mode 100644
index 5bc5d1b..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/include/ipa_building_navigation/tsp_solvers.h
+++ /dev/null
@@ -1,67 +0,0 @@
-/*!
- *****************************************************************
- * \file
- *
- * \note
- * Copyright (c) 2017 \n
- * Fraunhofer Institute for Manufacturing Engineering
- * and Automation (IPA) \n\n
- *
- *****************************************************************
- *
- * \note
- * Project name: Care-O-bot
- * \note
- * ROS stack name: autopnp
- * \note
- * ROS package name: ipa_building_navigation
- *
- * \author
- * Author: Richard Bormann
- * \author
- * Supervised by: Richard Bormann
- *
- * \date Date of creation: 03.2017
- *
- * \brief
- *
- *
- *****************************************************************
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer. \n
- * - Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution. \n
- * - Neither the name of the Fraunhofer Institute for Manufacturing
- * Engineering and Automation (IPA) nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission. \n
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License LGPL as
- * published by the Free Software Foundation, either version 3 of the
- * License, or (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU Lesser General Public License LGPL for more details.
- *
- * You should have received a copy of the GNU Lesser General Public
- * License LGPL along with this program.
- * If not, see .
- *
- ****************************************************************/
-
-#pragma once
-
-#include
-
-
-#include
-#include
-#include
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/A_star_pathplanner.cpp b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/A_star_pathplanner.cpp
deleted file mode 100644
index 067c2a4..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/A_star_pathplanner.cpp
+++ /dev/null
@@ -1,383 +0,0 @@
-#include
-
-#include
-
-const int dir = 8; // number of possible directions to go at any position
-// if dir==4
-//static int dx[dir]={1, 0, -1, 0};
-//static int dy[dir]={0, 1, 0, -1};
-// if dir==8
-static int dx[dir] =
-{ 1, 1, 0, -1, -1, -1, 0, 1 };
-static int dy[dir] =
-{ 0, 1, 1, 1, 0, -1, -1, -1 };
-
-static int expanding_counter = 0;
-
-// Determine priority (in the priority queue)
-bool operator<(const NodeAstar& a, const NodeAstar& b)
-{
- return a.getPriority() > b.getPriority();
-}
-
-AStarPlanner::AStarPlanner()
-{
- n = 1;
- m = 1;
-}
-
-void AStarPlanner::drawRoute(cv::Mat& map, const cv::Point start_point, const std::string& route, double step_length)
-{
- // follow the route on the map and update the path length
- if (route.length() > 0)
- {
- int j;
- char c;
- int x1 = start_point.x;
- int y1 = start_point.y;
- int x2,y2;
- for (int i = 0; i < route.length(); i++)
- {
- //get the next char of the string and make it an integer, which shows the direction
- c = route.at(i);
- j=c-'0';
- x2 = x1 + dx[j]*step_length;
- y2 = y1 + dy[j]*step_length;
- const double progress = 0.2 + 0.6*(double)i/(double)route.length();
- cv::line(map, cv::Point(x1,y1), cv::Point(x2,y2), CV_RGB(0,progress*255,0), 1);
- x1 = x2;
- y1 = y2;
- }
- }
-}
-
-void AStarPlanner::getRoute(const cv::Point start_point, const std::string& route,
- double step_length, std::vector& route_points)
-{
- // follow the route on the map and update the path length
- if (route.length() > 0)
- {
- int j;
- char c;
- int x1 = start_point.x;
- int y1 = start_point.y;
- route_points.push_back(cv::Point(x1, y1));
- int x2,y2;
- for (int i = 0; i < route.length(); i++)
- {
- //get the next char of the string and make it an integer, which shows the direction
- c = route.at(i);
- j=c-'0';
- x2 = x1 + dx[j]*step_length;
- y2 = y1 + dy[j]*step_length;
- route_points.push_back(cv::Point(x2, y2));
- x1 = x2;
- y1 = y2;
- }
- }
-}
-
-void AStarPlanner::downsampleMap(const cv::Mat& map, cv::Mat& downsampled_map, const double downsampling_factor, const double robot_radius, const double map_resolution)
-{
- //erode the map so the planner doesn't go near the walls
- // --> calculate the number of times for eroding from Robot Radius [m]
- cv::Mat eroded_map;
- int number_of_erosions = (robot_radius / map_resolution);
- cv::erode(map, eroded_map, cv::Mat(), cv::Point(-1, -1), number_of_erosions);
- //downsampling of the map to reduce calculation time
- if (downsampling_factor != 1.)
- cv::resize(eroded_map, downsampled_map, cv::Size(0, 0), downsampling_factor, downsampling_factor, cv::INTER_NEAREST);//_LINEAR);
- else
- downsampled_map = eroded_map;
-}
-
-// A-star algorithm.
-// The route returned is a string of direction digits.
-std::string AStarPlanner::pathFind(const int & xStart, const int & yStart, const int & xFinish, const int & yFinish, const cv::Mat& map)
-{
- static std::priority_queue pq[2]; // list of open (not-yet-tried) nodes
- static int pqi; // pq index
- static NodeAstar* n0;
- static NodeAstar* m0;
- static int i, j, x, y, xdx, ydy;
- static char c;
- pqi = 0;
-
- cv::Mat map_to_calculate_path(cv::Size(m, n), CV_32S);
-
- // create map from the given eroded map
- for (int y = 0; y < map.rows; y++)
- {
- for (int x = 0; x < map.cols; x++)
- {
- if (map.at(y, x) == 255)
- {
- map_to_calculate_path.at(x, y) = 0;
- }
- else
- {
- map_to_calculate_path.at(x, y) = 1;
- }
- }
- }
-
- cv::Mat closed_nodes_map(cv::Size(m, n), CV_32S); //map of already tried nodes
- cv::Mat open_nodes_map(cv::Size(m, n), CV_32S); // map of open (not-yet-tried) nodes
- cv::Mat dir_map(cv::Size(m, n), CV_32S); // map of directions
-
- // initialize the node maps
- for (y = 0; y < closed_nodes_map.rows; y++)
- {
- for (x = 0; x < closed_nodes_map.cols; x++)
- {
- closed_nodes_map.at(y, x) = 0;
- open_nodes_map.at(y, x) = 0;
- }
- }
-
- // create the start node and push into list of open nodes
- n0 = new NodeAstar(xStart, yStart, 0, 0);
- n0->updatePriority(xFinish, yFinish);
- pq[pqi].push(*n0);
- open_nodes_map.at(xStart, yStart) = n0->getPriority(); // mark it on the open nodes map
-
- //garbage collection
- delete n0;
-
- // A* search
- while (!pq[pqi].empty())
- {
- // get the current node w/ the highest priority
- // from the list of open nodes
- n0 = new NodeAstar(pq[pqi].top().getxPos(), pq[pqi].top().getyPos(), pq[pqi].top().getLevel(), pq[pqi].top().getPriority());
-
- x = n0->getxPos();
- y = n0->getyPos();
-
- pq[pqi].pop(); // remove the node from the open list
- open_nodes_map.at(x, y) = 0;
- // mark it on the closed nodes map
- closed_nodes_map.at(x, y) = 1;
-
- // quit searching when the goal state is reached
- //if((*n0).estimate(xFinish, yFinish) == 0)
- if (x == xFinish && y == yFinish)
- {
- // generate the path from finish to start
- // by following the directions
- std::string path = "";
- while (!(x == xStart && y == yStart))
- {
- j = dir_map.at(x, y);
- c = '0' + (j + dir / 2) % dir;
- path = c + path;
- x += dx[j];
- y += dy[j];
- }
-
- delete n0;// garbage collection
- // empty the leftover nodes
- while (!pq[pqi].empty())
- pq[pqi].pop();
- return path;
- }
-
- // generate moves (child nodes) in all possible directions
- for (i = 0; i < dir; i++)
- {
- xdx = x + dx[i];
- ydy = y + dy[i];
-
- expanding_counter++;
-
- if (!(xdx < 0 || xdx > n - 1 || ydy < 0 || ydy > m - 1 || map_to_calculate_path.at(xdx, ydy) == 1 || closed_nodes_map.at(xdx, ydy) == 1))
- {
- // generate a child node
- m0 = new NodeAstar(xdx, ydy, n0->getLevel(), n0->getPriority());
- m0->nextLevel(i);
- m0->updatePriority(xFinish, yFinish);
-
- // if it is not in the open list then add into that
- if (open_nodes_map.at(xdx, ydy) == 0)
- {
- open_nodes_map.at(xdx, ydy) = m0->getPriority();
- pq[pqi].push(*m0);
- // mark its parent node direction
- dir_map.at(xdx, ydy) = (i + dir / 2) % dir;
- }
- else if (open_nodes_map.at(xdx, ydy) > m0->getPriority())
- {
- // update the priority info
- open_nodes_map.at(xdx, ydy) = m0->getPriority();
- // update the parent direction info
- dir_map.at(xdx, ydy) = (i + dir / 2) % dir;
-
- // replace the node
- // by emptying one pq to the other one
- // except the node to be replaced will be ignored
- // and the new node will be pushed in instead
- while (!(pq[pqi].top().getxPos() == xdx && pq[pqi].top().getyPos() == ydy))
- {
- pq[1 - pqi].push(pq[pqi].top());
- pq[pqi].pop();
- }
- pq[pqi].pop(); // remove the wanted node
-
- // empty the larger size pq to the smaller one
- if (pq[pqi].size() > pq[1 - pqi].size())
- pqi = 1 - pqi;
- while (!pq[pqi].empty())
- {
- pq[1 - pqi].push(pq[pqi].top());
- pq[pqi].pop();
- }
- pqi = 1 - pqi;
- pq[pqi].push(*m0); // add the better node instead
- }
- delete m0; // garbage collection
- }
- }
- delete n0; // garbage collection
- }
- return ""; // no route found
-}
-
-//This is the path planning algorithm for this class. It downsamples the map with the given factor (0 < factor < 1) so the
-//map gets reduced and calculation time gets better. If it is set to 1 the map will have original size, if it is 0 the algorithm
-//won't work, so make sure to not set it to 0. The algorithm also needs the Robot radius [m] and the map resolution [m²/pixel] to
-//calculate the needed amount of erosions to include the radius in the planning.
-double AStarPlanner::planPath(const cv::Mat& map, const cv::Point& start_point, const cv::Point& end_point,
- const double downsampling_factor, const double robot_radius, const double map_resolution,
- const int end_point_valid_neighborhood_radius, std::vector* route)
-{
- expanding_counter = 0;
- double step_length = 1./downsampling_factor;
-
- //length of the planned path
- double path_length = 0;
-
- if(start_point.x == end_point.x && start_point.y == end_point.y)//if the start and end-point are the same return 0
- {
- return path_length;
- }
-
- // check for valid coordinates of start and end points
- if (start_point.x < 0 || start_point.x >= map.cols || start_point.y < 0 || start_point.y >= map.rows ||
- end_point.x < 0 || end_point.x >= map.cols || end_point.y < 0 || end_point.y >= map.rows)
- {
- return 1e100;
- }
-
- cv::Mat downsampled_map;
- downsampleMap(map, downsampled_map, downsampling_factor, robot_radius, map_resolution);
-
- //transform the Pixel values to the downsampled ones
- int start_x = downsampling_factor * start_point.x;
- int start_y = downsampling_factor * start_point.y;
- int end_x = downsampling_factor * end_point.x;
- int end_y = downsampling_factor * end_point.y;
-
- //set the sizes of the map
- m = downsampled_map.rows;// horizontal size of the map
- n = downsampled_map.cols;// vertical size size of the map
-
- // get the route
-// clock_t start = clock();
- route_ = pathFind(start_x, start_y, end_x, end_y, downsampled_map);
- if (route_ == "")
- {
- if (end_point_valid_neighborhood_radius > 0)
- {
- for (int r=1; r<=end_point_valid_neighborhood_radius; ++r)
- {
- for (int dy=-r; dy<=r; ++dy)
- {
- for (int dx=-r; dx<=r; ++dx)
- {
- if ((abs(dy)!=r && abs(dx)!=r) || end_x+dx<0 || end_x+dx>=n || end_y+dy<0 || end_y+dy>=m)
- continue;
- route_ = pathFind(start_x, start_y, end_x+dx, end_y+dy, downsampled_map);
- if (route_ != "")
- break;
- }
- if (route_ != "")
- break;
- }
- if (route_ != "")
- break;
- }
- }
- if (route_ == "")
- {
-// std::cout << "No path from " << start_point << " to " << end_point << " found for map of size " << map.rows << "x" << map.cols << " and downsampling factor " << downsampling_factor << std::endl;
- return 1e100; //return extremely large distance as path length if the rout could not be generated
- }
- }
-// clock_t end = clock();
-// double time_elapsed = double(end - start);
-
- // follow the route on the map and update the path length
- if (route_.length() > 0)
- {
- int j;
- char c;
- int x = start_x;
- int y = start_y;
- const double straight_step = (1. / downsampling_factor);
- const double diagonal_step = (std::sqrt(2.) / downsampling_factor);
- for (int i = 0; i < route_.length(); i++)
- {
- //get the next char of the string and make it an integer, which shows the direction
- c = route_.at(i);
- j=c-'0';
- x = x + dx[j];
- y = y + dy[j];
- //Update the pathlength with the directions of the path. When the path goes vertical or horizontal add length 1.
- //When it goes diagonal add sqrt(2)
- if (j == 0 || j == 2 || j == 4 || j == 6)
- {
- path_length += straight_step;
- }
- if (j == 1 || j == 3 || j == 5 || j == 7)
- {
- path_length += diagonal_step;
- }
- }
- }
-
- if(route != NULL)
- getRoute(start_point, route_, step_length, *route);
-
- return path_length;
-}
-
-
-double AStarPlanner::planPath(const cv::Mat& map, const cv::Mat& downsampled_map, const cv::Point& start_point, const cv::Point& end_point, const double downsampling_factor,
- const double robot_radius, const double map_resolution, const int end_point_valid_neighborhood_radius, cv::Mat* draw_path_map,
- std::vector* route)
-{
- route_ = "";
- double step_length = 1./downsampling_factor;
-// cv::Mat debug = map.clone();
-// cv::circle(debug, start_point, 2, cv::Scalar(127), CV_FILLED);
-// cv::circle(debug, end_point, 2, cv::Scalar(127), CV_FILLED);
-// cv::imshow("debug", debug);
-// cv::waitKey();
- double pathlength = step_length * planPath(downsampled_map, downsampling_factor*start_point, downsampling_factor*end_point, 1., 0., map_resolution, end_point_valid_neighborhood_radius, route);
- if(pathlength > 1e90) //if no path can be found try with the original map
- {
- pathlength = planPath(map, start_point, end_point, 1., 0., map_resolution, 1./downsampling_factor * end_point_valid_neighborhood_radius, route);
- step_length = 1.;
- }
- if(pathlength > 1e90)
- std::cout << "######################### No path found on the originally sized map #######################" << std::endl;
- else
- {
- if (draw_path_map!=NULL)
- {
- drawRoute(*draw_path_map, start_point, route_, step_length);
- }
- }
-
- return pathlength;
-}
diff --git a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/concorde_TSP.cpp b/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/concorde_TSP.cpp
deleted file mode 100644
index 711d718..0000000
--- a/Code/MowingRobot/PIBot_ROS/ros_ws/src/ipa_coverage_planning/ipa_building_navigation/common/src/concorde_TSP.cpp
+++ /dev/null
@@ -1,317 +0,0 @@
-# include
-
-#include
-#include
-#include
-
-//Default constructor
-ConcordeTSPSolver::ConcordeTSPSolver()
-: abort_computation_(false)
-{
-
-}
-
-void ConcordeTSPSolver::distance_matrix_thread(DistanceMatrix& distance_matrix_computation, cv::Mat& distance_matrix,
- const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, AStarPlanner& path_planner)
-{
- distance_matrix_computation.constructDistanceMatrix(distance_matrix, original_map, points, downsampling_factor,
- robot_radius, map_resolution, pathplanner_);
-}
-
-void ConcordeTSPSolver::abortComputation()
-{
- abort_computation_ = true;
-
- // kill concorde if running
- const std::string pid_filename = "concorde_tsp_pid" + unique_file_identifier_ + ".txt";
- std::string pid_cmd = "pidof concorde > " + pid_filename;
- int pid_result = system(pid_cmd.c_str());
- std::ifstream pid_reader(pid_filename.c_str());
- int value = -1;
- std::string line;
- if (pid_reader.is_open())
- {
- while (getline(pid_reader, line))
- {
- std::istringstream iss(line);
- while (iss >> value)
- {
- std::cout << "PID of concorde: " << value << std::endl;
- std::stringstream ss;
- ss << "kill " << value;
- std::string kill_cmd = ss.str();
- int kill_result = system(kill_cmd.c_str());
- std::cout << "kill result: " << kill_result << std::endl;
- }
- }
- pid_reader.close();
- remove(pid_filename.c_str());
- }
-}
-
-//This function generates a file with the current TSP in TSPlib format. This is necessary because concorde needs this file
-//as input to solve the TSP. See http://comopt.ifi.uni-heidelberg.de/software/TSPLIB95/ for documentation.
-void ConcordeTSPSolver::writeToFile(const cv::Mat& pathlength_matrix, const std::string& tsp_lib_filename, const std::string& tsp_order_filename)
-{
- const std::string path_for_saving_file = tsp_lib_filename; //ros::package::getPath("libconcorde_tsp_solver") + "/common/files/TSPlib_file.txt";
- std::ofstream saving_file(path_for_saving_file.c_str());
- if (saving_file.is_open())
- {
- std::cout << "Starting to create the TSPlib file: " << path_for_saving_file << std::endl;
- //specify name of the Problem, Type (TSP = symmetrical TSP) and add a comment to the file. Name and Type are necessary, comment is for better understanding when you open the file.
- saving_file << "NAME: ipa-building-navigation_" << tsp_lib_filename << std::endl
- << "TYPE: TSP" << std::endl
- << "COMMENT: This is the TSPlib file for using concorde. See http://comopt.ifi.uni-heidelberg.de/software/TSPLIB95/ for documentation."
- << std::endl;
- saving_file << "DIMENSION: " << pathlength_matrix.cols << std::endl; //Shows the Dimension of the problem --> the number of nodes (Necessary).
- //Write the distance-matrix into the file as a full-matrix.
- saving_file << "EDGE_WEIGHT_TYPE: EXPLICIT" << std::endl;
- saving_file << "EDGE_WEIGHT_FORMAT: FULL_MATRIX" << std::endl;
- saving_file << "EDGE_WEIGHT_SECTION" << std::endl;
-
- for (int row = 0; row < pathlength_matrix.rows; row++)
- {
- for (int col = 0; col < pathlength_matrix.cols; col++)
- {
- saving_file << " "
- << (int) pathlength_matrix.at(row, col);
- }
- saving_file << std::endl;
- }
- //shows the end of the file
- saving_file << "EOF";
-
- std::cout << "Created the TSPlib file." << std::endl;
- saving_file.close();
- }
- else
- {
- std::cout << "Saving file '" << path_for_saving_file << "' for concorde could not be opened." << std::endl;
- }
-
- // clear results file
- std::ofstream reading_file(tsp_order_filename.c_str()); //open file
- if (reading_file.is_open())
- {
- reading_file << "";
- reading_file.close();
- }
- else
- {
- std::cout << "Could not clear results file '" << tsp_order_filename << "'." << std::endl;
- }
-}
-
-//This function opens the file which saves the output from the concorde solver and reads the saved order. The names of the
-//nodes in the graph are stored as positions in the distance matrix in this case. The first integer in the file is the number
-//of nodes of this problem, so this one is not necessary.
-std::vector ConcordeTSPSolver::readFromFile(const std::string& tsp_order_filename)
-{
- std::string path_for_order_file = tsp_order_filename; //ros::package::getPath("libconcorde_tsp_solver") + "/common/files/TSP_order.txt"; //get path to file
- std::ifstream reading_file(path_for_order_file.c_str()); //open file
-
- std::vector order_vector; //vector that stores the calculated TSP order
-
- std::string line; //current line of the file
-
- int value; //current node in the line
-
- int line_counter = 0; //variable to make sure that the first line isn't stored
-
- if (reading_file.is_open())
- {
- //get new line in the file
- while (getline(reading_file, line))
- {
- std::istringstream iss(line);
- while (iss >> value)
- {
- if (line_counter > 0) //first line shows the number of nodes and is not relevant
- order_vector.push_back(value); //put the current node in the last position of the order
- line_counter++;
- }
- }
- reading_file.close();
- }
- else
- {
- std::cout << "TSP order file '" << path_for_order_file << "' could not be opened." << std::endl;
- }
- return order_vector;
-}
-
-//This function solves the given TSP using the systemcall to use the concorde TSP solver. This solver is applied from:
-// http://www.math.uwaterloo.ca/tsp/concorde.html
-//First you have to build the Solver in any possible way and if you don't make a ros-package out of it you have to change
-//the paths to the right ones. If it is a ros-package the ros::package::getpath() function will find the right path.
-//The usage of the solver is: ./concorde [-see below-] [dat_file]
-//Navigate to the build Solver and then ./TSP and type ./concorde -h for a short explanation.
-
-//with a given distance matrix
-std::vector ConcordeTSPSolver::solveConcordeTSP(const cv::Mat& path_length_matrix, const int start_Node)
-{
- // generate a unique filename
- timeval time;
- gettimeofday(&time, NULL);
- std::stringstream ss;
- ss << "_" << time.tv_sec << "_" << time.tv_usec;
- unique_file_identifier_ = ss.str();
- const std::string tsp_lib_filename = "TSPlib_file" + unique_file_identifier_ + ".txt";
- const std::string tsp_order_filename = "TSP_order" + unique_file_identifier_ + ".txt";
-
- std::vector unsorted_order, sorted_order;
- std::cout << "finding optimal order" << std::endl;
- std::cout << "number of nodes: " << path_length_matrix.rows << " start node: " << start_Node << std::endl;
- if (path_length_matrix.rows > 2) //check if the TSP has at least 3 nodes
- {
- //create the TSPlib file
- writeToFile(path_length_matrix, tsp_lib_filename, tsp_order_filename);
-
- //use concorde to find optimal tour
- std::string bin_folder;
- while (bin_folder.length()==0)
- {
- const std::string temp_file = "temp_libconcorde_path" + unique_file_identifier_ + ".txt";
- try
- {
- std::string cmd = "rospack libs-only-L libconcorde_tsp_solver > " + temp_file;
- int result = system(cmd.c_str());
- std::ifstream file(temp_file.c_str(), std::ifstream::in);
- if (file.is_open())
- {
- file >> bin_folder;
- file.close();
- }
- std::cout << "bin_folder: " << bin_folder << std::endl;
- remove(temp_file.c_str());
- //bin_folder = ros::package::command("libs-only-L libconcorde_tsp_solver"); // this command crashes sometimes
- //bin_folder.erase(std::remove(bin_folder.begin(), bin_folder.end(), '\n'));
- }
- catch (...)
- {
- std::cout << "ConcordeTSPSolver::solveConcordeTSP: ERROR: ['rospack libs-only-L libconcorde_tsp_solver > '" << temp_file << "] failed. Trying again." << std::endl;
- }
- }
- std::string cmd = bin_folder + "/libconcorde_tsp_solver/concorde -o " + "$HOME/.ros/" + tsp_order_filename + " $HOME/.ros/" + tsp_lib_filename;
- if (abort_computation_==true)
- return sorted_order;
- int result = system(cmd.c_str());
- if (abort_computation_==true)
- return sorted_order;
- assert(!result);
-
- //get order from saving file
- unsorted_order = readFromFile(tsp_order_filename);
- }
- else
- {
- for(int node = 0; node < path_length_matrix.rows; node++)
- {
- unsorted_order.push_back(node);
- }
- }
- // cleanup files
- remove(tsp_lib_filename.c_str());
- remove(tsp_order_filename.c_str());
- const std::string tsp_lib_sol_filename = "TSPlib_file" + unique_file_identifier_ + ".sol";
- remove(tsp_lib_sol_filename.c_str());
- const std::string tsp_lib_res_filename = "TSPlib_file" + unique_file_identifier_ + ".res";
- remove(tsp_lib_res_filename.c_str());
- std::cout << "finished TSP" << std::endl;
-
- // if there is an error, just set unsorted order to 1, 2, 3, ...
- if (unsorted_order.size() != path_length_matrix.rows)
- {
- std::cout << "ConcordeTSPSolver::solveConcordeTSP: Warning: Optimized order invalid, taking standard order 1, 2, 3, ..." << std::endl;
- unsorted_order.clear();
- unsorted_order.resize(path_length_matrix.rows);
- for (int i=0; i ConcordeTSPSolver::solveConcordeTSP(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, const int start_Node, cv::Mat* distance_matrix)
-{
- //calculate the distance matrix
- std::cout << "ConcordeTSPSolver::solveConcordeTSP: Constructing distance matrix..." << std::endl;
- cv::Mat distance_matrix_ref;
- if (distance_matrix != 0)
- distance_matrix_ref = *distance_matrix;
- DistanceMatrix distance_matrix_computation;
- boost::thread t(boost::bind(&ConcordeTSPSolver::distance_matrix_thread, this, boost::ref(distance_matrix_computation),
- boost::ref(distance_matrix_ref), boost::cref(original_map), boost::cref(points), downsampling_factor,
- robot_radius, map_resolution, boost::ref(pathplanner_)));
- bool finished = false;
- while (finished==false)
- {
- if (abort_computation_==true)
- distance_matrix_computation.abortComputation();
- finished = t.try_join_for(boost::chrono::milliseconds(10));
- }
-
-// distance_matrix_computation.constructDistanceMatrix(distance_matrix_ref, original_map, points, downsampling_factor,
-// robot_radius, map_resolution, pathplanner_);
-
- if (abort_computation_==true)
- {
- std::vector sorted_order;
- return sorted_order;
- }
-
- return (solveConcordeTSP(distance_matrix_ref, start_Node));
-}
-
-// compute TSP from a cleaned distance matrix (does not contain any infinity paths) that has to be computed
-std::vector ConcordeTSPSolver::solveConcordeTSPClean(const cv::Mat& original_map, const std::vector& points,
- double downsampling_factor, double robot_radius, double map_resolution, const int start_node)
-{
- // compute a cleaned distance matrix
- cv::Mat distance_matrix_cleaned;
- std::map cleaned_index_to_original_index_mapping; // maps the indices of the cleaned distance_matrix to the original indices of the original distance_matrix
- int new_start_node = start_node;
- DistanceMatrix distance_matrix_computation;
- distance_matrix_computation.computeCleanedDistanceMatrix(original_map, points, downsampling_factor, robot_radius, map_resolution, pathplanner_,
- distance_matrix_cleaned, cleaned_index_to_original_index_mapping, new_start_node);
-
- // solve TSP and re-index points to original indices
- return solveConcordeTSPWithCleanedDistanceMatrix(distance_matrix_cleaned, cleaned_index_to_original_index_mapping, new_start_node);
-}
-
-
-// compute TSP with pre-computed cleaned distance matrix (does not contain any infinity paths)
-std::vector ConcordeTSPSolver::solveConcordeTSPWithCleanedDistanceMatrix(const cv::Mat& distance_matrix,
- const std::map& cleaned_index_to_original_index_mapping, const int start_node)
-{
- // solve TSP and re-index points to original indices
- std::vector optimal_order = solveConcordeTSP(distance_matrix, start_node);
- for (size_t i=0; i
-
-#include
-#include
-
-//Default constructor
-GeneticTSPSolver::GeneticTSPSolver(int min_number_of_gens, int const_generations)
-: abort_computation_(false)
-{
- min_number_of_generations_ = min_number_of_gens;
- const_generations_number_ = const_generations;
-}
-
-void GeneticTSPSolver::distance_matrix_thread(DistanceMatrix& distance_matrix_computation, cv::Mat& distance_matrix,
- const cv::Mat& original_map, const std::vector& points, double downsampling_factor,
- double robot_radius, double map_resolution, AStarPlanner& path_planner)
-{
- distance_matrix_computation.constructDistanceMatrix(distance_matrix, original_map, points, downsampling_factor,
- robot_radius, map_resolution, pathplanner_);
-}
-
-void GeneticTSPSolver::abortComputation()
-{
- abort_computation_ = true;
-}
-
-////Function to construct the distance matrix from the given points. See the definition at solveGeneticTSP for the style of this matrix.
-//void GeneticTSPSolver::constructDistanceMatrix(cv::Mat& distance_matrix, const cv::Mat& original_map, const int number_of_nodes,
-// const std::vector& points, double downsampling_factor, double robot_radius, double map_resolution)
-//{
-// //create the distance matrix with the right size
-// cv::Mat pathlengths(cv::Size(number_of_nodes, number_of_nodes), CV_64F);
-//
-// for (int i = 0; i < points.size(); i++)
-// {
-// cv::Point current_center = points[i];
-// for (int p = 0; p < points.size(); p++)
-// {
-// if (p != i)
-// {
-// if (p > i) //only compute upper right triangle of matrix, rest is symmetrically added
-// {
-// cv::Point neighbor = points[p];
-// double length = pathplanner_.planPath(original_map, current_center, neighbor, downsampling_factor, robot_radius, map_resolution);
-// pathlengths.at(i, p) = length;
-// pathlengths.at(p, i) = length; //symmetrical-Matrix --> saves half the computationtime
-// }
-// }
-// else
-// {
-// pathlengths.at(i, p) = 0;
-// }
-// }
-// }
-//
-// distance_matrix = pathlengths.clone();
-//}
-
-// This function calculates for a given path the length of it. The Path is a vector with ints, that show the index of the
-// node in the path. It uses a pathlength Matrix, which should be calculated once.
-// This Matrix should save the pathlengths with this logic:
-// 1. The rows show from which Node the length is calculated.
-// 2. For the columns in a row the Matrix shows the distance to the Node in the column.
-// 3. From the node to itself the distance is 0.
-double GeneticTSPSolver::getPathLength(const cv::Mat& path_length_Matrix, std::vector given_path)
-{
- double length_of_given_path = 0;
-
- for (int i = 0; i < given_path.size() - 1; i++)
- {
- length_of_given_path += path_length_Matrix.at(given_path[i], given_path[i + 1]);
- }
-
- return length_of_given_path;
-}
-
-// This Function takes the given path and mutates it. A mutation is a random change of the path-order. For example random
-// nodes can be switched, or a random intervall of nodes can be inverted. Only the first and last Node can't be changed, because
-// they are given from the Main-function.
-std::vector GeneticTSPSolver::mutatePath(const std::vector