├── src ├── node2d.cpp ├── voronoi.cpp ├── dubins.cpp └── node4d.cpp ├── maps ├── hospital_04.pgm ├── voronoi │ ├── cache │ │ ├── 2377184163961880032 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 3383668063215391064 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 6375780720344636208 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 9584077836908302785 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 10917222191326015076 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 13544218348664178828 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 13672953455004835416 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ ├── 13724161401121741605 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ │ └── 16118496367390915469 │ │ │ ├── map.png │ │ │ ├── graphInfo │ │ │ └── treeInfo │ └── graph.yaml └── hospital_04.yaml ├── include └── hybrid_astar │ ├── voronoi.h │ ├── helper.h │ ├── node2d.h │ ├── constants.h │ ├── hybrid_astar.h │ ├── node4d.h │ └── dubins.h ├── launch └── hybrid_astar.launch ├── CMakeLists.txt ├── README.md └── package.xml /src/node2d.cpp: -------------------------------------------------------------------------------- 1 | #include "../include/hybrid_astar/node2d.h" 2 | -------------------------------------------------------------------------------- /maps/hospital_04.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/hospital_04.pgm -------------------------------------------------------------------------------- /maps/voronoi/cache/2377184163961880032/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/2377184163961880032/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/3383668063215391064/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/3383668063215391064/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/6375780720344636208/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/6375780720344636208/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/9584077836908302785/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/9584077836908302785/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/10917222191326015076/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/10917222191326015076/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/13544218348664178828/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/13544218348664178828/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/13672953455004835416/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/13672953455004835416/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/13724161401121741605/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/13724161401121741605/map.png -------------------------------------------------------------------------------- /maps/voronoi/cache/16118496367390915469/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tanujthakkar/Voronoi-Based-Hybrid-Astar/HEAD/maps/voronoi/cache/16118496367390915469/map.png -------------------------------------------------------------------------------- /maps/hospital_04.yaml: -------------------------------------------------------------------------------- 1 | image: hospital_04.pgm 2 | resolution: 0.050000 3 | origin: [0.000000, 0.000000, 0.000000] 4 | negate: 0 5 | occupied_thresh: 0.65 6 | free_thresh: 0.196 -------------------------------------------------------------------------------- /maps/voronoi/graph.yaml: -------------------------------------------------------------------------------- 1 | map_topic: "/map" 2 | map_smoothing: 15 3 | segments_topic: "/segments" 4 | segment_length: 0.9 5 | crossingOptimization: 0.2 6 | endSegmentOptimization: 0.4 -------------------------------------------------------------------------------- /include/hybrid_astar/voronoi.h: -------------------------------------------------------------------------------- 1 | #ifndef VORONOI 2 | #define VORONOI 3 | 4 | #include "constants.h" 5 | #include "helper.h" 6 | #include "node2d.h" 7 | #include "hybrid_astar.h" 8 | 9 | extern std::map> voronoi_nodes; 10 | 11 | std::vector> voronoi_path(); 12 | float calc_node_cost(float x, float y, float gx, float gy, float cost_so_far); 13 | float calc_yaw(float x_1, float y_1, float x_2, float y_2); 14 | void voronoi_map(); 15 | 16 | #endif -------------------------------------------------------------------------------- /maps/voronoi/cache/10917222191326015076/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 354 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/13544218348664178828/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 354 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/13672953455004835416/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 135 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/13724161401121741605/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 207 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/16118496367390915469/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -2.500000000e+01 7 | -2.500000000e+01 8 | 9 | 5.000000075e-02 10 | 207 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/2377184163961880032/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 172 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/3383668063215391064/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 168 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/6375780720344636208/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 210 11 | 12 | -------------------------------------------------------------------------------- /maps/voronoi/cache/9584077836908302785/graphInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0.000000000e+00 7 | 0.000000000e+00 8 | 9 | 5.000000075e-02 10 | 207 11 | 12 | -------------------------------------------------------------------------------- /include/hybrid_astar/helper.h: -------------------------------------------------------------------------------- 1 | #ifndef HELPER 2 | #define HELPER 3 | 4 | #include 5 | #include 6 | 7 | 8 | // Helper function to normalize heading to [-3.14, 3.14] 9 | static inline float pi_2_pi(float h) { 10 | 11 | while(h > M_PI) { 12 | h -= 2.0 * M_PI; 13 | } 14 | 15 | while(h < -M_PI) { 16 | h += 2.0 * M_PI; 17 | } 18 | 19 | return h; 20 | } 21 | 22 | // Helper function to convert radians to degree 23 | static inline float to_deg(float t) { 24 | return (t * 180.f / M_PI); 25 | } 26 | 27 | // Helper function to convert degrees to radians 28 | static inline float to_rad(float t) { 29 | return (t / 180.f * M_PI); 30 | } 31 | 32 | static inline float euclidean_2d(float x0, float y0, float x1, float y1) { 33 | return (hypot(x0 - x1, y0 - y1)); 34 | } 35 | 36 | #endif -------------------------------------------------------------------------------- /launch/hybrid_astar.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /include/hybrid_astar/node2d.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE2D 2 | #define NODE2D 3 | 4 | #include "constants.h" 5 | #include "helper.h" 6 | #include "hybrid_astar.h" 7 | 8 | using namespace std; 9 | 10 | class Node2D { 11 | 12 | public: 13 | 14 | // Default Constructor 15 | Node2D() {}; 16 | 17 | Node2D(float x, float y, float cost, uint pind) { 18 | 19 | this->x = x; 20 | this->y = y; 21 | this->cost = cost; 22 | this->g_cost = 0; 23 | this->pind = pind; 24 | } 25 | 26 | // Functions to get class data 27 | float get_x() const { return x; } 28 | 29 | float get_y() const { return y; } 30 | 31 | float get_cost() const { return cost; } 32 | 33 | float get_g_cost() const { return g_cost; } 34 | 35 | uint get_pind() const { return pind; } 36 | 37 | void set_g_cost(float g_cost) { this->g_cost = g_cost; } 38 | 39 | private: 40 | 41 | float x; // x co-ordinate of the node 42 | float y; // y co-ordinate of the node 43 | float cost; // cost of the node 44 | float g_cost; // g cost of the node 45 | uint pind; // parent index of the node 46 | 47 | }; 48 | 49 | #endif -------------------------------------------------------------------------------- /include/hybrid_astar/constants.h: -------------------------------------------------------------------------------- 1 | #ifndef CONSTANTS 2 | #define CONSTANTS 3 | 4 | #include 5 | 6 | // Environment Constants 7 | static const float XY_RESOLUTION = 0.05; // [m] Grid resolution of the map 8 | static const float YAW_RESOLUTION = (15 * (M_PI / 180)); // [rad] Yaw resolution 9 | static const float MOVE_STEP = 0.1; // [m] Path resolution 10 | static const float PATH_LENGTH = 0.8; // [m] Length of the path create by each node 11 | static const int VECTOR_SIZE = ceil(PATH_LENGTH/MOVE_STEP); // Size of node vectors 12 | static const float MIN_SAFE_DIST = 0.10; // [m] Minimum safe distance between vehicle and obstacles 13 | static const int STEER_STEP = 16; // Number of steering inputs (x2 total) 14 | 15 | // Path accuracy 16 | static const float XY_TOLERANCE = 0.8; // [m] Tolerance of error in solution 17 | static const float YAW_TOLERANCE = (5 * (M_PI / 180)); // [rad] Tolerance of yaw in solution 18 | 19 | // Vehicle Configuration Constants 20 | // Tractor/Robot Configuration 21 | static const float WHEELBASE = 0.638; // [m] Wheelbase of the tractor, i.e., distance from front axle to rear axle 22 | static const float RW = 0.793; // [m] Width of the tractor 23 | static const float RL = 0.960; // [m] Length of the robot/tractor 24 | static const float RF = 0.799; // [m] Distance from rear axle to front end 25 | static const float RB = 0.161; // [m] Distance from rear axle to back end 26 | static const float DELTAR = (RF - RB) / 2.0; // [m] Half of Wheelbase 27 | 28 | // Trailer Configuration 29 | static const float TW = 0.643; // [m] Width of the trailer 30 | static const float TL = 1.0; // [m] Length of the trailer 31 | static const float RTR = 0.9; // [m] Distance from the rear axle (hitch position) of the tractor to rear axle of the trailer 32 | static const float RTF = 0.025; // [m] Distance from rear axle of tractor to trailer front end 33 | static const float RTB = 0.975; // [m] Distance from rear axle of tractor to trailer back end 34 | static const float DELTAT = (RTF - RTB) / 2.0; // [m] Half the distance from hitch point to rear-axle 35 | 36 | // Costs 37 | static const float DIRECTION_CHANGE_COST = 100.0; // Penalizing change in direction of motion 38 | static const float BACKWARD_COST = 5.0; // Penalizing backwards motion 39 | static const float STEER_CHANGE_COST = 5.0; // Penalizing change in steering input 40 | static const float STEER_ANGLE_COST = 1.0; // Penalizing steering input 41 | static const float JACKNIFE_COST = 200.0; // Penalizing high hitch-angle 42 | static const float H_COST = 10.0; // Heuristic cost weight 43 | 44 | #endif -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(hybrid_astar) 3 | 4 | 5 | ## C++11 6 | include(CheckCXXCompilerFlag) 7 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) 8 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) 9 | if(COMPILER_SUPPORTS_CXX11) 10 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall") 11 | elseif(COMPILER_SUPPORTS_CXX0X) 12 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") 13 | else() 14 | message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") 15 | endif() 16 | 17 | 18 | ## Find catkin macros and libraries 19 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 20 | ## is used, also find other catkin packages 21 | find_package(catkin REQUIRED COMPONENTS 22 | roscpp 23 | rospy 24 | std_msgs 25 | nav_msgs 26 | sensor_msgs 27 | genmsg 28 | message_generation 29 | nav_core 30 | tf 31 | tuw_multi_robot_msgs 32 | ) 33 | 34 | ## Generate added messages and services with any dependencies listed here 35 | generate_messages( 36 | DEPENDENCIES 37 | std_msgs 38 | nav_msgs 39 | ) 40 | 41 | set(SOURCES 42 | ${CMAKE_CURRENT_SOURCE_DIR}/src/node2d.cpp 43 | ${CMAKE_CURRENT_SOURCE_DIR}/src/node4d.cpp 44 | ${CMAKE_CURRENT_SOURCE_DIR}/src/dubins.cpp 45 | ${CMAKE_CURRENT_SOURCE_DIR}/src/voronoi.cpp 46 | ) 47 | 48 | set(HEADERS 49 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/constants.h 50 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/helper.h 51 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/node2d.h 52 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/node4d.h 53 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/dubins.h 54 | ${CMAKE_CURRENT_SOURCE_DIR}/include/hybrid_astar/voronoi.h 55 | ) 56 | 57 | # Declare a catkin package 58 | catkin_package( 59 | CATKIN_DEPENDS roscpp rospy message_runtime 60 | ) 61 | 62 | ## OPEN MOTION PLANNING LIBRARY 63 | find_package(ompl REQUIRED) 64 | if(NOT OMPL_FOUND) 65 | message(AUTHOR_WARNING,"Open Motion Planning Library not found") 66 | endif(NOT OMPL_FOUND) 67 | 68 | include_directories(include ${catkin_INCLUDE_DIRS}) 69 | 70 | # Hybrid A* Header and Source files 71 | add_executable(hybrid_astar src/hybrid_astar.cpp ${SOURCES} ${HEADERS}) 72 | add_dependencies(hybrid_astar ${catkin_EXPORTED_TARGETS}) 73 | 74 | add_dependencies(hybrid_astar ${PROJECT_NAME}_generate_messages_cpp ) 75 | 76 | target_link_libraries(hybrid_astar ${catkin_LIBRARIES}) 77 | target_link_libraries(hybrid_astar ${OMPL_LIBRARIES}) -------------------------------------------------------------------------------- /include/hybrid_astar/hybrid_astar.h: -------------------------------------------------------------------------------- 1 | #ifndef HYBRID_ASTAR 2 | #define HYBRID_ASTAR 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include "std_msgs/String.h" 25 | #include "std_msgs/Int32.h" 26 | 27 | #include 28 | #include 29 | #include 30 | 31 | #include "constants.h" 32 | #include "helper.h" 33 | #include "node4d.h" 34 | #include "dubins.h" 35 | #include "voronoi.h" 36 | 37 | #include "tuw_multi_robot_msgs/Graph.h" 38 | 39 | using namespace std; 40 | 41 | // Library wide variables 42 | extern ros::Publisher start_pose_pub; 43 | extern ros::Publisher goal_pose_pub; 44 | extern ros::Publisher hybrid_path_pub; 45 | extern ros::Publisher hybrid_tractor_path_pub; 46 | extern ros::Publisher hybrid_trailer_path_pub; 47 | extern ros::Publisher dubins_path_pub; 48 | extern ros::Publisher reeds_shepp_path_pub; 49 | extern ros::Publisher visualize_nodes_pub; 50 | extern ros::Publisher robot_polygon_pub; 51 | extern ros::Publisher robot_polygon_array_pub; 52 | extern ros::Publisher trailer_polygon_pub; 53 | extern ros::Publisher trailer_polyogn_array_pub; 54 | extern ros::Publisher robot_center_pub; 55 | extern ros::Publisher trailer_center_pub; 56 | extern ros::Publisher robot_collision_check_pub; 57 | extern ros::Publisher trailer_collision_check_pub; 58 | extern ros::Publisher voronoi_path_pub; 59 | extern ros::Publisher voronoi_sub_goals_pub; 60 | extern ros::Publisher astar_path_pub; 61 | extern ros::Publisher cmd_pub; 62 | extern ros::Publisher target_point_pub; 63 | 64 | extern int grid_height; 65 | extern int grid_width; 66 | extern bool** bin_map; 67 | 68 | extern geometry_msgs::PoseStamped start_pose; 69 | extern geometry_msgs::PoseStamped goal_pose; 70 | extern nav_msgs::Path path; 71 | extern nav_msgs::Path trailer_path; 72 | extern std::vector dirs; 73 | extern bool visualization; 74 | extern jsk_recognition_msgs::PolygonArray robot_polygon_array; 75 | extern jsk_recognition_msgs::PolygonArray trailer_polygon_array; 76 | extern tuw_multi_robot_msgs::Graph voronoi_graph; 77 | 78 | extern float sx; 79 | extern float sy; 80 | extern float syaw; 81 | extern float syaw_t; 82 | extern int s_ind; 83 | 84 | extern float gx; 85 | extern float gy; 86 | extern float gyaw; 87 | extern int g_ind; 88 | 89 | #endif -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Voronoi Based Hybrid A* 2 | 3 | 4 | https://user-images.githubusercontent.com/32800090/122348976-5d5fb080-cf69-11eb-99d7-fbaa45056c92.mp4 5 | 6 | 7 | The following project is an extension of my bachelor's thesis conducted under the guidance of 8 | [Prof. Arpita Sinha](https://scholar.google.com/citations?user=ROSN3WgAAAAJ&hl=en&oi=ao) at Indian Institute of Technology Bombay (IITB) and submitted at 9 | Charotar University of Science and Technology. The goal of the project was to implement a suitable path planning strategy for a tractor-trailer system. In our 10 | implementation, we extend the [Hybrid A* algorithm](https://ai.stanford.edu/~ddolgov/papers/dolgov_gpp_stair08.pdf), first by introducing novelties to the 11 | heuristic search to suit the tractor-trailer model and then present a modified analytical expansion step based on voronoi graph to guide the search towards 12 | the goal faster. 13 | 14 | The code in this repository is specifically tested on Ubuntu 18.04 and ROS Melodic. The implementation is based on a 15 | [Clearpath Robotics Ridgeback](https://clearpathrobotics.com/ridgeback-indoor-robot-platform/) robot towing a custom designed trailer, however it can be tuned 16 | to other tractor-trailer systems easily. 17 | 18 |

Installation

19 | 20 |

Dependencies

21 |
    22 |
  • Ubuntu 18.04
  • 23 |
  • ROS Melodic
  • 24 |
  • Open Motion Planning Library (OMPL)
  • 25 | 26 | ``` 27 | sudo apt install libompl-dev 28 | ``` 29 | 30 |
  • jsk_reconition_msgs
  • 31 | 32 | ``` 33 | sudo apt-get install ros-melodic-jsk-recognition-msgs 34 | ``` 35 | 36 |
  • tuw_multi_robot
  • 37 | Follow INSTALL.md given in the repository. Refer to this issue if compilation error exists. Install it in the same catkin workspace as Voronoi based Hybrid A*. 38 |
39 | 40 |

Setup

41 | 42 | ``` 43 | mkdir -p catkin_ws/src 44 | cd catkin_ws/src 45 | git clone https://github.com/tanujthakkar/Voronoi-Based-Hybrid-Astar.git 46 | cd .. 47 | catkin_make 48 | source devel/setup.bash 49 | roslaunch hybrid_astar hybrid_astar.launch 50 | ``` 51 | 52 | Wait for the voronoi graph to be computed and visualized in RViz. After that, 2D Pose Estimate and 2D Nav Goal tools can be used to specify start and goal 53 | positions respectively for the planner. 54 | 55 |

Citation

56 | Our paper on Voronoi based Hybrid A* was presented at the Indian Control Conference (ICC) 2021 and is available on IEEE Explore. Please cite the paper if you find the work useful. 57 | 58 | ``` 59 | @INPROCEEDINGS{9703119, 60 | author={Thakkar, Tanuj and Sinha, Arpita}, 61 | booktitle={2021 Seventh Indian Control Conference (ICC)}, 62 | title={Motion Planning for Tractor-Trailer System}, 63 | year={2021}, 64 | volume={}, 65 | number={}, 66 | pages={93-98}, 67 | doi={10.1109/ICC54714.2021.9703119}} 68 | ``` 69 | 70 |

References

71 | 75 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hybrid_astar 4 | 0.0.0 5 | The hybrid_astar package 6 | 7 | 8 | 9 | 10 | tanujthakkar 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | roscpp 53 | rospy 54 | std_msgs 55 | roscpp 56 | rospy 57 | std_msgs 58 | roscpp 59 | rospy 60 | std_msgs 61 | 62 | message_generation 63 | message_runtime 64 | 65 | nav_core 66 | tf 67 | nav_core 68 | tf 69 | nav_core 70 | tf 71 | 72 | 73 | 74 | 75 | 76 | 77 | -------------------------------------------------------------------------------- /include/hybrid_astar/node4d.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE4D 2 | #define NODE4D 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include "std_msgs/String.h" 19 | #include "std_msgs/Int32.h" 20 | 21 | #include "constants.h" 22 | #include "helper.h" 23 | #include "hybrid_astar.h" 24 | 25 | using namespace std; 26 | 27 | class Node4D { 28 | 29 | public: 30 | 31 | // Default Constructor 32 | Node4D() {}; 33 | 34 | // Constructor for start and goal nodes 35 | Node4D(float x, float y, float yaw, float yawt, float yaw_t, int ind) { 36 | 37 | xlist.push_back(x); 38 | ylist.push_back(y); 39 | yawlist.push_back(yaw); 40 | yawtlist.push_back(yawt); 41 | this->yawt.push_back(yaw_t); 42 | this->direction = 1; 43 | this->steer = 0.0; 44 | this->cost = 0.0; 45 | this->ind = ind; 46 | this->parent_ind = NULL; 47 | } 48 | 49 | // Constructor for successor nodes 50 | Node4D(std::vector xlist, std::vector ylist, std::vector yawlist, 51 | std::vector yawtlist, std::vector yawt, int dir, float steer, float cost, int ind, int parent_ind) { 52 | 53 | int n = xlist.size(); 54 | this->xlist.resize(n); 55 | this->ylist.resize(n); 56 | this->yawlist.resize(n); 57 | this->yawtlist.resize(n); 58 | this->yawt.resize(n); 59 | 60 | this->xlist = xlist; 61 | this->ylist = ylist; 62 | this->yawlist = yawlist; 63 | this->yawtlist = yawtlist; 64 | this->yawt = yawt; 65 | this->direction = dir; 66 | this->steer = steer; 67 | this->cost = cost; 68 | this->ind = ind; 69 | this->parent_ind = parent_ind; 70 | } 71 | 72 | 73 | // Get functions to retrieve class data 74 | float get_x(int i) const { return xlist[i]; } 75 | 76 | float get_y(int i) const { return ylist[i]; } 77 | 78 | float get_yaw(int i) const { return yawlist[i]; } 79 | 80 | float get_yawt(int i) const { return yawtlist[i]; } 81 | 82 | float get_yaw_t(int i) const { return yawt[i]; } 83 | 84 | int get_dir() const { return direction; } 85 | 86 | float get_steer() const { return steer; } 87 | 88 | float get_cost() const { return cost; } 89 | 90 | Node4D* get_parent() { return parent; } 91 | 92 | Node4D* get_child() { return child; } 93 | 94 | int get_ind() { return ind; } 95 | 96 | int get_parent_ind() { return parent_ind; } 97 | 98 | int get_child_ind() { return child_ind; } 99 | 100 | int get_size() const { return xlist.size(); } 101 | 102 | // Set functions to set class data 103 | void set_cost(float cost) { this->cost + cost; } 104 | 105 | void set_child(Node4D* next) { child = next; } 106 | 107 | void set_ind(int ind) { this->ind = ind; } 108 | 109 | void set_child_ind(int child_ind) { this->child_ind = child_ind; } 110 | 111 | // Fucntion to check path collision 112 | bool check_path_collision(bool** bin_map); 113 | 114 | // Function to check tractor-trailer collision 115 | bool check_collision(nav_msgs::OccupancyGrid::Ptr grid, bool** bin_map, int** acc_obs_map); 116 | 117 | private: 118 | // Private node variables 119 | std::vector xlist; // x coords of path points 120 | std::vector ylist; // y coords of path points 121 | std::vector yawlist; // yaw of path points 122 | std::vector yawtlist; // hitch-angle of path points 123 | std::vector yawt; // Trailer yaw for collision check 124 | int direction; // Direction of motion 125 | float steer; // Node steering angle 126 | float cost; // Node cost 127 | Node4D* parent; // Pointer to the parent node 128 | Node4D* child; // Pointer to the next/child node in the final path 129 | int ind; // Node index 130 | int parent_ind; // Parent node index 131 | int child_ind; // Child node index 132 | }; 133 | 134 | // Function to create a polygon for the robot and the trailer 135 | geometry_msgs::PolygonStamped create_polygon(float l, float w, float cx, float cy, float yaw); 136 | 137 | #endif -------------------------------------------------------------------------------- /include/hybrid_astar/dubins.h: -------------------------------------------------------------------------------- 1 | #ifndef DUBINS 2 | #define DUBINS 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include "std_msgs/String.h" 19 | #include "std_msgs/Int32.h" 20 | 21 | #include 22 | #include 23 | #include 24 | #include 25 | 26 | #include "constants.h" 27 | #include "helper.h" 28 | #include "hybrid_astar.h" 29 | #include "node4d.h" 30 | 31 | using namespace std; 32 | 33 | /*! 34 | \file dubins.h 35 | \brief A dubins path class for finding analytical solutions to the problem of the shortest path. 36 | 37 | It has been copied from https://github.com/AndrewWalker/Dubins-Curves/ under the WTFPL. Please refer to the author in case of questions. 38 | \author Andrew Walker 39 | */ 40 | // Copyright (c) 2008-2014, Andrew Walker 41 | // 42 | // Permission is hereby granted, free of charge, to any person obtaining a copy 43 | // of this software and associated documentation files (the "Software"), to deal 44 | // in the Software without restriction, including without limitation the rights 45 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 46 | // copies of the Software, and to permit persons to whom the Software is 47 | // furnished to do so, subject to the following conditions: 48 | // 49 | // The above copyright notice and this permission notice shall be included in 50 | // all copies or substantial portions of the Software. 51 | // 52 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 53 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 54 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 55 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 56 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 57 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 58 | // THE SOFTWARE. 59 | 60 | // Path types 61 | #define LSL (0) 62 | #define LSR (1) 63 | #define RSL (2) 64 | #define RSR (3) 65 | #define RLR (4) 66 | #define LRL (5) 67 | 68 | // Error codes 69 | #define EDUBOK (0) // No error 70 | #define EDUBCOCONFIGS (1) // Colocated configurations 71 | #define EDUBPARAM (2) // Path parameterisitation error 72 | #define EDUBBADRHO (3) // the rho value is invalid 73 | #define EDUBNOPATH (4) // no connection between configurations with this word 74 | 75 | // The various types of solvers for each of the path types 76 | typedef int (*DubinsWord)(double, double, double, double* ); 77 | 78 | // A complete list of the possible solvers that could give optimal paths 79 | extern DubinsWord dubins_words[]; 80 | 81 | typedef struct 82 | { 83 | double qi[3]; // the initial configuration 84 | double param[3]; // the lengths of the three segments 85 | double rho; // model forward velocity / model angular velocity 86 | int type; // path type. one of LSL, LSR, ... 87 | } DubinsPath; 88 | 89 | /** 90 | * Callback function for path sampling 91 | * 92 | * @note the q parameter is a configuration 93 | * @note the t parameter is the distance along the path 94 | * @note the user_data parameter is forwarded from the caller 95 | * @note return non-zero to denote sampling should be stopped 96 | */ 97 | typedef int (*DubinsPathSamplingCallback)(double q[3], double t, void* user_data); 98 | 99 | /** 100 | * Generate a path from an initial configuration to 101 | * a target configuration, with a specified maximum turning 102 | * radii 103 | * 104 | * A configuration is (x, y, theta), where theta is in radians, with zero 105 | * along the line x = 0, and counter-clockwise is positive 106 | * 107 | * @param q0 - a configuration specified as an array of x, y, theta 108 | * @param q1 - a configuration specified as an array of x, y, theta 109 | * @param rho - turning radius of the vehicle (forward velocity divided by maximum angular velocity) 110 | * @param path - the resultant path 111 | * @return - non-zero on error 112 | */ 113 | int dubins_init( double q0[3], double q1[3], double rho, DubinsPath* path); 114 | 115 | /** 116 | * Calculate the length of an initialised path 117 | * 118 | * @param path - the path to find the length of 119 | */ 120 | double dubins_path_length( DubinsPath* path ); 121 | 122 | /** 123 | * Extract an integer that represents which path type was used 124 | * 125 | * @param path - an initialised path 126 | * @return - one of LSL, LSR, RSL, RSR, RLR or LRL (ie/ 0-5 inclusive) 127 | */ 128 | int dubins_path_type( DubinsPath * path ); 129 | 130 | /** 131 | * Calculate the configuration along the path, using the parameter t 132 | * 133 | * @param path - an initialised path 134 | * @param t - a length measure, where 0 <= t < dubins_path_length(path) 135 | * @param q - the configuration result 136 | * @returns - non-zero if 't' is not in the correct range 137 | */ 138 | int dubins_path_sample( DubinsPath* path, double t, double q[3]); 139 | 140 | /** 141 | * Walk along the path at a fixed sampling interval, calling the 142 | * callback function at each interval 143 | * 144 | * @param path - the path to sample 145 | * @param cb - the callback function to call for each sample 146 | * @param user_data - optional information to pass on to the callback 147 | * @param stepSize - the distance along the path for subsequent samples 148 | */ 149 | int dubins_path_sample_many( DubinsPath* path, DubinsPathSamplingCallback cb, double stepSize, void* user_data ); 150 | 151 | /** 152 | * Convenience function to identify the endpoint of a path 153 | * 154 | * @param path - an initialised path 155 | * @param q - the configuration result 156 | */ 157 | int dubins_path_endpoint( DubinsPath* path, double q[3] ); 158 | 159 | /** 160 | * Convenience function to extract a subset of a path 161 | * 162 | * @param path - an initialised path 163 | * @param t - a length measure, where 0 < t < dubins_path_length(path) 164 | * @param newpath - the resultant path 165 | */ 166 | int dubins_extract_subpath( DubinsPath* path, double t, DubinsPath* newpath ); 167 | 168 | // Only exposed for testing purposes 169 | int dubins_LSL( double alpha, double beta, double d, double* outputs ); 170 | int dubins_RSR( double alpha, double beta, double d, double* outputs ); 171 | int dubins_LSR( double alpha, double beta, double d, double* outputs ); 172 | int dubins_RSL( double alpha, double beta, double d, double* outputs ); 173 | int dubins_LRL( double alpha, double beta, double d, double* outputs ); 174 | int dubins_RLR( double alpha, double beta, double d, double* outputs ); 175 | 176 | #endif -------------------------------------------------------------------------------- /maps/voronoi/cache/13672953455004835416/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 135 6 | 2 7 | 2 8 | 2 9 | 2 10 | 2 11 | 2 12 | 2 13 | 2 14 | 2 15 | 2 16 | 2 17 | 2 18 | 3 19 | 3 20 | 2 21 | 2 22 | 2 23 | 2 24 | 2 25 | 2 26 | 2 27 | 2 28 | 2 29 | 2 30 | 3 31 | 3 32 | 2 33 | 2 34 | 2 35 | 2 36 | 2 37 | 2 38 | 2 39 | 2 40 | 2 41 | 2 42 | 2 43 | 2 44 | 2 45 | 2 46 | 2 47 | 3 48 | 3 49 | 2 50 | 3 51 | 3 52 | 3 53 | 3 54 | 3 55 | 3 56 | 3 57 | 3 58 | 3 59 | 3 60 | 3 61 | 3 62 | 2 63 | 2 64 | 2 65 | 2 66 | 2 67 | 2 68 | 2 69 | 2 70 | 2 71 | 2 72 | 2 73 | 2 74 | 4 75 | 4 76 | 2 77 | 2 78 | 3 79 | 3 80 | 3 81 | 3 82 | 3 83 | 3 84 | 3 85 | 3 86 | 2 87 | 2 88 | 2 89 | 2 90 | 2 91 | 2 92 | 2 93 | 3 94 | 3 95 | 3 96 | 3 97 | 3 98 | 3 99 | 3 100 | 3 101 | 3 102 | 3 103 | 3 104 | 2 105 | 2 106 | 2 107 | 2 108 | 2 109 | 2 110 | 2 111 | 2 112 | 2 113 | 2 114 | 2 115 | 2 116 | 2 117 | 2 118 | 2 119 | 2 120 | 2 121 | 2 122 | 3 123 | 3 124 | 3 125 | 2 126 | 2 127 | 2 128 | 2 129 | 2 130 | 2 131 | 2 132 | 2 133 | 2 134 | 2 135 | 2 136 | 2 137 | 2 138 | 2 139 | 2 140 | 2 141 | 1 142 | 2 143 | 1 144 | 1 145 | 2 146 | 1 147 | 1 148 | 2 149 | 1 150 | 0 151 | 2 152 | 1 153 | 1 154 | 0 155 | 3 156 | 2 157 | 1 158 | 0 159 | 1 160 | 2 161 | 2 162 | 1 163 | 0 164 | 1 165 | 2 166 | 0 167 | 2 168 | 1 169 | 2 170 | 1 171 | 2 172 | 0 173 | 2 174 | 3 175 | 2 176 | 2 177 | 2 178 | 4 179 | 0 180 | 2 181 | 4 182 | 2 183 | 2 184 | 3 185 | 1 186 | 3 187 | 1 188 | 0 189 | 1 190 | 3 191 | 0 192 | 1 193 | 0 194 | 3 195 | 0 196 | 1 197 | 0 198 | 0 199 | 1 200 | 0 201 | 2 202 | 4 203 | 0 204 | 1 205 | 3 206 | 1 207 | 3 208 | 3 209 | 3 210 | 2 211 | 0 212 | 0 213 | 3 214 | 3 215 | 3 216 | 3 217 | 3 218 | 2 219 | 2 220 | 2 221 | 0 222 | 1 223 | 2 224 | 0 225 | 0 226 | 2 227 | 0 228 | 1 229 | 0 230 | 1 231 | 1 232 | 1 233 | 0 234 | 0 235 | 1 236 | 0 237 | 2 238 | 2 239 | 2 240 | 2 241 | 2 242 | 2 243 | 2 244 | 2 245 | 0 246 | 2 247 | 2 248 | 3 249 | 2 250 | 2 251 | 0 252 | 2 253 | 2 254 | 1 255 | 1 256 | 2 257 | 0 258 | 0 259 | 1 260 | 1 261 | 2 262 | 1 263 | 0 264 | 1 265 | 2 266 | 1 267 | 0 268 | 1 269 | 1 270 | 1 271 | 0 272 | 1 273 | 1 274 | 1 275 | 1 276 | 23 277 | 44 278 | 24 279 | 23 280 | 44 281 | 24 282 | 38 283 | 51 284 | 39 285 | 38 286 | 82 287 | 39 288 | 48 289 | 49 290 | 107 291 | 24 292 | 48 293 | 44 294 | 46 295 | 80 296 | 24 297 | 48 298 | 44 299 | 46 300 | 71 301 | 46 302 | 62 303 | 21 304 | 51 305 | 24 306 | 71 307 | 35 308 | 75 309 | 91 310 | 50 311 | 114 312 | 130 313 | 174 314 | 35 315 | 41 316 | 98 317 | 101 318 | 20 319 | 195 320 | 38 321 | 71 322 | 38 323 | 39 324 | 38 325 | 71 326 | 38 327 | 39 328 | 38 329 | 71 330 | 38 331 | 39 332 | 30 333 | 25 334 | 44 335 | 44 336 | 59 337 | 144 338 | 42 339 | 23 340 | 41 341 | 23 342 | 100 343 | 95 344 | 22 345 | 18 346 | 104 347 | 103 348 | 79 349 | 71 350 | 79 351 | 71 352 | 71 353 | 104 354 | 149 355 | 165 356 | 44 357 | 44 358 | 59 359 | 41 360 | 28 361 | 74 362 | 29 363 | 35 364 | 38 365 | 39 366 | 35 367 | 38 368 | 39 369 | 35 370 | 38 371 | 39 372 | 110 373 | 10 374 | 94 375 | 104 376 | 46 377 | 37 378 | 62 379 | 130 380 | 38 381 | 82 382 | 78 383 | 72 384 | 70 385 | 50 386 | 38 387 | 51 388 | 44 389 | 25 390 | 22 391 | 43 392 | 46 393 | 49 394 | 45 395 | 48 396 | 24 397 | 44 398 | 46 399 | 48 400 | 24 401 | 44 402 | 46 403 | 40 404 | 35 405 | 40 406 | 35 407 | 25 408 | 20 409 | 25 410 | 20 411 | 412 | -------------------------------------------------------------------------------- /maps/voronoi/cache/3383668063215391064/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 168 6 | 2 7 | 2 8 | 1 9 | 1 10 | 1 11 | 1 12 | 1 13 | 1 14 | 1 15 | 1 16 | 1 17 | 1 18 | 1 19 | 1 20 | 1 21 | 1 22 | 1 23 | 1 24 | 2 25 | 1 26 | 1 27 | 1 28 | 1 29 | 1 30 | 1 31 | 1 32 | 1 33 | 2 34 | 1 35 | 1 36 | 1 37 | 1 38 | 1 39 | 1 40 | 1 41 | 1 42 | 2 43 | 1 44 | 1 45 | 1 46 | 1 47 | 1 48 | 1 49 | 1 50 | 1 51 | 1 52 | 1 53 | 1 54 | 1 55 | 1 56 | 1 57 | 1 58 | 1 59 | 1 60 | 2 61 | 2 62 | 1 63 | 2 64 | 1 65 | 1 66 | 1 67 | 1 68 | 1 69 | 2 70 | 1 71 | 1 72 | 2 73 | 2 74 | 1 75 | 1 76 | 2 77 | 1 78 | 1 79 | 1 80 | 1 81 | 2 82 | 1 83 | 2 84 | 1 85 | 2 86 | 1 87 | 2 88 | 1 89 | 2 90 | 2 91 | 2 92 | 2 93 | 1 94 | 1 95 | 2 96 | 1 97 | 1 98 | 2 99 | 1 100 | 2 101 | 2 102 | 1 103 | 2 104 | 2 105 | 1 106 | 2 107 | 1 108 | 2 109 | 2 110 | 2 111 | 1 112 | 2 113 | 2 114 | 1 115 | 1 116 | 1 117 | 2 118 | 1 119 | 1 120 | 1 121 | 1 122 | 1 123 | 2 124 | 2 125 | 2 126 | 1 127 | 1 128 | 2 129 | 2 130 | 2 131 | 1 132 | 2 133 | 2 134 | 1 135 | 2 136 | 2 137 | 2 138 | 2 139 | 2 140 | 2 141 | 1 142 | 1 143 | 1 144 | 1 145 | 1 146 | 2 147 | 2 148 | 1 149 | 1 150 | 1 151 | 1 152 | 1 153 | 2 154 | 2 155 | 1 156 | 1 157 | 1 158 | 1 159 | 1 160 | 1 161 | 1 162 | 1 163 | 2 164 | 1 165 | 1 166 | 1 167 | 1 168 | 1 169 | 1 170 | 1 171 | 1 172 | 2 173 | 2 174 | 0 175 | 1 176 | 1 177 | 1 178 | 1 179 | 1 180 | 1 181 | 1 182 | 1 183 | 1 184 | 1 185 | 1 186 | 1 187 | 1 188 | 1 189 | 1 190 | 1 191 | 2 192 | 1 193 | 1 194 | 1 195 | 1 196 | 1 197 | 1 198 | 1 199 | 1 200 | 2 201 | 1 202 | 1 203 | 1 204 | 1 205 | 1 206 | 1 207 | 1 208 | 1 209 | 2 210 | 1 211 | 1 212 | 1 213 | 1 214 | 1 215 | 1 216 | 1 217 | 1 218 | 1 219 | 1 220 | 1 221 | 1 222 | 1 223 | 1 224 | 1 225 | 1 226 | 1 227 | 2 228 | 0 229 | 1 230 | 2 231 | 1 232 | 1 233 | 1 234 | 1 235 | 1 236 | 2 237 | 1 238 | 1 239 | 2 240 | 0 241 | 1 242 | 1 243 | 2 244 | 1 245 | 1 246 | 1 247 | 1 248 | 2 249 | 1 250 | 0 251 | 1 252 | 2 253 | 1 254 | 0 255 | 1 256 | 2 257 | 0 258 | 2 259 | 0 260 | 1 261 | 1 262 | 2 263 | 1 264 | 1 265 | 2 266 | 1 267 | 0 268 | 0 269 | 1 270 | 0 271 | 0 272 | 1 273 | 2 274 | 1 275 | 2 276 | 2 277 | 0 278 | 1 279 | 2 280 | 0 281 | 1 282 | 1 283 | 1 284 | 2 285 | 1 286 | 1 287 | 1 288 | 1 289 | 1 290 | 2 291 | 2 292 | 0 293 | 1 294 | 1 295 | 2 296 | 2 297 | 0 298 | 1 299 | 0 300 | 0 301 | 1 302 | 2 303 | 0 304 | 0 305 | 2 306 | 0 307 | 0 308 | 1 309 | 1 310 | 1 311 | 1 312 | 1 313 | 2 314 | 0 315 | 1 316 | 1 317 | 1 318 | 1 319 | 1 320 | 2 321 | 2 322 | 1 323 | 1 324 | 1 325 | 1 326 | 1 327 | 1 328 | 1 329 | 1 330 | 2 331 | 1 332 | 1 333 | 1 334 | 1 335 | 1 336 | 1 337 | 1 338 | 1 339 | 2 340 | 0 341 | 0 342 | 23 343 | 21 344 | 20 345 | 20 346 | 20 347 | 20 348 | 20 349 | 20 350 | 20 351 | 20 352 | 20 353 | 20 354 | 20 355 | 20 356 | 20 357 | 20 358 | 20 359 | 20 360 | 21 361 | 20 362 | 20 363 | 20 364 | 20 365 | 20 366 | 20 367 | 20 368 | 15 369 | 21 370 | 20 371 | 20 372 | 20 373 | 20 374 | 20 375 | 20 376 | 20 377 | 16 378 | 21 379 | 20 380 | 20 381 | 20 382 | 20 383 | 20 384 | 20 385 | 20 386 | 20 387 | 20 388 | 20 389 | 20 390 | 20 391 | 20 392 | 20 393 | 20 394 | 20 395 | 5 396 | 20 397 | 27 398 | 26 399 | 21 400 | 20 401 | 20 402 | 20 403 | 20 404 | 20 405 | 22 406 | 21 407 | 20 408 | 29 409 | 24 410 | 23 411 | 21 412 | 23 413 | 22 414 | 22 415 | 22 416 | 21 417 | 22 418 | 20 419 | 28 420 | 26 421 | 22 422 | 20 423 | 27 424 | 25 425 | 27 426 | 18 427 | 30 428 | 26 429 | 25 430 | 24 431 | 26 432 | 25 433 | 23 434 | 21 435 | 19 436 | 35 437 | 20 438 | 18 439 | 31 440 | 25 441 | 24 442 | 23 443 | 21 444 | 21 445 | 28 446 | 27 447 | 25 448 | 27 449 | 23 450 | 22 451 | 22 452 | 20 453 | 20 454 | 19 455 | 19 456 | 19 457 | 19 458 | 19 459 | 18 460 | 30 461 | 26 462 | 25 463 | 24 464 | 32 465 | 35 466 | 20 467 | 18 468 | 31 469 | 25 470 | 24 471 | 19 472 | 19 473 | 30 474 | 28 475 | 29 476 | 22 477 | 21 478 | 21 479 | 21 480 | 21 481 | 19 482 | 27 483 | 23 484 | 22 485 | 22 486 | 22 487 | 22 488 | 17 489 | 36 490 | 21 491 | 20 492 | 20 493 | 20 494 | 20 495 | 20 496 | 20 497 | 20 498 | 17 499 | 21 500 | 20 501 | 20 502 | 20 503 | 20 504 | 20 505 | 20 506 | 20 507 | 16 508 | 23 509 | 19 510 | 511 | -------------------------------------------------------------------------------- /maps/voronoi/cache/2377184163961880032/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 172 6 | 2 7 | 2 8 | 2 9 | 2 10 | 2 11 | 2 12 | 2 13 | 2 14 | 2 15 | 2 16 | 2 17 | 1 18 | 2 19 | 3 20 | 3 21 | 2 22 | 1 23 | 2 24 | 2 25 | 2 26 | 2 27 | 2 28 | 2 29 | 2 30 | 2 31 | 2 32 | 3 33 | 3 34 | 2 35 | 2 36 | 2 37 | 2 38 | 2 39 | 2 40 | 2 41 | 2 42 | 1 43 | 2 44 | 2 45 | 1 46 | 2 47 | 1 48 | 1 49 | 2 50 | 1 51 | 1 52 | 1 53 | 2 54 | 2 55 | 2 56 | 1 57 | 2 58 | 2 59 | 1 60 | 2 61 | 2 62 | 1 63 | 1 64 | 1 65 | 3 66 | 3 67 | 3 68 | 3 69 | 3 70 | 3 71 | 3 72 | 3 73 | 3 74 | 3 75 | 3 76 | 3 77 | 2 78 | 2 79 | 2 80 | 2 81 | 2 82 | 2 83 | 1 84 | 1 85 | 2 86 | 2 87 | 2 88 | 2 89 | 2 90 | 2 91 | 2 92 | 1 93 | 2 94 | 1 95 | 2 96 | 2 97 | 2 98 | 1 99 | 2 100 | 1 101 | 3 102 | 3 103 | 3 104 | 3 105 | 3 106 | 2 107 | 1 108 | 2 109 | 1 110 | 1 111 | 2 112 | 2 113 | 1 114 | 1 115 | 1 116 | 2 117 | 2 118 | 2 119 | 2 120 | 2 121 | 2 122 | 2 123 | 3 124 | 3 125 | 3 126 | 3 127 | 3 128 | 3 129 | 3 130 | 3 131 | 3 132 | 2 133 | 2 134 | 1 135 | 2 136 | 2 137 | 1 138 | 2 139 | 1 140 | 2 141 | 2 142 | 2 143 | 2 144 | 1 145 | 1 146 | 2 147 | 2 148 | 1 149 | 2 150 | 2 151 | 2 152 | 2 153 | 2 154 | 2 155 | 2 156 | 2 157 | 2 158 | 2 159 | 3 160 | 3 161 | 3 162 | 2 163 | 2 164 | 2 165 | 2 166 | 2 167 | 2 168 | 2 169 | 2 170 | 2 171 | 2 172 | 2 173 | 2 174 | 2 175 | 2 176 | 2 177 | 2 178 | 0 179 | 2 180 | 0 181 | 0 182 | 2 183 | 0 184 | 0 185 | 2 186 | 0 187 | 0 188 | 1 189 | 2 190 | 0 191 | 0 192 | 0 193 | 1 194 | 2 195 | 2 196 | 0 197 | 0 198 | 0 199 | 2 200 | 2 201 | 0 202 | 0 203 | 0 204 | 2 205 | 0 206 | 2 207 | 0 208 | 2 209 | 0 210 | 2 211 | 0 212 | 2 213 | 1 214 | 2 215 | 2 216 | 1 217 | 2 218 | 1 219 | 1 220 | 2 221 | 1 222 | 1 223 | 1 224 | 2 225 | 0 226 | 2 227 | 1 228 | 2 229 | 2 230 | 1 231 | 2 232 | 2 233 | 1 234 | 1 235 | 1 236 | 2 237 | 0 238 | 3 239 | 0 240 | 0 241 | 0 242 | 3 243 | 0 244 | 0 245 | 0 246 | 3 247 | 0 248 | 0 249 | 0 250 | 0 251 | 0 252 | 0 253 | 2 254 | 1 255 | 1 256 | 2 257 | 0 258 | 2 259 | 2 260 | 0 261 | 3 262 | 0 263 | 1 264 | 2 265 | 1 266 | 3 267 | 2 268 | 2 269 | 1 270 | 0 271 | 1 272 | 0 273 | 3 274 | 3 275 | 3 276 | 3 277 | 3 278 | 1 279 | 2 280 | 1 281 | 1 282 | 2 283 | 2 284 | 1 285 | 1 286 | 1 287 | 2 288 | 0 289 | 0 290 | 2 291 | 0 292 | 0 293 | 2 294 | 0 295 | 0 296 | 0 297 | 0 298 | 0 299 | 0 300 | 0 301 | 0 302 | 0 303 | 0 304 | 2 305 | 1 306 | 2 307 | 2 308 | 1 309 | 2 310 | 1 311 | 2 312 | 2 313 | 2 314 | 2 315 | 1 316 | 1 317 | 2 318 | 0 319 | 1 320 | 2 321 | 2 322 | 3 323 | 2 324 | 2 325 | 0 326 | 2 327 | 2 328 | 0 329 | 0 330 | 2 331 | 0 332 | 0 333 | 0 334 | 0 335 | 2 336 | 0 337 | 0 338 | 0 339 | 2 340 | 0 341 | 0 342 | 0 343 | 0 344 | 0 345 | 0 346 | 0 347 | 0 348 | 0 349 | 0 350 | 23 351 | 44 352 | 24 353 | 23 354 | 44 355 | 24 356 | 38 357 | 51 358 | 39 359 | 38 360 | 42 361 | 41 362 | 39 363 | 48 364 | 49 365 | 55 366 | 53 367 | 24 368 | 48 369 | 44 370 | 46 371 | 80 372 | 24 373 | 48 374 | 44 375 | 46 376 | 71 377 | 46 378 | 62 379 | 21 380 | 51 381 | 24 382 | 71 383 | 35 384 | 75 385 | 47 386 | 45 387 | 50 388 | 58 389 | 57 390 | 45 391 | 44 392 | 43 393 | 45 394 | 44 395 | 44 396 | 44 397 | 35 398 | 41 399 | 50 400 | 49 401 | 8 402 | 52 403 | 50 404 | 20 405 | 51 406 | 50 407 | 50 408 | 47 409 | 38 410 | 71 411 | 38 412 | 39 413 | 38 414 | 71 415 | 38 416 | 39 417 | 38 418 | 71 419 | 38 420 | 39 421 | 30 422 | 25 423 | 44 424 | 44 425 | 59 426 | 50 427 | 49 428 | 47 429 | 42 430 | 23 431 | 7 432 | 23 433 | 41 434 | 23 435 | 51 436 | 50 437 | 49 438 | 47 439 | 22 440 | 18 441 | 54 442 | 51 443 | 53 444 | 51 445 | 79 446 | 71 447 | 79 448 | 71 449 | 71 450 | 53 451 | 52 452 | 51 453 | 50 454 | 50 455 | 7 456 | 43 457 | 42 458 | 42 459 | 41 460 | 44 461 | 44 462 | 59 463 | 41 464 | 28 465 | 74 466 | 29 467 | 35 468 | 38 469 | 39 470 | 35 471 | 38 472 | 39 473 | 35 474 | 38 475 | 39 476 | 21 477 | 56 478 | 55 479 | 10 480 | 48 481 | 47 482 | 53 483 | 52 484 | 46 485 | 37 486 | 62 487 | 45 488 | 44 489 | 43 490 | 38 491 | 42 492 | 41 493 | 78 494 | 72 495 | 70 496 | 50 497 | 38 498 | 51 499 | 44 500 | 25 501 | 22 502 | 43 503 | 46 504 | 49 505 | 45 506 | 48 507 | 24 508 | 44 509 | 46 510 | 48 511 | 24 512 | 44 513 | 46 514 | 40 515 | 35 516 | 40 517 | 35 518 | 25 519 | 20 520 | 25 521 | 20 522 | 523 | -------------------------------------------------------------------------------- /src/voronoi.cpp: -------------------------------------------------------------------------------- 1 | #include "../include/hybrid_astar/voronoi.h" 2 | 3 | std::map> voronoi_nodes; // Map of voronoi nodes with their respective neighbours 4 | typedef pair pi; 5 | 6 | 7 | /* 8 | Function to create a map of voronoi nodes with their neighbours 9 | 10 | Returns: updates voronoi_nodes variable 11 | */ 12 | void voronoi_map() { 13 | 14 | std::vector neighbours; // Vector to store neighbours of a node 15 | std::vector redundunt_nodes; // Vector to store redundant nodes 16 | 17 | for(int i = 0; i < voronoi_graph.vertices.size(); ++i) 18 | { 19 | if(!voronoi_nodes.count(voronoi_graph.vertices[i].id)) { 20 | neighbours.clear(); 21 | redundunt_nodes.clear(); 22 | redundunt_nodes.push_back(voronoi_graph.vertices[i].path[0]); 23 | 24 | for (int succ = 0; succ < voronoi_graph.vertices[i].successors.size(); ++succ) 25 | { 26 | if(count(neighbours.begin(), neighbours.end(), voronoi_graph.vertices[i].successors[succ])) { 27 | continue; 28 | } else { 29 | redundunt_nodes.push_back(voronoi_graph.vertices[voronoi_graph.vertices[i].successors[succ]].path[0]); 30 | neighbours.push_back(voronoi_graph.vertices[i].successors[succ]); 31 | } 32 | } 33 | 34 | for (int pred = 0; pred < voronoi_graph.vertices[i].predecessors.size(); ++pred) 35 | { 36 | if(count(neighbours.begin(), neighbours.end(), voronoi_graph.vertices[i].predecessors[pred])) { 37 | continue; 38 | } else { 39 | redundunt_nodes.push_back(voronoi_graph.vertices[voronoi_graph.vertices[i].predecessors[pred]].path[0]); 40 | neighbours.push_back(voronoi_graph.vertices[i].predecessors[pred]); 41 | } 42 | } 43 | 44 | voronoi_nodes[voronoi_graph.vertices[i].id] = neighbours; 45 | } else { 46 | continue; 47 | } 48 | } 49 | } 50 | 51 | 52 | /* 53 | Function to calculate node cost 54 | 55 | x: x coordinate of node 56 | y: y coordinate of node 57 | gx: goal x 58 | gy: goal y 59 | cost_so_far: cost of the path so far 60 | 61 | Returns: node cost 62 | */ 63 | float calc_node_cost(float x, float y, float gx, float gy, float cost_so_far) { 64 | return cost_so_far + sqrt(pow(x - gx, 2) + pow(y - gy, 2) + pow(abs(abs(abs(calc_yaw(x, y, sx, sy) - syaw) - 3.14) - 3.14), 2)); 65 | // (hypot(x - gx, y - gy)) + (abs(abs(abs(calc_yaw(x, y, sx, sy) - syaw) - 3.14) - 3.14)); 66 | } 67 | 68 | 69 | /* 70 | Function to calculate yaw/heading of nodes 71 | 72 | x_1: x coordinate of parent node 73 | y_1: y coordinate of parent node 74 | x_2: x coordinate of current node 75 | y_2: y coordinate of current node 76 | 77 | Returns: new node object 78 | */ 79 | float calc_yaw(float x_1, float y_1, float x_2, float y_2) { 80 | 81 | if(y_2 - y_1 > 0 && x_2 - x_1 > 0) { 82 | return asin((y_2 - y_1)/hypot(x_2 - x_1, y_2 - y_1)); 83 | } 84 | 85 | if(y_2 - y_1 > 0 && x_2 - x_1 < 0) { 86 | return (3.14 - asin((y_2 - y_1)/hypot(x_2 - x_1, y_2 - y_1))); 87 | } 88 | 89 | if(y_2 - y_1 < 0 && x_2 - x_1 > 0) { 90 | return asin((y_2 - y_1)/hypot(x_2 - x_1, y_2 - y_1)); 91 | } 92 | 93 | if(y_2 - y_1 < 0 && x_2 - x_1 < 0) { 94 | return (-3.14 - asin((y_2 - y_1)/hypot(x_2 - x_1, y_2 - y_1))); 95 | } 96 | 97 | if(y_2 - y_1 == 0) { 98 | if(x_2 > x_1) { 99 | return 0.0; 100 | } else { 101 | return 3.14; 102 | } 103 | } 104 | 105 | if(x_2 - x_1 == 0) { 106 | if(y_2 > y_1) { 107 | return 1.57; 108 | } else { 109 | return -1.57; 110 | } 111 | } 112 | } 113 | 114 | 115 | /* 116 | Function to display contents of a map 117 | 118 | m: map to be displayed 119 | */ 120 | void display_map(std::map m) { 121 | std::map::iterator itr; 122 | for (itr = m.begin(); itr != m.end(); ++itr) { 123 | cout << '\t' << itr->first << endl; 124 | } 125 | } 126 | 127 | 128 | /* 129 | Function to display contents of the priority queue 130 | 131 | gq: priority queue to be displayed 132 | */ 133 | void display_pq(priority_queue, greater> gq) 134 | { 135 | priority_queue, greater> g = gq; 136 | 137 | cout << "Priority Queue - " << endl; 138 | if(g.empty()) { 139 | cout << "Priority Queue EMPTY" << endl; 140 | } 141 | while (!g.empty()) { 142 | cout << "\tCost: " << g.top().first << " Index: " << g.top().second << endl; 143 | g.pop(); 144 | } 145 | cout << endl; 146 | } 147 | 148 | 149 | /* 150 | Function to compute the voronoi path 151 | */ 152 | std::vector> voronoi_path() { 153 | 154 | geometry_msgs::PointStamped voronoi_start; 155 | float nearest_voronoi_start = hypot(voronoi_graph.vertices[0].path[0].x - sx, voronoi_graph.vertices[0].path[0].y - sy); 156 | uint voronoi_start_id; 157 | geometry_msgs::PointStamped voronoi_goal; 158 | float nearest_voronoi_goal = hypot(voronoi_graph.vertices[0].path[0].x - gx, voronoi_graph.vertices[0].path[0].y - gy); 159 | uint voronoi_goal_id; 160 | 161 | voronoi_start.header.stamp = ros::Time::now(); 162 | voronoi_start.header.frame_id = "/map"; 163 | voronoi_goal.header.stamp = ros::Time::now(); 164 | voronoi_goal.header.frame_id = "/map"; 165 | 166 | for (int i = 0; i < voronoi_graph.vertices.size(); ++i) { 167 | if(nearest_voronoi_start >= hypot(voronoi_graph.vertices[i].path[0].x - sx, voronoi_graph.vertices[i].path[0].y - sy)) { 168 | nearest_voronoi_start = hypot(voronoi_graph.vertices[i].path[0].x - sx, voronoi_graph.vertices[i].path[0].y - sy); 169 | voronoi_start.point = voronoi_graph.vertices[i].path[0]; 170 | voronoi_start_id = voronoi_graph.vertices[i].id; 171 | robot_center_pub.publish(voronoi_start); 172 | } 173 | if(nearest_voronoi_goal >= hypot(voronoi_graph.vertices[i].path[0].x - gx, voronoi_graph.vertices[i].path[0].y - gy)) { 174 | nearest_voronoi_goal = hypot(voronoi_graph.vertices[i].path[0].x - gx, voronoi_graph.vertices[i].path[0].y - gy); 175 | voronoi_goal.point = voronoi_graph.vertices[i].path[0]; 176 | voronoi_goal_id = voronoi_graph.vertices[i].id; 177 | trailer_center_pub.publish(voronoi_goal); 178 | } 179 | } 180 | 181 | visualization_msgs::Marker voronoi_path_points; 182 | voronoi_path_points.header.stamp = ros::Time::now(); 183 | voronoi_path_points.header.frame_id = "/map"; 184 | voronoi_path_points.ns = "voronoi_path_points"; 185 | voronoi_path_points.action = visualization_msgs::Marker::ADD; 186 | voronoi_path_points.id = 0; 187 | voronoi_path_points.type = visualization_msgs::Marker::POINTS; 188 | voronoi_path_points.scale.x = 0.2; 189 | voronoi_path_points.scale.y = 0.2; 190 | voronoi_path_points.color.r = 1.0; 191 | voronoi_path_points.color.g = 0.0; 192 | voronoi_path_points.color.b = 0.0; 193 | voronoi_path_points.color.a = 1.0; 194 | voronoi_path_points.points.clear(); 195 | 196 | geometry_msgs::Point voronoi_neighbour; 197 | 198 | Node2D current_node; // Node2D object to track current node 199 | Node2D new_node; // Node2D object to track new nodes 200 | float node_cost; 201 | float cost_so_far = 0; 202 | pair current_id; // Variable to track ID of current node 203 | uint new_id; // Variable to track ID of new node 204 | 205 | std::map open_list; // Creating the open_list using a map 206 | std::map closed_list; // Creating the closed_list using a map 207 | 208 | open_list[voronoi_start_id] = Node2D(voronoi_graph.vertices[voronoi_start_id].path[0].x, voronoi_graph.vertices[voronoi_start_id].path[0].y, 0, NULL); 209 | 210 | priority_queue, greater> pq; // Creating a min priority queue to sort nodes with respect to highest priority (lowest cost) 211 | pq.push(make_pair(0, voronoi_start_id)); // Adding the start node to the priority queue 212 | 213 | while(true) { 214 | 215 | if(open_list.empty()) { 216 | ROS_INFO("SOLUTION DOESN'T EXIST - NO NODES FOUND IN OPEN LIST"); 217 | break; 218 | } 219 | 220 | current_id = pq.top(); // Retrieve the pair with the highest priority (lowest cost) 221 | pq.pop(); // Pop the pair with highest priority 222 | 223 | current_node = open_list[current_id.second]; // Update current node to the node with highest priority 224 | cost_so_far = cost_so_far + current_node.get_cost(); // Update cost_so_far 225 | closed_list[current_id.second] = current_node; // Added updated current node to the closed list 226 | open_list.erase(current_id.second); // Remove updated current node from open list 227 | 228 | // Check if goal is reached 229 | if(current_id.second == voronoi_goal_id) { 230 | break; 231 | } 232 | 233 | // Expand the current node 234 | for (int i = 0; i < voronoi_nodes[current_id.second].size(); ++i) { 235 | 236 | node_cost = calc_node_cost(voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].x, voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].y, gx, gy, cost_so_far); 237 | node_cost = node_cost + hypot(voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].x - voronoi_graph.vertices[current_id.second].path[0].x, voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].y - voronoi_graph.vertices[current_id.second].path[0].y); 238 | new_node = Node2D(voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].x, voronoi_graph.vertices[voronoi_nodes[current_id.second][i]].path[0].y, node_cost, current_id.second); 239 | 240 | new_id = voronoi_nodes[current_id.second][i]; // Updaign new_id 241 | 242 | // Checking if new node exists in closed list 243 | if(closed_list.count(new_id)) { 244 | continue; 245 | } 246 | 247 | // Checking if new node exists in open list 248 | if(!open_list.count(new_id)) { 249 | open_list[new_id] = new_node; 250 | pq.push(make_pair(new_node.get_cost(), new_id)); 251 | } else { 252 | if(open_list[new_id].get_cost() > new_node.get_cost()) { 253 | open_list[new_id] = new_node; 254 | } 255 | } 256 | } 257 | } 258 | 259 | std::vector> sub_goals; 260 | std::vector redundunt_nodes; 261 | 262 | float yaw; 263 | geometry_msgs::Pose p; 264 | 265 | while(current_node.get_pind() != NULL) { 266 | if(count(redundunt_nodes.begin(), redundunt_nodes.end(), voronoi_graph.vertices[current_node.get_pind()].path[0])) { 267 | current_node = closed_list[current_node.get_pind()]; 268 | continue; 269 | } 270 | voronoi_path_points.points.push_back(voronoi_graph.vertices[current_node.get_pind()].path[0]); 271 | p.position.x = voronoi_graph.vertices[current_node.get_pind()].path[0].x; 272 | p.position.y = voronoi_graph.vertices[current_node.get_pind()].path[0].y; 273 | yaw = calc_yaw(voronoi_graph.vertices[current_node.get_pind()].path[0].x, voronoi_graph.vertices[current_node.get_pind()].path[0].y, current_node.get_x(), current_node.get_y()); 274 | tf::Quaternion quat = tf::createQuaternionFromYaw(yaw); 275 | p.orientation.x = quat.x(); 276 | p.orientation.y = quat.y(); 277 | p.orientation.z = quat.z(); 278 | p.orientation.w = quat.w(); 279 | redundunt_nodes.push_back(voronoi_graph.vertices[current_node.get_pind()].path[0]); 280 | sub_goals.push_back({p.position.x, p.position.y, yaw}); 281 | current_node = closed_list[current_node.get_pind()]; 282 | voronoi_path_pub.publish(voronoi_path_points); 283 | } 284 | voronoi_path_points.points.erase(voronoi_path_points.points.begin()); 285 | voronoi_path_pub.publish(voronoi_path_points); 286 | 287 | sub_goals.erase(sub_goals.begin()); 288 | reverse(sub_goals.begin(), sub_goals.end()); 289 | sub_goals.push_back({gx, gy, gyaw}); 290 | 291 | return sub_goals; 292 | } -------------------------------------------------------------------------------- /src/dubins.cpp: -------------------------------------------------------------------------------- 1 | #include "../include/hybrid_astar/dubins.h" 2 | 3 | // Copyright (c) 2008-2014, Andrew Walker 4 | // 5 | // Permission is hereby granted, free of charge, to any person obtaining a copy 6 | // of this software and associated documentation files (the "Software"), to deal 7 | // in the Software without restriction, including without limitation the rights 8 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | // copies of the Software, and to permit persons to whom the Software is 10 | // furnished to do so, subject to the following conditions: 11 | // 12 | // The above copyright notice and this permission notice shall be included in 13 | // all copies or substantial portions of the Software. 14 | // 15 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 21 | // THE SOFTWARE. 22 | 23 | #define _USE_MATH_DEFINES // for C++ 24 | #include 25 | #include 26 | 27 | #define EPSILON (10e-10) 28 | 29 | #define LSL (0) 30 | #define LSR (1) 31 | #define RSL (2) 32 | #define RSR (3) 33 | #define RLR (4) 34 | #define LRL (5) 35 | 36 | // The three segment types a path can be made up of 37 | #define L_SEG (0) 38 | #define S_SEG (1) 39 | #define R_SEG (2) 40 | 41 | 42 | // The segment types for each of the Path types 43 | const int DIRDATA[][3] = { 44 | { L_SEG, S_SEG, L_SEG }, 45 | { L_SEG, S_SEG, R_SEG }, 46 | { R_SEG, S_SEG, L_SEG }, 47 | { R_SEG, S_SEG, R_SEG }, 48 | { R_SEG, L_SEG, R_SEG }, 49 | { L_SEG, R_SEG, L_SEG } 50 | }; 51 | 52 | DubinsWord dubins_words[] = { 53 | dubins_LSL, 54 | dubins_LSR, 55 | dubins_RSL, 56 | dubins_RSR, 57 | dubins_RLR, 58 | dubins_LRL, 59 | }; 60 | 61 | #define UNPACK_INPUTS(alpha, beta) \ 62 | double sa = sin(alpha); \ 63 | double sb = sin(beta); \ 64 | double ca = cos(alpha); \ 65 | double cb = cos(beta); \ 66 | double c_ab = cos(alpha - beta); \ 67 | 68 | #define PACK_OUTPUTS(outputs) \ 69 | outputs[0] = t; \ 70 | outputs[1] = p; \ 71 | outputs[2] = q; 72 | 73 | /** 74 | * Floating point modulus suitable for rings 75 | * 76 | * fmod doesn't behave correctly for angular quantities, this function does 77 | */ 78 | double fmodr( double x, double y) 79 | { 80 | return x - y*floor(x/y); 81 | } 82 | 83 | double mod2pi( double theta ) 84 | { 85 | return fmodr( theta, 2 * M_PI ); 86 | } 87 | 88 | int dubins_init_normalised( double alpha, double beta, double d, DubinsPath* path) 89 | { 90 | double best_cost = INFINITY; 91 | int best_word; 92 | int i; 93 | 94 | best_word = -1; 95 | for( i = 0; i < 6; i++ ) { 96 | double params[3]; 97 | int err = dubins_words[i](alpha, beta, d, params); 98 | if(err == EDUBOK) { 99 | double cost = params[0] + params[1] + params[2]; 100 | if(cost < best_cost) { 101 | best_word = i; 102 | best_cost = cost; 103 | path->param[0] = params[0]; 104 | path->param[1] = params[1]; 105 | path->param[2] = params[2]; 106 | path->type = i; 107 | } 108 | } 109 | } 110 | 111 | if(best_word == -1) { 112 | return EDUBNOPATH; 113 | } 114 | path->type = best_word; 115 | return EDUBOK; 116 | } 117 | 118 | int dubins_init( double q0[3], double q1[3], double rho, DubinsPath* path ) 119 | { 120 | int i; 121 | double dx = q1[0] - q0[0]; 122 | double dy = q1[1] - q0[1]; 123 | double D = sqrt( dx * dx + dy * dy ); 124 | double d = D / rho; 125 | if( rho <= 0. ) { 126 | return EDUBBADRHO; 127 | } 128 | double theta = mod2pi(atan2( dy, dx )); 129 | double alpha = mod2pi(q0[2] - theta); 130 | double beta = mod2pi(q1[2] - theta); 131 | for( i = 0; i < 3; i ++ ) { 132 | path->qi[i] = q0[i]; 133 | } 134 | path->rho = rho; 135 | 136 | return dubins_init_normalised( alpha, beta, d, path ); 137 | } 138 | 139 | int dubins_LSL( double alpha, double beta, double d, double* outputs ) 140 | { 141 | UNPACK_INPUTS(alpha, beta); 142 | double tmp0 = d+sa-sb; 143 | double p_squared = 2 + (d*d) -(2*c_ab) + (2*d*(sa - sb)); 144 | if( p_squared < 0 ) { 145 | return EDUBNOPATH; 146 | } 147 | double tmp1 = atan2( (cb-ca), tmp0 ); 148 | double t = mod2pi(-alpha + tmp1 ); 149 | double p = sqrt( p_squared ); 150 | double q = mod2pi(beta - tmp1 ); 151 | PACK_OUTPUTS(outputs); 152 | return EDUBOK; 153 | } 154 | 155 | int dubins_RSR( double alpha, double beta, double d, double* outputs ) 156 | { 157 | UNPACK_INPUTS(alpha, beta); 158 | double tmp0 = d-sa+sb; 159 | double p_squared = 2 + (d*d) -(2*c_ab) + (2*d*(sb-sa)); 160 | if( p_squared < 0 ) { 161 | return EDUBNOPATH; 162 | } 163 | double tmp1 = atan2( (ca-cb), tmp0 ); 164 | double t = mod2pi( alpha - tmp1 ); 165 | double p = sqrt( p_squared ); 166 | double q = mod2pi( -beta + tmp1 ); 167 | PACK_OUTPUTS(outputs); 168 | return EDUBOK; 169 | } 170 | 171 | int dubins_LSR( double alpha, double beta, double d, double* outputs ) 172 | { 173 | UNPACK_INPUTS(alpha, beta); 174 | double p_squared = -2 + (d*d) + (2*c_ab) + (2*d*(sa+sb)); 175 | if( p_squared < 0 ) { 176 | return EDUBNOPATH; 177 | } 178 | double p = sqrt( p_squared ); 179 | double tmp2 = atan2( (-ca-cb), (d+sa+sb) ) - atan2(-2.0, p); 180 | double t = mod2pi(-alpha + tmp2); 181 | double q = mod2pi( -mod2pi(beta) + tmp2 ); 182 | PACK_OUTPUTS(outputs); 183 | return EDUBOK; 184 | } 185 | 186 | int dubins_RSL( double alpha, double beta, double d, double* outputs ) 187 | { 188 | UNPACK_INPUTS(alpha, beta); 189 | double p_squared = (d*d) -2 + (2*c_ab) - (2*d*(sa+sb)); 190 | if( p_squared< 0 ) { 191 | return EDUBNOPATH; 192 | } 193 | double p = sqrt( p_squared ); 194 | double tmp2 = atan2( (ca+cb), (d-sa-sb) ) - atan2(2.0, p); 195 | double t = mod2pi(alpha - tmp2); 196 | double q = mod2pi(beta - tmp2); 197 | PACK_OUTPUTS(outputs); 198 | return EDUBOK; 199 | } 200 | 201 | int dubins_RLR( double alpha, double beta, double d, double* outputs ) 202 | { 203 | UNPACK_INPUTS(alpha, beta); 204 | double tmp_rlr = (6. - d*d + 2*c_ab + 2*d*(sa-sb)) / 8.; 205 | if( fabs(tmp_rlr) > 1) { 206 | return EDUBNOPATH; 207 | } 208 | double p = mod2pi( 2*M_PI - acos( tmp_rlr ) ); 209 | double t = mod2pi(alpha - atan2( ca-cb, d-sa+sb ) + mod2pi(p/2.)); 210 | double q = mod2pi(alpha - beta - t + mod2pi(p)); 211 | PACK_OUTPUTS( outputs ); 212 | return EDUBOK; 213 | } 214 | 215 | int dubins_LRL( double alpha, double beta, double d, double* outputs ) 216 | { 217 | UNPACK_INPUTS(alpha, beta); 218 | double tmp_lrl = (6. - d*d + 2*c_ab + 2*d*(- sa + sb)) / 8.; 219 | if( fabs(tmp_lrl) > 1) { 220 | return EDUBNOPATH; 221 | } 222 | double p = mod2pi( 2*M_PI - acos( tmp_lrl ) ); 223 | double t = mod2pi(-alpha - atan2( ca-cb, d+sa-sb ) + p/2.); 224 | double q = mod2pi(mod2pi(beta) - alpha -t + mod2pi(p)); 225 | PACK_OUTPUTS( outputs ); 226 | return EDUBOK; 227 | } 228 | 229 | double dubins_path_length( DubinsPath* path ) 230 | { 231 | double length = 0.; 232 | length += path->param[0]; 233 | length += path->param[1]; 234 | length += path->param[2]; 235 | length = length * path->rho; 236 | return length; 237 | } 238 | 239 | int dubins_path_type( DubinsPath* path ) { 240 | return path->type; 241 | } 242 | 243 | void dubins_segment( double t, double qi[3], double qt[3], int type) 244 | { 245 | assert( type == L_SEG || type == S_SEG || type == R_SEG ); 246 | 247 | if( type == L_SEG ) { 248 | qt[0] = qi[0] + sin(qi[2]+t) - sin(qi[2]); 249 | qt[1] = qi[1] - cos(qi[2]+t) + cos(qi[2]); 250 | qt[2] = qi[2] + t; 251 | } 252 | else if( type == R_SEG ) { 253 | qt[0] = qi[0] - sin(qi[2]-t) + sin(qi[2]); 254 | qt[1] = qi[1] + cos(qi[2]-t) - cos(qi[2]); 255 | qt[2] = qi[2] - t; 256 | } 257 | else if( type == S_SEG ) { 258 | qt[0] = qi[0] + cos(qi[2]) * t; 259 | qt[1] = qi[1] + sin(qi[2]) * t; 260 | qt[2] = qi[2]; 261 | } 262 | } 263 | 264 | int dubins_path_sample( DubinsPath* path, double t, double q[3] ) 265 | { 266 | if( t < 0 || t >= dubins_path_length(path) ) { 267 | // error, parameter out of bounds 268 | return EDUBPARAM; 269 | } 270 | 271 | // tprime is the normalised variant of the parameter t 272 | double tprime = t / path->rho; 273 | 274 | // In order to take rho != 1 into account this function needs to be more complex 275 | // than it would be otherwise. The transformation is done in five stages. 276 | // 277 | // 1. translate the components of the initial configuration to the origin 278 | // 2. generate the target configuration 279 | // 3. transform the target configuration 280 | // scale the target configuration 281 | // translate the target configration back to the original starting point 282 | // normalise the target configurations angular component 283 | 284 | // The translated initial configuration 285 | double qi[3] = { 0, 0, path->qi[2] }; 286 | 287 | // Generate the target configuration 288 | const int* types = DIRDATA[path->type]; 289 | double p1 = path->param[0]; 290 | double p2 = path->param[1]; 291 | double q1[3]; // end-of segment 1 292 | double q2[3]; // end-of segment 2 293 | dubins_segment( p1, qi, q1, types[0] ); 294 | dubins_segment( p2, q1, q2, types[1] ); 295 | if( tprime < p1 ) { 296 | dubins_segment( tprime, qi, q, types[0] ); 297 | } 298 | else if( tprime < (p1+p2) ) { 299 | dubins_segment( tprime-p1, q1, q, types[1] ); 300 | } 301 | else { 302 | dubins_segment( tprime-p1-p2, q2, q, types[2] ); 303 | } 304 | 305 | // scale the target configuration, translate back to the original starting point 306 | q[0] = q[0] * path->rho + path->qi[0]; 307 | q[1] = q[1] * path->rho + path->qi[1]; 308 | q[2] = mod2pi(q[2]); 309 | 310 | return 0; 311 | } 312 | 313 | int dubins_path_sample_many( DubinsPath* path, DubinsPathSamplingCallback cb, double stepSize, void* user_data ) 314 | { 315 | double x = 0.0; 316 | double length = dubins_path_length(path); 317 | while( x < length ) { 318 | double q[3]; 319 | dubins_path_sample( path, x, q ); 320 | int retcode = cb(q, x, user_data); 321 | if( retcode != 0 ) { 322 | return retcode; 323 | } 324 | x += stepSize; 325 | } 326 | return 0; 327 | } 328 | 329 | int dubins_path_endpoint( DubinsPath* path, double q[3] ) 330 | { 331 | // TODO - introduce a new constant rather than just using EPSILON 332 | return dubins_path_sample( path, dubins_path_length(path) - EPSILON, q ); 333 | } 334 | 335 | int dubins_extract_subpath( DubinsPath* path, double t, DubinsPath* newpath ) 336 | { 337 | // calculate the true parameter 338 | double tprime = t / path->rho; 339 | 340 | // copy most of the data 341 | newpath->qi[0] = path->qi[0]; 342 | newpath->qi[1] = path->qi[1]; 343 | newpath->qi[2] = path->qi[2]; 344 | newpath->rho = path->rho; 345 | newpath->type = path->type; 346 | 347 | // fix the parameters 348 | newpath->param[0] = fmin( path->param[0], tprime ); 349 | newpath->param[1] = fmin( path->param[1], tprime - newpath->param[0]); 350 | newpath->param[2] = fmin( path->param[2], tprime - newpath->param[0] - newpath->param[1]); 351 | return 0; 352 | } 353 | 354 | 355 | 356 | // using namespace std; 357 | 358 | // namespace ob = ompl::base; 359 | // namespace og = ompl::geometric; 360 | 361 | // void dubins_node(Node4D* node, Node4D* g, float radius) { 362 | 363 | // ob::StateSpacePtr space(new ompl::base::SE2StateSpace()); 364 | 365 | // ob::State* start = space->allocState(); 366 | // ob::State* goal = space->allocState(); 367 | 368 | // auto* s = start->as(); 369 | // s->setX(node->get_x(node->get_size()-1)); 370 | // s->setY(node->get_y(node->get_size()-1)); 371 | // s->setYaw(node->get_yaw(node->get_size()-1)); 372 | 373 | // auto* t = goal->as(); 374 | // t->setX(g->get_x(0)); 375 | // t->setY(g->get_y(0)); 376 | // t->setYaw(g->get_yaw(0)); 377 | 378 | // ob::DubinsStateSpace DP(radius, true); 379 | // auto dubins_path = DP.dubins(start, goal); 380 | // // cout << "Dubins Path: " << dubins_path << endl; 381 | // } -------------------------------------------------------------------------------- /maps/voronoi/cache/13724161401121741605/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 207 6 | 2 7 | 2 8 | 2 9 | 1 10 | 2 11 | 2 12 | 2 13 | 1 14 | 2 15 | 2 16 | 2 17 | 1 18 | 1 19 | 2 20 | 2 21 | 2 22 | 1 23 | 2 24 | 2 25 | 2 26 | 1 27 | 1 28 | 1 29 | 2 30 | 1 31 | 2 32 | 2 33 | 2 34 | 2 35 | 1 36 | 1 37 | 1 38 | 1 39 | 1 40 | 2 41 | 1 42 | 1 43 | 1 44 | 1 45 | 1 46 | 1 47 | 2 48 | 1 49 | 2 50 | 1 51 | 1 52 | 1 53 | 1 54 | 2 55 | 1 56 | 1 57 | 1 58 | 1 59 | 1 60 | 1 61 | 2 62 | 2 63 | 2 64 | 2 65 | 1 66 | 1 67 | 1 68 | 1 69 | 2 70 | 2 71 | 1 72 | 1 73 | 1 74 | 1 75 | 1 76 | 1 77 | 1 78 | 1 79 | 1 80 | 2 81 | 2 82 | 2 83 | 1 84 | 2 85 | 2 86 | 2 87 | 1 88 | 2 89 | 2 90 | 2 91 | 1 92 | 2 93 | 2 94 | 2 95 | 1 96 | 1 97 | 1 98 | 1 99 | 2 100 | 2 101 | 2 102 | 2 103 | 1 104 | 2 105 | 3 106 | 1 107 | 1 108 | 1 109 | 1 110 | 2 111 | 1 112 | 1 113 | 1 114 | 1 115 | 3 116 | 1 117 | 1 118 | 1 119 | 3 120 | 1 121 | 3 122 | 1 123 | 1 124 | 1 125 | 3 126 | 1 127 | 3 128 | 1 129 | 2 130 | 2 131 | 2 132 | 1 133 | 1 134 | 1 135 | 1 136 | 2 137 | 1 138 | 1 139 | 1 140 | 1 141 | 2 142 | 2 143 | 2 144 | 1 145 | 1 146 | 1 147 | 1 148 | 1 149 | 2 150 | 1 151 | 1 152 | 1 153 | 1 154 | 2 155 | 2 156 | 1 157 | 1 158 | 1 159 | 1 160 | 1 161 | 1 162 | 2 163 | 2 164 | 2 165 | 2 166 | 2 167 | 2 168 | 2 169 | 2 170 | 1 171 | 1 172 | 1 173 | 1 174 | 1 175 | 2 176 | 2 177 | 1 178 | 1 179 | 1 180 | 2 181 | 1 182 | 1 183 | 2 184 | 2 185 | 2 186 | 1 187 | 2 188 | 2 189 | 1 190 | 2 191 | 1 192 | 1 193 | 1 194 | 1 195 | 1 196 | 1 197 | 2 198 | 2 199 | 2 200 | 2 201 | 2 202 | 2 203 | 2 204 | 1 205 | 2 206 | 2 207 | 2 208 | 2 209 | 2 210 | 2 211 | 2 212 | 2 213 | 0 214 | 0 215 | 1 216 | 2 217 | 0 218 | 0 219 | 1 220 | 2 221 | 0 222 | 0 223 | 1 224 | 1 225 | 2 226 | 0 227 | 0 228 | 1 229 | 2 230 | 0 231 | 0 232 | 1 233 | 1 234 | 1 235 | 2 236 | 1 237 | 2 238 | 2 239 | 0 240 | 0 241 | 1 242 | 1 243 | 1 244 | 1 245 | 1 246 | 2 247 | 1 248 | 1 249 | 1 250 | 1 251 | 1 252 | 1 253 | 2 254 | 1 255 | 2 256 | 1 257 | 1 258 | 1 259 | 1 260 | 2 261 | 1 262 | 1 263 | 1 264 | 1 265 | 1 266 | 1 267 | 2 268 | 0 269 | 0 270 | 2 271 | 1 272 | 1 273 | 1 274 | 1 275 | 2 276 | 2 277 | 1 278 | 1 279 | 1 280 | 1 281 | 1 282 | 1 283 | 1 284 | 1 285 | 1 286 | 2 287 | 0 288 | 0 289 | 1 290 | 3 291 | 0 292 | 0 293 | 1 294 | 3 295 | 0 296 | 0 297 | 1 298 | 3 299 | 0 300 | 0 301 | 1 302 | 1 303 | 1 304 | 1 305 | 2 306 | 2 307 | 2 308 | 0 309 | 1 310 | 3 311 | 0 312 | 1 313 | 1 314 | 1 315 | 1 316 | 2 317 | 1 318 | 1 319 | 1 320 | 1 321 | 2 322 | 1 323 | 1 324 | 1 325 | 3 326 | 1 327 | 2 328 | 1 329 | 1 330 | 1 331 | 3 332 | 1 333 | 2 334 | 1 335 | 2 336 | 2 337 | 2 338 | 1 339 | 1 340 | 1 341 | 1 342 | 0 343 | 1 344 | 1 345 | 1 346 | 1 347 | 0 348 | 0 349 | 0 350 | 1 351 | 1 352 | 1 353 | 1 354 | 1 355 | 2 356 | 1 357 | 1 358 | 1 359 | 1 360 | 2 361 | 2 362 | 1 363 | 1 364 | 1 365 | 1 366 | 1 367 | 1 368 | 2 369 | 0 370 | 0 371 | 0 372 | 0 373 | 0 374 | 0 375 | 2 376 | 1 377 | 1 378 | 1 379 | 1 380 | 1 381 | 2 382 | 2 383 | 1 384 | 1 385 | 1 386 | 2 387 | 1 388 | 1 389 | 2 390 | 0 391 | 0 392 | 1 393 | 2 394 | 2 395 | 1 396 | 2 397 | 1 398 | 1 399 | 1 400 | 1 401 | 1 402 | 1 403 | 2 404 | 2 405 | 0 406 | 0 407 | 2 408 | 0 409 | 0 410 | 1 411 | 2 412 | 0 413 | 0 414 | 0 415 | 0 416 | 0 417 | 0 418 | 0 419 | 0 420 | 13 421 | 14 422 | 26 423 | 25 424 | 13 425 | 14 426 | 21 427 | 19 428 | 13 429 | 14 430 | 23 431 | 22 432 | 22 433 | 13 434 | 14 435 | 20 436 | 19 437 | 14 438 | 14 439 | 22 440 | 21 441 | 21 442 | 19 443 | 26 444 | 25 445 | 35 446 | 11 447 | 12 448 | 21 449 | 20 450 | 20 451 | 20 452 | 20 453 | 18 454 | 21 455 | 20 456 | 20 457 | 20 458 | 20 459 | 20 460 | 15 461 | 22 462 | 20 463 | 22 464 | 21 465 | 21 466 | 21 467 | 17 468 | 22 469 | 21 470 | 21 471 | 21 472 | 21 473 | 21 474 | 19 475 | 11 476 | 12 477 | 8 478 | 22 479 | 21 480 | 21 481 | 21 482 | 20 483 | 20 484 | 21 485 | 20 486 | 20 487 | 20 488 | 20 489 | 20 490 | 20 491 | 20 492 | 20 493 | 17 494 | 11 495 | 12 496 | 24 497 | 22 498 | 11 499 | 12 500 | 24 501 | 22 502 | 11 503 | 12 504 | 23 505 | 22 506 | 14 507 | 14 508 | 24 509 | 23 510 | 23 511 | 23 512 | 19 513 | 23 514 | 7 515 | 26 516 | 21 517 | 20 518 | 26 519 | 21 520 | 20 521 | 20 522 | 20 523 | 17 524 | 22 525 | 21 526 | 21 527 | 21 528 | 20 529 | 22 530 | 21 531 | 21 532 | 18 533 | 23 534 | 21 535 | 21 536 | 20 537 | 20 538 | 19 539 | 23 540 | 21 541 | 23 542 | 22 543 | 22 544 | 18 545 | 23 546 | 22 547 | 22 548 | 22 549 | 19 550 | 23 551 | 22 552 | 22 553 | 22 554 | 18 555 | 14 556 | 14 557 | 21 558 | 20 559 | 20 560 | 20 561 | 20 562 | 16 563 | 23 564 | 22 565 | 22 566 | 22 567 | 19 568 | 7 569 | 21 570 | 20 571 | 20 572 | 20 573 | 20 574 | 20 575 | 17 576 | 13 577 | 9 578 | 13 579 | 9 580 | 13 581 | 9 582 | 21 583 | 20 584 | 19 585 | 19 586 | 19 587 | 19 588 | 19 589 | 10 590 | 23 591 | 22 592 | 22 593 | 19 594 | 23 595 | 22 596 | 20 597 | 11 598 | 12 599 | 24 600 | 23 601 | 37 602 | 26 603 | 24 604 | 21 605 | 20 606 | 20 607 | 20 608 | 20 609 | 20 610 | 15 611 | 37 612 | 14 613 | 14 614 | 37 615 | 11 616 | 12 617 | 20 618 | 19 619 | 15 620 | 11 621 | 15 622 | 11 623 | 15 624 | 11 625 | 15 626 | 11 627 | 628 | -------------------------------------------------------------------------------- /maps/voronoi/cache/16118496367390915469/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 207 6 | 2 7 | 2 8 | 2 9 | 1 10 | 2 11 | 2 12 | 2 13 | 1 14 | 2 15 | 2 16 | 2 17 | 1 18 | 1 19 | 2 20 | 2 21 | 2 22 | 1 23 | 2 24 | 2 25 | 2 26 | 1 27 | 1 28 | 1 29 | 2 30 | 1 31 | 2 32 | 2 33 | 2 34 | 2 35 | 1 36 | 1 37 | 1 38 | 1 39 | 1 40 | 2 41 | 1 42 | 1 43 | 1 44 | 1 45 | 1 46 | 1 47 | 2 48 | 1 49 | 2 50 | 1 51 | 1 52 | 1 53 | 1 54 | 2 55 | 1 56 | 1 57 | 1 58 | 1 59 | 1 60 | 1 61 | 2 62 | 2 63 | 2 64 | 2 65 | 1 66 | 1 67 | 1 68 | 1 69 | 2 70 | 2 71 | 1 72 | 1 73 | 1 74 | 1 75 | 1 76 | 1 77 | 1 78 | 1 79 | 1 80 | 2 81 | 2 82 | 2 83 | 1 84 | 2 85 | 2 86 | 2 87 | 1 88 | 2 89 | 2 90 | 2 91 | 1 92 | 2 93 | 2 94 | 2 95 | 1 96 | 1 97 | 1 98 | 1 99 | 2 100 | 2 101 | 2 102 | 2 103 | 1 104 | 2 105 | 3 106 | 1 107 | 1 108 | 1 109 | 1 110 | 2 111 | 1 112 | 1 113 | 1 114 | 1 115 | 3 116 | 1 117 | 1 118 | 1 119 | 3 120 | 1 121 | 3 122 | 1 123 | 1 124 | 1 125 | 3 126 | 1 127 | 3 128 | 1 129 | 2 130 | 2 131 | 2 132 | 1 133 | 1 134 | 1 135 | 1 136 | 2 137 | 1 138 | 1 139 | 1 140 | 1 141 | 2 142 | 2 143 | 2 144 | 1 145 | 1 146 | 1 147 | 1 148 | 1 149 | 2 150 | 1 151 | 1 152 | 1 153 | 1 154 | 2 155 | 2 156 | 1 157 | 1 158 | 1 159 | 1 160 | 1 161 | 1 162 | 2 163 | 2 164 | 2 165 | 2 166 | 2 167 | 2 168 | 2 169 | 2 170 | 1 171 | 1 172 | 1 173 | 1 174 | 1 175 | 2 176 | 2 177 | 1 178 | 1 179 | 1 180 | 2 181 | 1 182 | 1 183 | 2 184 | 2 185 | 2 186 | 1 187 | 2 188 | 2 189 | 1 190 | 2 191 | 1 192 | 1 193 | 1 194 | 1 195 | 1 196 | 1 197 | 2 198 | 2 199 | 2 200 | 2 201 | 2 202 | 2 203 | 2 204 | 1 205 | 2 206 | 2 207 | 2 208 | 2 209 | 2 210 | 2 211 | 2 212 | 2 213 | 0 214 | 0 215 | 1 216 | 2 217 | 0 218 | 0 219 | 1 220 | 2 221 | 0 222 | 0 223 | 1 224 | 1 225 | 2 226 | 0 227 | 0 228 | 1 229 | 2 230 | 0 231 | 0 232 | 1 233 | 1 234 | 1 235 | 2 236 | 1 237 | 2 238 | 2 239 | 0 240 | 0 241 | 1 242 | 1 243 | 1 244 | 1 245 | 1 246 | 2 247 | 1 248 | 1 249 | 1 250 | 1 251 | 1 252 | 1 253 | 2 254 | 1 255 | 2 256 | 1 257 | 1 258 | 1 259 | 1 260 | 2 261 | 1 262 | 1 263 | 1 264 | 1 265 | 1 266 | 1 267 | 2 268 | 0 269 | 0 270 | 2 271 | 1 272 | 1 273 | 1 274 | 1 275 | 2 276 | 2 277 | 1 278 | 1 279 | 1 280 | 1 281 | 1 282 | 1 283 | 1 284 | 1 285 | 1 286 | 2 287 | 0 288 | 0 289 | 1 290 | 3 291 | 0 292 | 0 293 | 1 294 | 3 295 | 0 296 | 0 297 | 1 298 | 3 299 | 0 300 | 0 301 | 1 302 | 1 303 | 1 304 | 1 305 | 2 306 | 2 307 | 2 308 | 0 309 | 1 310 | 3 311 | 0 312 | 1 313 | 1 314 | 1 315 | 1 316 | 2 317 | 1 318 | 1 319 | 1 320 | 1 321 | 2 322 | 1 323 | 1 324 | 1 325 | 3 326 | 1 327 | 2 328 | 1 329 | 1 330 | 1 331 | 3 332 | 1 333 | 2 334 | 1 335 | 2 336 | 2 337 | 2 338 | 1 339 | 1 340 | 1 341 | 1 342 | 0 343 | 1 344 | 1 345 | 1 346 | 1 347 | 0 348 | 0 349 | 0 350 | 1 351 | 1 352 | 1 353 | 1 354 | 1 355 | 2 356 | 1 357 | 1 358 | 1 359 | 1 360 | 2 361 | 2 362 | 1 363 | 1 364 | 1 365 | 1 366 | 1 367 | 1 368 | 2 369 | 0 370 | 0 371 | 0 372 | 0 373 | 0 374 | 0 375 | 2 376 | 1 377 | 1 378 | 1 379 | 1 380 | 1 381 | 2 382 | 2 383 | 1 384 | 1 385 | 1 386 | 2 387 | 1 388 | 1 389 | 2 390 | 0 391 | 0 392 | 1 393 | 2 394 | 2 395 | 1 396 | 2 397 | 1 398 | 1 399 | 1 400 | 1 401 | 1 402 | 1 403 | 2 404 | 2 405 | 0 406 | 0 407 | 2 408 | 0 409 | 0 410 | 1 411 | 2 412 | 0 413 | 0 414 | 0 415 | 0 416 | 0 417 | 0 418 | 0 419 | 0 420 | 13 421 | 14 422 | 26 423 | 25 424 | 13 425 | 14 426 | 21 427 | 19 428 | 13 429 | 14 430 | 23 431 | 22 432 | 22 433 | 13 434 | 14 435 | 20 436 | 19 437 | 14 438 | 14 439 | 22 440 | 21 441 | 21 442 | 19 443 | 26 444 | 25 445 | 35 446 | 11 447 | 12 448 | 21 449 | 20 450 | 20 451 | 20 452 | 20 453 | 18 454 | 21 455 | 20 456 | 20 457 | 20 458 | 20 459 | 20 460 | 15 461 | 22 462 | 20 463 | 22 464 | 21 465 | 21 466 | 21 467 | 17 468 | 22 469 | 21 470 | 21 471 | 21 472 | 21 473 | 21 474 | 19 475 | 11 476 | 12 477 | 8 478 | 22 479 | 21 480 | 21 481 | 21 482 | 20 483 | 20 484 | 21 485 | 20 486 | 20 487 | 20 488 | 20 489 | 20 490 | 20 491 | 20 492 | 20 493 | 17 494 | 11 495 | 12 496 | 24 497 | 22 498 | 11 499 | 12 500 | 24 501 | 22 502 | 11 503 | 12 504 | 23 505 | 22 506 | 14 507 | 14 508 | 24 509 | 23 510 | 23 511 | 23 512 | 19 513 | 23 514 | 7 515 | 26 516 | 21 517 | 20 518 | 26 519 | 21 520 | 20 521 | 20 522 | 20 523 | 17 524 | 22 525 | 21 526 | 21 527 | 21 528 | 20 529 | 22 530 | 21 531 | 21 532 | 18 533 | 23 534 | 21 535 | 21 536 | 20 537 | 20 538 | 19 539 | 23 540 | 21 541 | 23 542 | 22 543 | 22 544 | 18 545 | 23 546 | 22 547 | 22 548 | 22 549 | 19 550 | 23 551 | 22 552 | 22 553 | 22 554 | 18 555 | 14 556 | 14 557 | 21 558 | 20 559 | 20 560 | 20 561 | 20 562 | 16 563 | 23 564 | 22 565 | 22 566 | 22 567 | 19 568 | 7 569 | 21 570 | 20 571 | 20 572 | 20 573 | 20 574 | 20 575 | 17 576 | 13 577 | 9 578 | 13 579 | 9 580 | 13 581 | 9 582 | 21 583 | 20 584 | 19 585 | 19 586 | 19 587 | 19 588 | 19 589 | 10 590 | 23 591 | 22 592 | 22 593 | 19 594 | 23 595 | 22 596 | 20 597 | 11 598 | 12 599 | 24 600 | 23 601 | 37 602 | 26 603 | 24 604 | 21 605 | 20 606 | 20 607 | 20 608 | 20 609 | 20 610 | 15 611 | 37 612 | 14 613 | 14 614 | 37 615 | 11 616 | 12 617 | 20 618 | 19 619 | 15 620 | 11 621 | 15 622 | 11 623 | 15 624 | 11 625 | 15 626 | 11 627 | 628 | -------------------------------------------------------------------------------- /maps/voronoi/cache/9584077836908302785/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 207 6 | 2 7 | 2 8 | 2 9 | 1 10 | 2 11 | 2 12 | 2 13 | 1 14 | 2 15 | 2 16 | 2 17 | 1 18 | 1 19 | 2 20 | 2 21 | 2 22 | 1 23 | 2 24 | 2 25 | 2 26 | 1 27 | 1 28 | 1 29 | 2 30 | 1 31 | 2 32 | 2 33 | 2 34 | 2 35 | 1 36 | 1 37 | 1 38 | 1 39 | 1 40 | 2 41 | 1 42 | 1 43 | 1 44 | 1 45 | 1 46 | 1 47 | 2 48 | 1 49 | 2 50 | 1 51 | 1 52 | 1 53 | 1 54 | 2 55 | 1 56 | 1 57 | 1 58 | 1 59 | 1 60 | 1 61 | 2 62 | 2 63 | 2 64 | 2 65 | 1 66 | 1 67 | 1 68 | 1 69 | 2 70 | 2 71 | 1 72 | 1 73 | 1 74 | 1 75 | 1 76 | 1 77 | 1 78 | 1 79 | 1 80 | 2 81 | 2 82 | 1 83 | 2 84 | 2 85 | 2 86 | 1 87 | 2 88 | 2 89 | 2 90 | 1 91 | 2 92 | 2 93 | 2 94 | 2 95 | 1 96 | 1 97 | 1 98 | 1 99 | 2 100 | 2 101 | 2 102 | 2 103 | 1 104 | 2 105 | 2 106 | 1 107 | 1 108 | 1 109 | 1 110 | 2 111 | 1 112 | 1 113 | 1 114 | 1 115 | 2 116 | 2 117 | 2 118 | 1 119 | 1 120 | 1 121 | 1 122 | 2 123 | 1 124 | 1 125 | 1 126 | 1 127 | 3 128 | 1 129 | 1 130 | 1 131 | 3 132 | 1 133 | 3 134 | 1 135 | 1 136 | 1 137 | 3 138 | 1 139 | 3 140 | 1 141 | 2 142 | 2 143 | 2 144 | 1 145 | 1 146 | 1 147 | 1 148 | 1 149 | 2 150 | 1 151 | 1 152 | 1 153 | 1 154 | 2 155 | 2 156 | 1 157 | 1 158 | 1 159 | 1 160 | 1 161 | 1 162 | 2 163 | 2 164 | 2 165 | 2 166 | 2 167 | 2 168 | 2 169 | 2 170 | 1 171 | 1 172 | 1 173 | 1 174 | 1 175 | 2 176 | 2 177 | 1 178 | 1 179 | 1 180 | 2 181 | 1 182 | 1 183 | 2 184 | 2 185 | 2 186 | 1 187 | 2 188 | 2 189 | 1 190 | 2 191 | 1 192 | 1 193 | 1 194 | 1 195 | 1 196 | 1 197 | 2 198 | 2 199 | 2 200 | 2 201 | 2 202 | 2 203 | 2 204 | 1 205 | 2 206 | 2 207 | 2 208 | 2 209 | 2 210 | 2 211 | 2 212 | 2 213 | 0 214 | 0 215 | 1 216 | 2 217 | 0 218 | 0 219 | 1 220 | 2 221 | 0 222 | 0 223 | 1 224 | 1 225 | 2 226 | 0 227 | 0 228 | 1 229 | 2 230 | 0 231 | 0 232 | 1 233 | 1 234 | 1 235 | 2 236 | 1 237 | 2 238 | 2 239 | 0 240 | 0 241 | 1 242 | 1 243 | 1 244 | 1 245 | 1 246 | 2 247 | 1 248 | 1 249 | 1 250 | 1 251 | 1 252 | 1 253 | 2 254 | 1 255 | 2 256 | 1 257 | 1 258 | 1 259 | 1 260 | 2 261 | 1 262 | 1 263 | 1 264 | 1 265 | 1 266 | 1 267 | 2 268 | 0 269 | 0 270 | 2 271 | 1 272 | 1 273 | 1 274 | 1 275 | 2 276 | 2 277 | 1 278 | 1 279 | 1 280 | 1 281 | 1 282 | 1 283 | 1 284 | 1 285 | 1 286 | 2 287 | 0 288 | 1 289 | 3 290 | 0 291 | 0 292 | 1 293 | 3 294 | 0 295 | 0 296 | 1 297 | 3 298 | 0 299 | 0 300 | 0 301 | 1 302 | 1 303 | 1 304 | 1 305 | 2 306 | 2 307 | 2 308 | 0 309 | 1 310 | 3 311 | 0 312 | 1 313 | 1 314 | 1 315 | 1 316 | 2 317 | 1 318 | 1 319 | 1 320 | 1 321 | 3 322 | 2 323 | 2 324 | 1 325 | 1 326 | 1 327 | 1 328 | 0 329 | 1 330 | 1 331 | 1 332 | 1 333 | 0 334 | 1 335 | 1 336 | 1 337 | 3 338 | 1 339 | 2 340 | 1 341 | 1 342 | 1 343 | 3 344 | 1 345 | 2 346 | 1 347 | 2 348 | 0 349 | 0 350 | 1 351 | 1 352 | 1 353 | 1 354 | 1 355 | 2 356 | 1 357 | 1 358 | 1 359 | 1 360 | 2 361 | 2 362 | 1 363 | 1 364 | 1 365 | 1 366 | 1 367 | 1 368 | 2 369 | 0 370 | 0 371 | 0 372 | 0 373 | 0 374 | 0 375 | 2 376 | 1 377 | 1 378 | 1 379 | 1 380 | 1 381 | 2 382 | 2 383 | 1 384 | 1 385 | 1 386 | 2 387 | 1 388 | 1 389 | 2 390 | 0 391 | 0 392 | 1 393 | 2 394 | 2 395 | 1 396 | 2 397 | 1 398 | 1 399 | 1 400 | 1 401 | 1 402 | 1 403 | 2 404 | 2 405 | 0 406 | 0 407 | 2 408 | 0 409 | 0 410 | 1 411 | 2 412 | 0 413 | 0 414 | 0 415 | 0 416 | 0 417 | 0 418 | 0 419 | 0 420 | 13 421 | 14 422 | 26 423 | 25 424 | 13 425 | 14 426 | 21 427 | 19 428 | 13 429 | 14 430 | 23 431 | 22 432 | 22 433 | 13 434 | 14 435 | 20 436 | 19 437 | 14 438 | 14 439 | 22 440 | 21 441 | 21 442 | 19 443 | 26 444 | 25 445 | 35 446 | 11 447 | 12 448 | 21 449 | 20 450 | 20 451 | 20 452 | 20 453 | 18 454 | 21 455 | 20 456 | 20 457 | 20 458 | 20 459 | 20 460 | 15 461 | 22 462 | 20 463 | 22 464 | 21 465 | 21 466 | 21 467 | 17 468 | 22 469 | 21 470 | 21 471 | 21 472 | 21 473 | 21 474 | 19 475 | 11 476 | 12 477 | 8 478 | 22 479 | 21 480 | 21 481 | 21 482 | 20 483 | 20 484 | 22 485 | 21 486 | 21 487 | 21 488 | 21 489 | 21 490 | 21 491 | 21 492 | 21 493 | 14 494 | 12 495 | 23 496 | 21 497 | 13 498 | 12 499 | 23 500 | 21 501 | 13 502 | 12 503 | 23 504 | 21 505 | 13 506 | 14 507 | 14 508 | 24 509 | 23 510 | 23 511 | 23 512 | 19 513 | 23 514 | 7 515 | 23 516 | 22 517 | 21 518 | 23 519 | 22 520 | 21 521 | 21 522 | 21 523 | 19 524 | 21 525 | 20 526 | 20 527 | 20 528 | 16 529 | 22 530 | 18 531 | 23 532 | 22 533 | 22 534 | 22 535 | 19 536 | 23 537 | 22 538 | 22 539 | 22 540 | 18 541 | 23 542 | 22 543 | 22 544 | 22 545 | 22 546 | 21 547 | 23 548 | 22 549 | 22 550 | 22 551 | 22 552 | 21 553 | 22 554 | 21 555 | 14 556 | 14 557 | 21 558 | 20 559 | 20 560 | 20 561 | 20 562 | 16 563 | 23 564 | 22 565 | 22 566 | 22 567 | 19 568 | 7 569 | 21 570 | 20 571 | 20 572 | 20 573 | 20 574 | 20 575 | 17 576 | 14 577 | 10 578 | 14 579 | 10 580 | 14 581 | 10 582 | 21 583 | 20 584 | 19 585 | 19 586 | 19 587 | 19 588 | 19 589 | 10 590 | 23 591 | 22 592 | 22 593 | 19 594 | 23 595 | 22 596 | 20 597 | 11 598 | 12 599 | 24 600 | 23 601 | 37 602 | 26 603 | 24 604 | 21 605 | 20 606 | 20 607 | 20 608 | 20 609 | 20 610 | 15 611 | 37 612 | 14 613 | 14 614 | 37 615 | 11 616 | 12 617 | 20 618 | 19 619 | 15 620 | 11 621 | 15 622 | 11 623 | 15 624 | 11 625 | 15 626 | 11 627 | 628 | -------------------------------------------------------------------------------- /maps/voronoi/cache/6375780720344636208/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 210 6 | 2 7 | 2 8 | 2 9 | 2 10 | 2 11 | 2 12 | 2 13 | 2 14 | 2 15 | 2 16 | 2 17 | 1 18 | 2 19 | 3 20 | 3 21 | 2 22 | 1 23 | 1 24 | 2 25 | 2 26 | 2 27 | 2 28 | 2 29 | 1 30 | 2 31 | 2 32 | 2 33 | 2 34 | 3 35 | 1 36 | 3 37 | 2 38 | 1 39 | 2 40 | 2 41 | 2 42 | 2 43 | 1 44 | 2 45 | 2 46 | 1 47 | 2 48 | 1 49 | 2 50 | 2 51 | 1 52 | 1 53 | 2 54 | 1 55 | 1 56 | 1 57 | 2 58 | 1 59 | 1 60 | 1 61 | 1 62 | 2 63 | 2 64 | 2 65 | 1 66 | 1 67 | 2 68 | 2 69 | 1 70 | 1 71 | 2 72 | 2 73 | 1 74 | 1 75 | 1 76 | 1 77 | 1 78 | 3 79 | 3 80 | 1 81 | 3 82 | 3 83 | 3 84 | 3 85 | 1 86 | 3 87 | 3 88 | 3 89 | 3 90 | 1 91 | 3 92 | 3 93 | 2 94 | 2 95 | 2 96 | 2 97 | 2 98 | 2 99 | 1 100 | 1 101 | 1 102 | 2 103 | 2 104 | 2 105 | 2 106 | 2 107 | 2 108 | 2 109 | 1 110 | 1 111 | 2 112 | 1 113 | 1 114 | 2 115 | 2 116 | 2 117 | 1 118 | 1 119 | 2 120 | 1 121 | 1 122 | 3 123 | 1 124 | 3 125 | 1 126 | 3 127 | 1 128 | 3 129 | 1 130 | 3 131 | 1 132 | 2 133 | 1 134 | 1 135 | 2 136 | 1 137 | 1 138 | 1 139 | 2 140 | 2 141 | 1 142 | 1 143 | 1 144 | 1 145 | 2 146 | 2 147 | 2 148 | 2 149 | 2 150 | 2 151 | 1 152 | 2 153 | 3 154 | 3 155 | 3 156 | 3 157 | 3 158 | 3 159 | 3 160 | 3 161 | 3 162 | 2 163 | 2 164 | 1 165 | 1 166 | 2 167 | 2 168 | 1 169 | 1 170 | 2 171 | 1 172 | 1 173 | 2 174 | 2 175 | 2 176 | 1 177 | 2 178 | 1 179 | 1 180 | 1 181 | 2 182 | 2 183 | 1 184 | 2 185 | 1 186 | 2 187 | 1 188 | 2 189 | 1 190 | 2 191 | 2 192 | 2 193 | 2 194 | 2 195 | 2 196 | 2 197 | 3 198 | 3 199 | 3 200 | 2 201 | 2 202 | 2 203 | 2 204 | 2 205 | 2 206 | 2 207 | 2 208 | 2 209 | 2 210 | 2 211 | 2 212 | 2 213 | 2 214 | 2 215 | 2 216 | 0 217 | 2 218 | 0 219 | 0 220 | 2 221 | 0 222 | 0 223 | 2 224 | 0 225 | 0 226 | 1 227 | 2 228 | 0 229 | 0 230 | 0 231 | 1 232 | 1 233 | 2 234 | 2 235 | 0 236 | 0 237 | 0 238 | 1 239 | 2 240 | 2 241 | 0 242 | 0 243 | 0 244 | 1 245 | 2 246 | 0 247 | 1 248 | 2 249 | 0 250 | 2 251 | 0 252 | 1 253 | 2 254 | 0 255 | 1 256 | 2 257 | 1 258 | 2 259 | 2 260 | 1 261 | 1 262 | 2 263 | 1 264 | 1 265 | 1 266 | 2 267 | 1 268 | 1 269 | 1 270 | 1 271 | 2 272 | 0 273 | 2 274 | 1 275 | 1 276 | 2 277 | 2 278 | 1 279 | 1 280 | 2 281 | 2 282 | 1 283 | 1 284 | 1 285 | 1 286 | 1 287 | 2 288 | 0 289 | 1 290 | 3 291 | 0 292 | 0 293 | 0 294 | 1 295 | 3 296 | 0 297 | 0 298 | 0 299 | 1 300 | 3 301 | 0 302 | 0 303 | 0 304 | 0 305 | 0 306 | 0 307 | 2 308 | 1 309 | 1 310 | 1 311 | 2 312 | 0 313 | 2 314 | 2 315 | 0 316 | 3 317 | 0 318 | 1 319 | 1 320 | 2 321 | 1 322 | 1 323 | 3 324 | 2 325 | 2 326 | 1 327 | 1 328 | 0 329 | 1 330 | 1 331 | 0 332 | 1 333 | 3 334 | 1 335 | 3 336 | 1 337 | 3 338 | 1 339 | 3 340 | 1 341 | 3 342 | 1 343 | 1 344 | 2 345 | 1 346 | 1 347 | 1 348 | 2 349 | 2 350 | 1 351 | 1 352 | 1 353 | 1 354 | 2 355 | 0 356 | 0 357 | 2 358 | 0 359 | 0 360 | 1 361 | 2 362 | 0 363 | 0 364 | 0 365 | 0 366 | 0 367 | 0 368 | 0 369 | 0 370 | 0 371 | 0 372 | 2 373 | 1 374 | 1 375 | 2 376 | 2 377 | 1 378 | 1 379 | 2 380 | 1 381 | 1 382 | 2 383 | 2 384 | 2 385 | 1 386 | 2 387 | 1 388 | 1 389 | 1 390 | 2 391 | 0 392 | 1 393 | 2 394 | 1 395 | 2 396 | 1 397 | 3 398 | 1 399 | 2 400 | 2 401 | 0 402 | 2 403 | 2 404 | 0 405 | 0 406 | 2 407 | 0 408 | 0 409 | 0 410 | 0 411 | 2 412 | 0 413 | 0 414 | 0 415 | 2 416 | 0 417 | 0 418 | 0 419 | 0 420 | 0 421 | 0 422 | 0 423 | 0 424 | 0 425 | 0 426 | 23 427 | 44 428 | 24 429 | 23 430 | 44 431 | 24 432 | 38 433 | 51 434 | 39 435 | 38 436 | 42 437 | 41 438 | 39 439 | 48 440 | 49 441 | 37 442 | 36 443 | 36 444 | 24 445 | 48 446 | 44 447 | 46 448 | 41 449 | 40 450 | 24 451 | 48 452 | 44 453 | 46 454 | 37 455 | 35 456 | 46 457 | 32 458 | 31 459 | 21 460 | 51 461 | 24 462 | 37 463 | 35 464 | 35 465 | 39 466 | 37 467 | 47 468 | 45 469 | 50 470 | 40 471 | 39 472 | 37 473 | 34 474 | 33 475 | 33 476 | 33 477 | 37 478 | 36 479 | 36 480 | 36 481 | 33 482 | 35 483 | 41 484 | 34 485 | 33 486 | 33 487 | 8 488 | 35 489 | 34 490 | 34 491 | 20 492 | 35 493 | 34 494 | 34 495 | 34 496 | 34 497 | 29 498 | 38 499 | 37 500 | 35 501 | 38 502 | 39 503 | 38 504 | 37 505 | 35 506 | 38 507 | 39 508 | 38 509 | 37 510 | 35 511 | 38 512 | 39 513 | 30 514 | 25 515 | 44 516 | 44 517 | 59 518 | 38 519 | 37 520 | 37 521 | 35 522 | 42 523 | 23 524 | 7 525 | 23 526 | 41 527 | 23 528 | 35 529 | 34 530 | 33 531 | 33 532 | 32 533 | 32 534 | 22 535 | 18 536 | 37 537 | 36 538 | 33 539 | 36 540 | 35 541 | 34 542 | 41 543 | 39 544 | 37 545 | 35 546 | 41 547 | 39 548 | 37 549 | 35 550 | 37 551 | 35 552 | 36 553 | 35 554 | 35 555 | 39 556 | 38 557 | 38 558 | 37 559 | 7 560 | 35 561 | 34 562 | 34 563 | 34 564 | 32 565 | 44 566 | 44 567 | 59 568 | 41 569 | 28 570 | 38 571 | 37 572 | 29 573 | 35 574 | 38 575 | 39 576 | 35 577 | 38 578 | 39 579 | 35 580 | 38 581 | 39 582 | 21 583 | 38 584 | 37 585 | 37 586 | 10 587 | 33 588 | 32 589 | 31 590 | 36 591 | 35 592 | 35 593 | 46 594 | 37 595 | 32 596 | 31 597 | 34 598 | 33 599 | 33 600 | 33 601 | 38 602 | 42 603 | 41 604 | 40 605 | 39 606 | 37 607 | 36 608 | 36 609 | 35 610 | 50 611 | 38 612 | 51 613 | 44 614 | 25 615 | 22 616 | 43 617 | 46 618 | 49 619 | 45 620 | 48 621 | 24 622 | 44 623 | 46 624 | 48 625 | 24 626 | 44 627 | 46 628 | 40 629 | 35 630 | 40 631 | 35 632 | 25 633 | 20 634 | 25 635 | 20 636 | 637 | -------------------------------------------------------------------------------- /src/node4d.cpp: -------------------------------------------------------------------------------- 1 | #include "../include/hybrid_astar/node4d.h" 2 | 3 | using namespace std; 4 | 5 | jsk_recognition_msgs::PolygonArray system_polygons; 6 | 7 | /* 8 | Function to check point collision 9 | 10 | bin_map: A 2D binary obstacle map 11 | 12 | Returns a boolean, true for collision, false otherwise 13 | */ 14 | bool Node4D::check_path_collision(bool** bin_map) { 15 | 16 | for (int i = 0; i < xlist.capacity(); ++i) 17 | { 18 | if(bin_map[(int)round(xlist[i]/XY_RESOLUTION)][(int)round(ylist[i]/XY_RESOLUTION)]) { 19 | ROS_INFO("IN COLLISION!"); 20 | return true; 21 | } 22 | } 23 | 24 | ROS_INFO("NO COLLISION!"); 25 | return false; // NO collision 26 | } 27 | 28 | /* 29 | Function to check node collision 30 | 31 | grid: Pointer to the occupancy grid msg 32 | bin_map: A 2D binary obstacle map 33 | 34 | Returns: boolean, true for collision, false otherwise 35 | */ 36 | bool Node4D::check_collision(nav_msgs::OccupancyGrid::Ptr grid, bool** bin_map, int** acc_obs_map) { 37 | 38 | int max_x; 39 | int min_x; 40 | int max_y; 41 | int min_y; 42 | 43 | float deltar; 44 | float deltat; 45 | 46 | int s; 47 | int t; 48 | 49 | visualization_msgs::Marker robot_collision_check_points; 50 | visualization_msgs::Marker trailer_collision_check_points; 51 | 52 | // Robot/Tractor Collision Check Variables 53 | robot_collision_check_points.header.stamp = ros::Time::now(); 54 | robot_collision_check_points.header.frame_id = "/map"; 55 | robot_collision_check_points.ns = "robot_collision_check_points"; 56 | robot_collision_check_points.action = visualization_msgs::Marker::ADD; 57 | robot_collision_check_points.id = 0; 58 | robot_collision_check_points.type = visualization_msgs::Marker::POINTS; 59 | robot_collision_check_points.scale.x = 0.05; 60 | robot_collision_check_points.scale.y = 0.05; 61 | robot_collision_check_points.color.g = 1.0; 62 | robot_collision_check_points.color.a = 1.0; 63 | geometry_msgs::Point robot_collision_check_point; 64 | 65 | float cx; // Center x of the robot 66 | float cy; // Center y of the robot 67 | 68 | deltar = (RF - RB) / 2.0; 69 | 70 | // Trailer Collision Check Variables 71 | trailer_collision_check_points.header.stamp = ros::Time::now(); 72 | trailer_collision_check_points.header.frame_id = "/map"; 73 | trailer_collision_check_points.ns = "trailer_collision_check_points"; 74 | trailer_collision_check_points.action = visualization_msgs::Marker::ADD; 75 | trailer_collision_check_points.id = 0; 76 | trailer_collision_check_points.type = visualization_msgs::Marker::POINTS; 77 | trailer_collision_check_points.scale.x = 0.05; 78 | trailer_collision_check_points.scale.y = 0.05; 79 | trailer_collision_check_points.color.b = 1.0; 80 | trailer_collision_check_points.color.a = 1.0; 81 | geometry_msgs::Point trailer_collision_check_point; 82 | 83 | float ctx; // Center x of the trailer 84 | float cty; // Center y of the trailer 85 | 86 | deltat = (RTF - RTB) / 2.0; 87 | 88 | for (int i = 0; i < xlist.capacity(); ++i) { 89 | 90 | // printf("xlist: %f ylist: %f yaw: %f yawt: %f yaw_t: %f \n", xlist[i], ylist[i], yawlist[i], yawtlist[i], yawt[i]); 91 | // cout << "Press ENTER for collision check " << i << endl; 92 | // cin.get(); 93 | 94 | // Checking for jackknifing 95 | if(abs(abs(yawlist[i] - yawt[i]) - 3.14) <= 1.744) { 96 | // ROS_INFO("SELF-COLLISION - JACKNIFE"); 97 | return true; 98 | } 99 | 100 | // Computing center of tractor from hitch position 101 | cx = xlist[i] + deltar * cos(yawlist[i]); 102 | cy = ylist[i] + deltar * sin(yawlist[i]); 103 | 104 | // Visualize robot center 105 | if(visualization) { 106 | geometry_msgs::PointStamped robot_center; 107 | robot_center.header.stamp = ros::Time::now(); 108 | robot_center.header.frame_id = "/map"; 109 | robot_center.point.x = xlist[i]; 110 | robot_center.point.y = ylist[i]; 111 | robot_center_pub.publish(robot_center); 112 | robot_polygon_pub.publish(create_polygon(RL, RW, cx, cy, yawlist[i])); 113 | } 114 | 115 | // Checking for out of bounds robot state 116 | if(xlist[i] >= grid->info.width || xlist[i]<0 || ylist[i] >= grid->info.height || ylist[i] < 0) { 117 | // ROS_INFO("ROBOT OUT OF BOUNDS"); 118 | return true; // OUT OF BOUNDS 119 | } 120 | 121 | max_x = (cx + RL * abs(cos(yawlist[i]))/2 + RW * abs(sin(yawlist[i]))/2) + MIN_SAFE_DIST; 122 | min_x = (cx - RL * abs(cos(yawlist[i]))/2 - RW * abs(sin(yawlist[i]))/2) - MIN_SAFE_DIST; 123 | 124 | max_y = (cy + RL * abs(sin(yawlist[i]))/2 + RW * abs(cos(yawlist[i]))/2) + MIN_SAFE_DIST; 125 | min_y = (cy - RL * abs(sin(yawlist[i]))/2 - RW * abs(cos(yawlist[i]))/2) - MIN_SAFE_DIST; 126 | 127 | if(max_x >= grid->info.width || min_x < 0 || max_y >= grid->info.height || min_y < 0) { 128 | // ROS_INFO("ROBOT OUT OF BOUNDS"); 129 | return true; // OUT OF BOUNDS 130 | } 131 | 132 | // Checking the robot polygon for collision 133 | for(float k = -RL/2; k <= RL/2 + MIN_SAFE_DIST; k += RL/4) { 134 | for(float j = -RW/2 - MIN_SAFE_DIST; j <= RW/2 + MIN_SAFE_DIST; j += RW/4) { 135 | 136 | // Top Right 137 | s = (cx + (k * cos(yawlist[i])) - (j * sin(yawlist[i])))/XY_RESOLUTION; 138 | t = (cy + (k * sin(yawlist[i])) + (j * cos(yawlist[i])))/XY_RESOLUTION; 139 | 140 | // robot_collision_check_point.x = s * XY_RESOLUTION; 141 | // robot_collision_check_point.y = t * XY_RESOLUTION; 142 | // robot_collision_check_points.points.push_back(robot_collision_check_point); 143 | // robot_collision_check_pub.publish(robot_collision_check_points); 144 | 145 | if(bin_map[s][t] != 0) { 146 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 147 | // robot_collision_check_pub.publish(robot_collision_check_points); 148 | // ROS_INFO("ROBOT POLYGON COLLISION"); 149 | return true; // IN COLLISION 150 | } 151 | 152 | // Top Left 153 | s = (cx - (k * cos(yawlist[i])) - (j * sin(yawlist[i])))/XY_RESOLUTION; 154 | t = (cy - (k * sin(yawlist[i])) + (j * cos(yawlist[i])))/XY_RESOLUTION; 155 | 156 | // robot_collision_check_point.x = s * XY_RESOLUTION; 157 | // robot_collision_check_point.y = t * XY_RESOLUTION; 158 | // robot_collision_check_points.points.push_back(robot_collision_check_point); 159 | // robot_collision_check_pub.publish(robot_collision_check_points); 160 | 161 | if(bin_map[s][t] != 0) { 162 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 163 | // robot_collision_check_pub.publish(robot_collision_check_points); 164 | // ROS_INFO("ROBOT POLYGON COLLISION"); 165 | return true; // IN COLLISION 166 | } 167 | 168 | // Bottom Left 169 | s = (cx - (k * cos(yawlist[i])) + (j * sin(yawlist[i])))/XY_RESOLUTION; 170 | t = (cy - (k * sin(yawlist[i])) - (j * cos(yawlist[i])))/XY_RESOLUTION; 171 | 172 | // robot_collision_check_point.x = s * XY_RESOLUTION; 173 | // robot_collision_check_point.y = t * XY_RESOLUTION; 174 | // robot_collision_check_points.points.push_back(robot_collision_check_point); 175 | // robot_collision_check_pub.publish(robot_collision_check_points); 176 | 177 | if(bin_map[s][t] != 0) { 178 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 179 | // robot_collision_check_pub.publish(robot_collision_check_points); 180 | // ROS_INFO("ROBOT POLYGON COLLISION"); 181 | return true; // IN COLLISION 182 | } 183 | 184 | // Bottom Right 185 | s = (cx + (k * cos(yawlist[i])) + (j * sin(yawlist[i])))/XY_RESOLUTION; 186 | t = (cy + (k * sin(yawlist[i])) - (j * cos(yawlist[i])))/XY_RESOLUTION; 187 | 188 | // robot_collision_check_point.x = s * XY_RESOLUTION; 189 | // robot_collision_check_point.y = t * XY_RESOLUTION; 190 | // robot_collision_check_points.points.push_back(robot_collision_check_point); 191 | // robot_collision_check_pub.publish(robot_collision_check_points); 192 | 193 | if(bin_map[s][t] != 0) { 194 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 195 | // robot_collision_check_pub.publish(robot_collision_check_points); 196 | // ROS_INFO("ROBOT POLYGON COLLISION"); 197 | return true; // IN COLLISION 198 | } 199 | } 200 | } 201 | 202 | // ROS_INFO("Trailer Collision check for X : %f || Y : %f ", xlist[i], ylist[i]); 203 | 204 | // Computing trailer center from hitch position 205 | ctx = xlist[i] + deltat * cos(yawt[i]); 206 | cty = ylist[i] + deltat * sin(yawt[i]); 207 | 208 | // Visualize trailer center 209 | if(visualization) { 210 | geometry_msgs::PointStamped trailer_center; 211 | trailer_center.header.stamp = ros::Time::now(); 212 | trailer_center.header.frame_id = "/map"; 213 | trailer_center.point.x = ctx; 214 | trailer_center.point.y = cty; 215 | trailer_center_pub.publish(trailer_center); 216 | trailer_polygon_pub.publish(create_polygon(TL, TW, ctx, cty, yawt[i])); 217 | } 218 | 219 | max_x = (ctx + TL * (cos(yawt[i]))/2 + TW * (sin(yawt[i]))/2) + MIN_SAFE_DIST; 220 | min_x = (ctx - TL * (cos(yawt[i]))/2 - TW * (sin(yawt[i]))/2) - MIN_SAFE_DIST; 221 | 222 | max_y = (cty + TL * (sin(yawt[i]))/2 + TW * (cos(yawt[i]))/2) + MIN_SAFE_DIST; 223 | min_y = (cty - TL * (sin(yawt[i]))/2 - TW * (cos(yawt[i]))/2) - MIN_SAFE_DIST; 224 | 225 | if(max_x >= grid->info.width || min_x < 0 || max_y >= grid->info.height || min_y < 0) { 226 | // ROS_INFO("TRAILER OUT OF BOUNDS"); 227 | return true; // OUT OF BOUNDS 228 | } 229 | 230 | // Checking the trailer polygon/rectangle 231 | for(float k = -TL/2 - MIN_SAFE_DIST; k <= TL/2 + MIN_SAFE_DIST; k += TL/4) { 232 | for(float j = -TW/2 - MIN_SAFE_DIST; j <= TW/2 + MIN_SAFE_DIST; j += TW/4) { 233 | 234 | // Top Right 235 | s = (ctx + (k * cos(yawt[i])) - (j * sin(yawt[i])))/XY_RESOLUTION; 236 | t = (cty + (k * sin(yawt[i])) + (j * cos(yawt[i])))/XY_RESOLUTION; 237 | 238 | // trailer_collision_check_point.x = s * XY_RESOLUTION; 239 | // trailer_collision_check_point.y = t * XY_RESOLUTION; 240 | // trailer_collision_check_points.points.push_back(trailer_collision_check_point); 241 | // trailer_collision_check_pub.publish(trailer_collision_check_points); 242 | 243 | if(bin_map[s][t] != 0) { 244 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 245 | // robot_collision_check_pub.publish(robot_collision_check_points); 246 | // ROS_INFO("ROBOT POLYGON COLLISION"); 247 | return true; // IN COLLISION 248 | } 249 | 250 | // Top Left 251 | s = (ctx - (k * cos(yawt[i])) - (j * sin(yawt[i])))/XY_RESOLUTION; 252 | t = (cty - (k * sin(yawt[i])) + (j * cos(yawt[i])))/XY_RESOLUTION; 253 | 254 | // trailer_collision_check_point.x = s * XY_RESOLUTION; 255 | // trailer_collision_check_point.y = t * XY_RESOLUTION; 256 | // trailer_collision_check_points.points.push_back(trailer_collision_check_point); 257 | // trailer_collision_check_pub.publish(trailer_collision_check_points); 258 | 259 | if(bin_map[s][t] != 0) { 260 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 261 | // robot_collision_check_pub.publish(robot_collision_check_points); 262 | // ROS_INFO("ROBOT POLYGON COLLISION"); 263 | return true; // IN COLLISION 264 | } 265 | 266 | // Bottom Left 267 | s = (ctx - (k * cos(yawt[i])) + (j * sin(yawt[i])))/XY_RESOLUTION; 268 | t = (cty - (k * sin(yawt[i])) - (j * cos(yawt[i])))/XY_RESOLUTION; 269 | 270 | // trailer_collision_check_point.x = s * XY_RESOLUTION; 271 | // trailer_collision_check_point.y = t * XY_RESOLUTION; 272 | // trailer_collision_check_points.points.push_back(trailer_collision_check_point); 273 | // trailer_collision_check_pub.publish(trailer_collision_check_points); 274 | 275 | if(bin_map[s][t] != 0) { 276 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 277 | // robot_collision_check_pub.publish(robot_collision_check_points); 278 | // ROS_INFO("ROBOT POLYGON COLLISION"); 279 | return true; // IN COLLISION 280 | } 281 | 282 | // Bottom Right 283 | s = (ctx + (k * cos(yawt[i])) + (j * sin(yawt[i])))/XY_RESOLUTION; 284 | t = (cty + (k * sin(yawt[i])) - (j * cos(yawt[i])))/XY_RESOLUTION; 285 | 286 | // trailer_collision_check_point.x = s * XY_RESOLUTION; 287 | // trailer_collision_check_point.y = t * XY_RESOLUTION; 288 | // trailer_collision_check_points.points.push_back(trailer_collision_check_point); 289 | // trailer_collision_check_pub.publish(trailer_collision_check_points); 290 | 291 | if(bin_map[s][t] != 0) { 292 | // cout << "X : " << s << " Y : "<< t << " BIN_MAP : " << bin_map[s][t] << endl; 293 | // robot_collision_check_pub.publish(robot_collision_check_points); 294 | // ROS_INFO("ROBOT POLYGON COLLISION"); 295 | return true; // IN COLLISION 296 | } 297 | } 298 | } 299 | } 300 | 301 | // ROS_INFO("NO COLLISION - SAFE"); 302 | return false; // NO COLLISION 303 | } 304 | 305 | 306 | /* 307 | Function to visualize robot/trailer polygons 308 | 309 | grid: Pointer to the occupancy grid msg 310 | bin_map: A 2D binary obstacle map 311 | 312 | Returns: geometry_msgs:PolygonStamped 313 | */ 314 | geometry_msgs::PolygonStamped create_polygon(float l, float w, float cx, float cy, float yaw) { 315 | 316 | geometry_msgs::PolygonStamped polygon; 317 | polygon.header.stamp = ros::Time::now(); 318 | polygon.header.frame_id = "/map"; 319 | polygon.polygon.points.clear(); 320 | 321 | float length = l; 322 | float width = w; 323 | 324 | geometry_msgs::Point32 p; 325 | // Top Right 326 | p.x = cx + ((length/2) * cos(yaw)) - ((width/2) * sin(yaw)); 327 | p.y = cy + ((length/2) * sin(yaw)) + ((width/2) * cos(yaw)); 328 | polygon.polygon.points.push_back(p); 329 | 330 | // Top Left 331 | p.x = cx - ((length/2) * cos(yaw)) - ((width/2) * sin(yaw)); 332 | p.y = cy - ((length/2) * sin(yaw)) + ((width/2) * cos(yaw)); 333 | polygon.polygon.points.push_back(p); 334 | 335 | // Bottom Left 336 | p.x = cx - ((length/2) * cos(yaw)) + ((width/2) * sin(yaw)); 337 | p.y = cy - ((length/2) * sin(yaw)) - ((width/2) * cos(yaw)); 338 | polygon.polygon.points.push_back(p); 339 | 340 | // Bottom Right 341 | p.x = cx + ((length/2) * cos(yaw)) + ((width/2) * sin(yaw)); 342 | p.y = cy + ((length/2) * sin(yaw)) - ((width/2) * cos(yaw)); 343 | polygon.polygon.points.push_back(p); 344 | 345 | return polygon; 346 | } -------------------------------------------------------------------------------- /maps/voronoi/cache/10917222191326015076/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 354 6 | 2 7 | 2 8 | 1 9 | 2 10 | 2 11 | 2 12 | 1 13 | 2 14 | 2 15 | 1 16 | 2 17 | 1 18 | 2 19 | 1 20 | 2 21 | 1 22 | 2 23 | 1 24 | 1 25 | 1 26 | 2 27 | 1 28 | 3 29 | 1 30 | 3 31 | 1 32 | 2 33 | 1 34 | 1 35 | 1 36 | 1 37 | 2 38 | 2 39 | 1 40 | 2 41 | 1 42 | 2 43 | 1 44 | 2 45 | 1 46 | 1 47 | 1 48 | 2 49 | 2 50 | 1 51 | 2 52 | 1 53 | 2 54 | 1 55 | 3 56 | 1 57 | 1 58 | 3 59 | 1 60 | 2 61 | 1 62 | 1 63 | 2 64 | 2 65 | 1 66 | 2 67 | 2 68 | 1 69 | 1 70 | 2 71 | 2 72 | 1 73 | 1 74 | 1 75 | 2 76 | 1 77 | 1 78 | 1 79 | 2 80 | 1 81 | 2 82 | 1 83 | 1 84 | 1 85 | 1 86 | 1 87 | 2 88 | 1 89 | 1 90 | 1 91 | 1 92 | 1 93 | 1 94 | 2 95 | 1 96 | 1 97 | 1 98 | 1 99 | 1 100 | 1 101 | 1 102 | 1 103 | 2 104 | 2 105 | 1 106 | 2 107 | 1 108 | 1 109 | 1 110 | 1 111 | 2 112 | 2 113 | 1 114 | 1 115 | 1 116 | 1 117 | 2 118 | 2 119 | 1 120 | 1 121 | 1 122 | 1 123 | 1 124 | 1 125 | 1 126 | 1 127 | 1 128 | 3 129 | 1 130 | 3 131 | 1 132 | 1 133 | 3 134 | 1 135 | 3 136 | 1 137 | 3 138 | 1 139 | 3 140 | 1 141 | 1 142 | 3 143 | 1 144 | 3 145 | 1 146 | 3 147 | 1 148 | 3 149 | 1 150 | 1 151 | 3 152 | 1 153 | 3 154 | 1 155 | 2 156 | 2 157 | 2 158 | 1 159 | 2 160 | 1 161 | 2 162 | 1 163 | 1 164 | 2 165 | 1 166 | 1 167 | 1 168 | 1 169 | 1 170 | 1 171 | 2 172 | 1 173 | 2 174 | 2 175 | 2 176 | 2 177 | 1 178 | 2 179 | 2 180 | 1 181 | 1 182 | 1 183 | 1 184 | 2 185 | 1 186 | 1 187 | 1 188 | 1 189 | 2 190 | 2 191 | 2 192 | 1 193 | 1 194 | 1 195 | 1 196 | 2 197 | 1 198 | 1 199 | 1 200 | 1 201 | 3 202 | 1 203 | 1 204 | 1 205 | 3 206 | 1 207 | 1 208 | 3 209 | 1 210 | 1 211 | 1 212 | 3 213 | 1 214 | 1 215 | 3 216 | 1 217 | 1 218 | 2 219 | 1 220 | 1 221 | 1 222 | 1 223 | 2 224 | 1 225 | 1 226 | 1 227 | 1 228 | 1 229 | 1 230 | 1 231 | 2 232 | 2 233 | 1 234 | 1 235 | 1 236 | 1 237 | 1 238 | 1 239 | 1 240 | 1 241 | 2 242 | 1 243 | 2 244 | 1 245 | 2 246 | 1 247 | 1 248 | 2 249 | 1 250 | 2 251 | 2 252 | 1 253 | 1 254 | 1 255 | 2 256 | 3 257 | 3 258 | 1 259 | 3 260 | 1 261 | 3 262 | 3 263 | 1 264 | 3 265 | 1 266 | 3 267 | 3 268 | 1 269 | 3 270 | 1 271 | 2 272 | 2 273 | 1 274 | 1 275 | 1 276 | 1 277 | 1 278 | 2 279 | 2 280 | 1 281 | 1 282 | 1 283 | 1 284 | 2 285 | 1 286 | 1 287 | 1 288 | 1 289 | 2 290 | 1 291 | 2 292 | 2 293 | 1 294 | 1 295 | 2 296 | 1 297 | 1 298 | 1 299 | 1 300 | 1 301 | 1 302 | 2 303 | 1 304 | 2 305 | 1 306 | 1 307 | 1 308 | 2 309 | 1 310 | 1 311 | 1 312 | 2 313 | 1 314 | 1 315 | 2 316 | 1 317 | 1 318 | 2 319 | 1 320 | 2 321 | 1 322 | 2 323 | 1 324 | 2 325 | 1 326 | 2 327 | 2 328 | 2 329 | 1 330 | 3 331 | 1 332 | 3 333 | 1 334 | 3 335 | 1 336 | 2 337 | 1 338 | 2 339 | 2 340 | 1 341 | 2 342 | 1 343 | 2 344 | 1 345 | 2 346 | 2 347 | 1 348 | 2 349 | 1 350 | 2 351 | 1 352 | 2 353 | 2 354 | 1 355 | 2 356 | 2 357 | 2 358 | 2 359 | 2 360 | 0 361 | 1 362 | 2 363 | 0 364 | 0 365 | 1 366 | 2 367 | 0 368 | 1 369 | 0 370 | 1 371 | 2 372 | 1 373 | 0 374 | 1 375 | 0 376 | 1 377 | 1 378 | 1 379 | 2 380 | 1 381 | 0 382 | 1 383 | 0 384 | 1 385 | 0 386 | 1 387 | 1 388 | 1 389 | 1 390 | 2 391 | 2 392 | 1 393 | 0 394 | 1 395 | 0 396 | 1 397 | 0 398 | 1 399 | 1 400 | 1 401 | 2 402 | 2 403 | 1 404 | 0 405 | 1 406 | 0 407 | 1 408 | 0 409 | 1 410 | 1 411 | 2 412 | 1 413 | 0 414 | 1 415 | 1 416 | 2 417 | 0 418 | 1 419 | 2 420 | 0 421 | 1 422 | 1 423 | 2 424 | 0 425 | 1 426 | 1 427 | 1 428 | 2 429 | 1 430 | 1 431 | 1 432 | 2 433 | 1 434 | 2 435 | 1 436 | 1 437 | 1 438 | 1 439 | 1 440 | 2 441 | 1 442 | 1 443 | 1 444 | 1 445 | 1 446 | 1 447 | 2 448 | 1 449 | 1 450 | 1 451 | 1 452 | 1 453 | 1 454 | 1 455 | 1 456 | 2 457 | 0 458 | 1 459 | 2 460 | 1 461 | 1 462 | 1 463 | 1 464 | 2 465 | 2 466 | 1 467 | 1 468 | 1 469 | 1 470 | 2 471 | 2 472 | 1 473 | 1 474 | 1 475 | 1 476 | 1 477 | 1 478 | 1 479 | 1 480 | 1 481 | 2 482 | 1 483 | 0 484 | 1 485 | 1 486 | 3 487 | 1 488 | 0 489 | 1 490 | 0 491 | 1 492 | 0 493 | 1 494 | 1 495 | 3 496 | 1 497 | 0 498 | 1 499 | 0 500 | 1 501 | 0 502 | 1 503 | 1 504 | 3 505 | 1 506 | 0 507 | 1 508 | 0 509 | 0 510 | 0 511 | 1 512 | 0 513 | 1 514 | 0 515 | 1 516 | 1 517 | 2 518 | 1 519 | 1 520 | 1 521 | 1 522 | 1 523 | 1 524 | 2 525 | 1 526 | 0 527 | 2 528 | 2 529 | 0 530 | 1 531 | 3 532 | 0 533 | 1 534 | 1 535 | 1 536 | 1 537 | 2 538 | 1 539 | 1 540 | 1 541 | 1 542 | 3 543 | 2 544 | 2 545 | 1 546 | 1 547 | 1 548 | 1 549 | 0 550 | 1 551 | 1 552 | 1 553 | 1 554 | 0 555 | 1 556 | 1 557 | 1 558 | 3 559 | 1 560 | 1 561 | 3 562 | 1 563 | 1 564 | 1 565 | 3 566 | 1 567 | 1 568 | 3 569 | 1 570 | 1 571 | 3 572 | 1 573 | 1 574 | 1 575 | 1 576 | 2 577 | 1 578 | 1 579 | 1 580 | 1 581 | 1 582 | 1 583 | 1 584 | 2 585 | 2 586 | 1 587 | 1 588 | 1 589 | 1 590 | 1 591 | 1 592 | 1 593 | 1 594 | 2 595 | 1 596 | 0 597 | 1 598 | 0 599 | 1 600 | 1 601 | 2 602 | 1 603 | 0 604 | 0 605 | 1 606 | 1 607 | 1 608 | 2 609 | 0 610 | 0 611 | 1 612 | 0 613 | 1 614 | 0 615 | 0 616 | 1 617 | 0 618 | 1 619 | 0 620 | 0 621 | 1 622 | 0 623 | 1 624 | 0 625 | 2 626 | 1 627 | 1 628 | 1 629 | 1 630 | 1 631 | 2 632 | 2 633 | 1 634 | 1 635 | 1 636 | 1 637 | 2 638 | 1 639 | 1 640 | 1 641 | 1 642 | 2 643 | 1 644 | 2 645 | 2 646 | 1 647 | 1 648 | 2 649 | 1 650 | 1 651 | 1 652 | 1 653 | 1 654 | 1 655 | 2 656 | 1 657 | 0 658 | 1 659 | 1 660 | 1 661 | 2 662 | 1 663 | 1 664 | 1 665 | 2 666 | 1 667 | 1 668 | 3 669 | 1 670 | 1 671 | 2 672 | 1 673 | 2 674 | 1 675 | 0 676 | 1 677 | 2 678 | 1 679 | 2 680 | 0 681 | 0 682 | 1 683 | 2 684 | 1 685 | 0 686 | 1 687 | 0 688 | 1 689 | 0 690 | 1 691 | 0 692 | 2 693 | 1 694 | 0 695 | 1 696 | 0 697 | 1 698 | 0 699 | 2 700 | 1 701 | 0 702 | 1 703 | 0 704 | 1 705 | 0 706 | 0 707 | 1 708 | 0 709 | 0 710 | 0 711 | 0 712 | 0 713 | 0 714 | 23 715 | 23 716 | 22 717 | 24 718 | 23 719 | 23 720 | 22 721 | 24 722 | 21 723 | 18 724 | 27 725 | 25 726 | 21 727 | 19 728 | 21 729 | 18 730 | 22 731 | 21 732 | 21 733 | 21 734 | 21 735 | 19 736 | 26 737 | 23 738 | 26 739 | 24 740 | 23 741 | 22 742 | 22 743 | 22 744 | 22 745 | 24 746 | 26 747 | 23 748 | 24 749 | 21 750 | 25 751 | 22 752 | 22 753 | 21 754 | 21 755 | 19 756 | 24 757 | 26 758 | 23 759 | 24 760 | 21 761 | 25 762 | 22 763 | 25 764 | 24 765 | 24 766 | 25 767 | 22 768 | 22 769 | 21 770 | 21 771 | 21 772 | 27 773 | 25 774 | 24 775 | 25 776 | 24 777 | 24 778 | 35 779 | 21 780 | 20 781 | 20 782 | 17 783 | 25 784 | 24 785 | 24 786 | 21 787 | 26 788 | 25 789 | 21 790 | 20 791 | 20 792 | 20 793 | 20 794 | 18 795 | 21 796 | 20 797 | 20 798 | 20 799 | 20 800 | 20 801 | 15 802 | 22 803 | 21 804 | 21 805 | 21 806 | 21 807 | 21 808 | 21 809 | 21 810 | 13 811 | 35 812 | 22 813 | 20 814 | 22 815 | 21 816 | 21 817 | 21 818 | 17 819 | 8 820 | 22 821 | 21 822 | 21 823 | 21 824 | 20 825 | 20 826 | 22 827 | 21 828 | 21 829 | 21 830 | 21 831 | 21 832 | 21 833 | 21 834 | 21 835 | 14 836 | 21 837 | 18 838 | 25 839 | 24 840 | 24 841 | 21 842 | 18 843 | 21 844 | 19 845 | 21 846 | 18 847 | 25 848 | 24 849 | 24 850 | 21 851 | 18 852 | 21 853 | 19 854 | 21 855 | 18 856 | 25 857 | 24 858 | 24 859 | 21 860 | 18 861 | 21 862 | 19 863 | 30 864 | 25 865 | 24 866 | 21 867 | 24 868 | 21 869 | 21 870 | 20 871 | 20 872 | 23 873 | 22 874 | 22 875 | 22 876 | 22 877 | 22 878 | 17 879 | 23 880 | 20 881 | 23 882 | 7 883 | 23 884 | 22 885 | 20 886 | 23 887 | 22 888 | 21 889 | 21 890 | 21 891 | 19 892 | 21 893 | 20 894 | 20 895 | 20 896 | 18 897 | 22 898 | 18 899 | 23 900 | 22 901 | 22 902 | 22 903 | 19 904 | 23 905 | 22 906 | 22 907 | 22 908 | 18 909 | 22 910 | 21 911 | 21 912 | 18 913 | 25 914 | 24 915 | 24 916 | 22 917 | 21 918 | 21 919 | 18 920 | 25 921 | 24 922 | 24 923 | 25 924 | 24 925 | 24 926 | 23 927 | 22 928 | 22 929 | 22 930 | 19 931 | 21 932 | 20 933 | 20 934 | 20 935 | 20 936 | 20 937 | 20 938 | 15 939 | 7 940 | 21 941 | 20 942 | 20 943 | 20 944 | 20 945 | 20 946 | 20 947 | 20 948 | 12 949 | 24 950 | 21 951 | 24 952 | 21 953 | 21 954 | 20 955 | 20 956 | 22 957 | 20 958 | 28 959 | 20 960 | 19 961 | 19 962 | 19 963 | 29 964 | 35 965 | 21 966 | 18 967 | 21 968 | 19 969 | 35 970 | 21 971 | 18 972 | 21 973 | 19 974 | 35 975 | 21 976 | 18 977 | 21 978 | 19 979 | 21 980 | 20 981 | 19 982 | 19 983 | 19 984 | 19 985 | 19 986 | 10 987 | 21 988 | 20 989 | 20 990 | 20 991 | 17 992 | 23 993 | 22 994 | 22 995 | 22 996 | 19 997 | 24 998 | 23 999 | 37 1000 | 22 1001 | 21 1002 | 21 1003 | 21 1004 | 20 1005 | 20 1006 | 20 1007 | 20 1008 | 20 1009 | 15 1010 | 21 1011 | 18 1012 | 22 1013 | 21 1014 | 21 1015 | 21 1016 | 21 1017 | 20 1018 | 20 1019 | 20 1020 | 26 1021 | 25 1022 | 23 1023 | 25 1024 | 24 1025 | 23 1026 | 26 1027 | 25 1028 | 21 1029 | 18 1030 | 27 1031 | 25 1032 | 23 1033 | 22 1034 | 25 1035 | 22 1036 | 23 1037 | 21 1038 | 25 1039 | 22 1040 | 26 1041 | 24 1042 | 24 1043 | 22 1044 | 26 1045 | 23 1046 | 24 1047 | 24 1048 | 21 1049 | 25 1050 | 22 1051 | 26 1052 | 23 1053 | 24 1054 | 24 1055 | 21 1056 | 25 1057 | 22 1058 | 22 1059 | 19 1060 | 35 1061 | 22 1062 | 19 1063 | 35 1064 | 25 1065 | 20 1066 | 25 1067 | 20 1068 | 1069 | -------------------------------------------------------------------------------- /maps/voronoi/cache/13544218348664178828/treeInfo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 354 6 | 2 7 | 2 8 | 1 9 | 2 10 | 2 11 | 2 12 | 1 13 | 2 14 | 2 15 | 1 16 | 2 17 | 1 18 | 2 19 | 1 20 | 2 21 | 1 22 | 2 23 | 1 24 | 1 25 | 1 26 | 2 27 | 1 28 | 3 29 | 1 30 | 3 31 | 1 32 | 2 33 | 1 34 | 1 35 | 1 36 | 1 37 | 2 38 | 2 39 | 1 40 | 2 41 | 1 42 | 2 43 | 1 44 | 2 45 | 1 46 | 1 47 | 1 48 | 2 49 | 2 50 | 1 51 | 2 52 | 1 53 | 2 54 | 1 55 | 3 56 | 1 57 | 1 58 | 3 59 | 1 60 | 2 61 | 1 62 | 1 63 | 2 64 | 2 65 | 1 66 | 2 67 | 2 68 | 1 69 | 1 70 | 2 71 | 2 72 | 1 73 | 1 74 | 1 75 | 2 76 | 1 77 | 1 78 | 1 79 | 2 80 | 1 81 | 2 82 | 1 83 | 1 84 | 1 85 | 1 86 | 1 87 | 2 88 | 1 89 | 1 90 | 1 91 | 1 92 | 1 93 | 1 94 | 2 95 | 1 96 | 1 97 | 1 98 | 1 99 | 1 100 | 1 101 | 1 102 | 1 103 | 2 104 | 2 105 | 1 106 | 2 107 | 1 108 | 1 109 | 1 110 | 1 111 | 2 112 | 2 113 | 1 114 | 1 115 | 1 116 | 1 117 | 2 118 | 2 119 | 1 120 | 1 121 | 1 122 | 1 123 | 1 124 | 1 125 | 1 126 | 1 127 | 1 128 | 3 129 | 1 130 | 3 131 | 1 132 | 1 133 | 3 134 | 1 135 | 3 136 | 1 137 | 3 138 | 1 139 | 3 140 | 1 141 | 1 142 | 3 143 | 1 144 | 3 145 | 1 146 | 3 147 | 1 148 | 3 149 | 1 150 | 1 151 | 3 152 | 1 153 | 3 154 | 1 155 | 2 156 | 2 157 | 2 158 | 1 159 | 2 160 | 1 161 | 2 162 | 1 163 | 1 164 | 2 165 | 1 166 | 1 167 | 1 168 | 1 169 | 1 170 | 1 171 | 2 172 | 1 173 | 2 174 | 2 175 | 2 176 | 2 177 | 1 178 | 2 179 | 2 180 | 1 181 | 1 182 | 1 183 | 1 184 | 2 185 | 1 186 | 1 187 | 1 188 | 1 189 | 2 190 | 2 191 | 2 192 | 1 193 | 1 194 | 1 195 | 1 196 | 2 197 | 1 198 | 1 199 | 1 200 | 1 201 | 3 202 | 1 203 | 1 204 | 1 205 | 3 206 | 1 207 | 1 208 | 3 209 | 1 210 | 1 211 | 1 212 | 3 213 | 1 214 | 1 215 | 3 216 | 1 217 | 1 218 | 2 219 | 1 220 | 1 221 | 1 222 | 1 223 | 2 224 | 1 225 | 1 226 | 1 227 | 1 228 | 1 229 | 1 230 | 1 231 | 2 232 | 2 233 | 1 234 | 1 235 | 1 236 | 1 237 | 1 238 | 1 239 | 1 240 | 1 241 | 2 242 | 1 243 | 2 244 | 1 245 | 2 246 | 1 247 | 1 248 | 2 249 | 1 250 | 2 251 | 2 252 | 1 253 | 1 254 | 1 255 | 2 256 | 3 257 | 3 258 | 1 259 | 3 260 | 1 261 | 3 262 | 3 263 | 1 264 | 3 265 | 1 266 | 3 267 | 3 268 | 1 269 | 3 270 | 1 271 | 2 272 | 2 273 | 1 274 | 1 275 | 1 276 | 1 277 | 1 278 | 2 279 | 2 280 | 1 281 | 1 282 | 1 283 | 1 284 | 2 285 | 1 286 | 1 287 | 1 288 | 1 289 | 2 290 | 1 291 | 2 292 | 2 293 | 1 294 | 1 295 | 2 296 | 1 297 | 1 298 | 1 299 | 1 300 | 1 301 | 1 302 | 2 303 | 1 304 | 2 305 | 1 306 | 1 307 | 1 308 | 2 309 | 1 310 | 1 311 | 1 312 | 2 313 | 1 314 | 1 315 | 2 316 | 1 317 | 1 318 | 2 319 | 1 320 | 2 321 | 1 322 | 2 323 | 1 324 | 2 325 | 1 326 | 2 327 | 2 328 | 2 329 | 1 330 | 3 331 | 1 332 | 3 333 | 1 334 | 3 335 | 1 336 | 2 337 | 1 338 | 2 339 | 2 340 | 1 341 | 2 342 | 1 343 | 2 344 | 1 345 | 2 346 | 2 347 | 1 348 | 2 349 | 1 350 | 2 351 | 1 352 | 2 353 | 2 354 | 1 355 | 2 356 | 2 357 | 2 358 | 2 359 | 2 360 | 0 361 | 1 362 | 2 363 | 0 364 | 0 365 | 1 366 | 2 367 | 0 368 | 1 369 | 0 370 | 1 371 | 2 372 | 1 373 | 0 374 | 1 375 | 0 376 | 1 377 | 1 378 | 1 379 | 2 380 | 1 381 | 0 382 | 1 383 | 0 384 | 1 385 | 0 386 | 1 387 | 1 388 | 1 389 | 1 390 | 2 391 | 2 392 | 1 393 | 0 394 | 1 395 | 0 396 | 1 397 | 0 398 | 1 399 | 1 400 | 1 401 | 2 402 | 2 403 | 1 404 | 0 405 | 1 406 | 0 407 | 1 408 | 0 409 | 1 410 | 1 411 | 2 412 | 1 413 | 0 414 | 1 415 | 1 416 | 2 417 | 0 418 | 1 419 | 2 420 | 0 421 | 1 422 | 1 423 | 2 424 | 0 425 | 1 426 | 1 427 | 1 428 | 2 429 | 1 430 | 1 431 | 1 432 | 2 433 | 1 434 | 2 435 | 1 436 | 1 437 | 1 438 | 1 439 | 1 440 | 2 441 | 1 442 | 1 443 | 1 444 | 1 445 | 1 446 | 1 447 | 2 448 | 1 449 | 1 450 | 1 451 | 1 452 | 1 453 | 1 454 | 1 455 | 1 456 | 2 457 | 0 458 | 1 459 | 2 460 | 1 461 | 1 462 | 1 463 | 1 464 | 2 465 | 2 466 | 1 467 | 1 468 | 1 469 | 1 470 | 2 471 | 2 472 | 1 473 | 1 474 | 1 475 | 1 476 | 1 477 | 1 478 | 1 479 | 1 480 | 1 481 | 2 482 | 1 483 | 0 484 | 1 485 | 1 486 | 3 487 | 1 488 | 0 489 | 1 490 | 0 491 | 1 492 | 0 493 | 1 494 | 1 495 | 3 496 | 1 497 | 0 498 | 1 499 | 0 500 | 1 501 | 0 502 | 1 503 | 1 504 | 3 505 | 1 506 | 0 507 | 1 508 | 0 509 | 0 510 | 0 511 | 1 512 | 0 513 | 1 514 | 0 515 | 1 516 | 1 517 | 2 518 | 1 519 | 1 520 | 1 521 | 1 522 | 1 523 | 1 524 | 2 525 | 1 526 | 0 527 | 2 528 | 2 529 | 0 530 | 1 531 | 3 532 | 0 533 | 1 534 | 1 535 | 1 536 | 1 537 | 2 538 | 1 539 | 1 540 | 1 541 | 1 542 | 3 543 | 2 544 | 2 545 | 1 546 | 1 547 | 1 548 | 1 549 | 0 550 | 1 551 | 1 552 | 1 553 | 1 554 | 0 555 | 1 556 | 1 557 | 1 558 | 3 559 | 1 560 | 1 561 | 3 562 | 1 563 | 1 564 | 1 565 | 3 566 | 1 567 | 1 568 | 3 569 | 1 570 | 1 571 | 3 572 | 1 573 | 1 574 | 1 575 | 1 576 | 2 577 | 1 578 | 1 579 | 1 580 | 1 581 | 1 582 | 1 583 | 1 584 | 2 585 | 2 586 | 1 587 | 1 588 | 1 589 | 1 590 | 1 591 | 1 592 | 1 593 | 1 594 | 2 595 | 1 596 | 0 597 | 1 598 | 0 599 | 1 600 | 1 601 | 2 602 | 1 603 | 0 604 | 0 605 | 1 606 | 1 607 | 1 608 | 2 609 | 0 610 | 0 611 | 1 612 | 0 613 | 1 614 | 0 615 | 0 616 | 1 617 | 0 618 | 1 619 | 0 620 | 0 621 | 1 622 | 0 623 | 1 624 | 0 625 | 2 626 | 1 627 | 1 628 | 1 629 | 1 630 | 1 631 | 2 632 | 2 633 | 1 634 | 1 635 | 1 636 | 1 637 | 2 638 | 1 639 | 1 640 | 1 641 | 1 642 | 2 643 | 1 644 | 2 645 | 2 646 | 1 647 | 1 648 | 2 649 | 1 650 | 1 651 | 1 652 | 1 653 | 1 654 | 1 655 | 2 656 | 1 657 | 0 658 | 1 659 | 1 660 | 1 661 | 2 662 | 1 663 | 1 664 | 1 665 | 2 666 | 1 667 | 1 668 | 3 669 | 1 670 | 1 671 | 2 672 | 1 673 | 2 674 | 1 675 | 0 676 | 1 677 | 2 678 | 1 679 | 2 680 | 0 681 | 0 682 | 1 683 | 2 684 | 1 685 | 0 686 | 1 687 | 0 688 | 1 689 | 0 690 | 1 691 | 0 692 | 2 693 | 1 694 | 0 695 | 1 696 | 0 697 | 1 698 | 0 699 | 2 700 | 1 701 | 0 702 | 1 703 | 0 704 | 1 705 | 0 706 | 0 707 | 1 708 | 0 709 | 0 710 | 0 711 | 0 712 | 0 713 | 0 714 | 23 715 | 23 716 | 22 717 | 24 718 | 23 719 | 23 720 | 22 721 | 24 722 | 21 723 | 18 724 | 27 725 | 25 726 | 21 727 | 19 728 | 21 729 | 18 730 | 22 731 | 21 732 | 21 733 | 21 734 | 21 735 | 19 736 | 26 737 | 23 738 | 26 739 | 24 740 | 23 741 | 22 742 | 22 743 | 22 744 | 22 745 | 24 746 | 26 747 | 23 748 | 24 749 | 21 750 | 25 751 | 22 752 | 22 753 | 21 754 | 21 755 | 19 756 | 24 757 | 26 758 | 23 759 | 24 760 | 21 761 | 25 762 | 22 763 | 25 764 | 24 765 | 24 766 | 25 767 | 22 768 | 22 769 | 21 770 | 21 771 | 21 772 | 27 773 | 25 774 | 24 775 | 25 776 | 24 777 | 24 778 | 35 779 | 21 780 | 20 781 | 20 782 | 17 783 | 25 784 | 24 785 | 24 786 | 21 787 | 26 788 | 25 789 | 21 790 | 20 791 | 20 792 | 20 793 | 20 794 | 18 795 | 21 796 | 20 797 | 20 798 | 20 799 | 20 800 | 20 801 | 15 802 | 22 803 | 21 804 | 21 805 | 21 806 | 21 807 | 21 808 | 21 809 | 21 810 | 13 811 | 35 812 | 22 813 | 20 814 | 22 815 | 21 816 | 21 817 | 21 818 | 17 819 | 8 820 | 22 821 | 21 822 | 21 823 | 21 824 | 20 825 | 20 826 | 22 827 | 21 828 | 21 829 | 21 830 | 21 831 | 21 832 | 21 833 | 21 834 | 21 835 | 14 836 | 21 837 | 18 838 | 25 839 | 24 840 | 24 841 | 21 842 | 18 843 | 21 844 | 19 845 | 21 846 | 18 847 | 25 848 | 24 849 | 24 850 | 21 851 | 18 852 | 21 853 | 19 854 | 21 855 | 18 856 | 25 857 | 24 858 | 24 859 | 21 860 | 18 861 | 21 862 | 19 863 | 30 864 | 25 865 | 24 866 | 21 867 | 24 868 | 21 869 | 21 870 | 20 871 | 20 872 | 23 873 | 22 874 | 22 875 | 22 876 | 22 877 | 22 878 | 17 879 | 23 880 | 20 881 | 23 882 | 7 883 | 23 884 | 22 885 | 20 886 | 23 887 | 22 888 | 21 889 | 21 890 | 21 891 | 19 892 | 21 893 | 20 894 | 20 895 | 20 896 | 18 897 | 22 898 | 18 899 | 23 900 | 22 901 | 22 902 | 22 903 | 19 904 | 23 905 | 22 906 | 22 907 | 22 908 | 18 909 | 22 910 | 21 911 | 21 912 | 18 913 | 25 914 | 24 915 | 24 916 | 22 917 | 21 918 | 21 919 | 18 920 | 25 921 | 24 922 | 24 923 | 25 924 | 24 925 | 24 926 | 23 927 | 22 928 | 22 929 | 22 930 | 19 931 | 21 932 | 20 933 | 20 934 | 20 935 | 20 936 | 20 937 | 20 938 | 15 939 | 7 940 | 21 941 | 20 942 | 20 943 | 20 944 | 20 945 | 20 946 | 20 947 | 20 948 | 12 949 | 24 950 | 21 951 | 24 952 | 21 953 | 21 954 | 20 955 | 20 956 | 22 957 | 20 958 | 28 959 | 20 960 | 19 961 | 19 962 | 19 963 | 29 964 | 35 965 | 21 966 | 18 967 | 21 968 | 19 969 | 35 970 | 21 971 | 18 972 | 21 973 | 19 974 | 35 975 | 21 976 | 18 977 | 21 978 | 19 979 | 21 980 | 20 981 | 19 982 | 19 983 | 19 984 | 19 985 | 19 986 | 10 987 | 21 988 | 20 989 | 20 990 | 20 991 | 17 992 | 23 993 | 22 994 | 22 995 | 22 996 | 19 997 | 24 998 | 23 999 | 37 1000 | 22 1001 | 21 1002 | 21 1003 | 21 1004 | 20 1005 | 20 1006 | 20 1007 | 20 1008 | 20 1009 | 15 1010 | 21 1011 | 18 1012 | 22 1013 | 21 1014 | 21 1015 | 21 1016 | 21 1017 | 20 1018 | 20 1019 | 20 1020 | 26 1021 | 25 1022 | 23 1023 | 25 1024 | 24 1025 | 23 1026 | 26 1027 | 25 1028 | 21 1029 | 18 1030 | 27 1031 | 25 1032 | 23 1033 | 22 1034 | 25 1035 | 22 1036 | 23 1037 | 21 1038 | 25 1039 | 22 1040 | 26 1041 | 24 1042 | 24 1043 | 22 1044 | 26 1045 | 23 1046 | 24 1047 | 24 1048 | 21 1049 | 25 1050 | 22 1051 | 26 1052 | 23 1053 | 24 1054 | 24 1055 | 21 1056 | 25 1057 | 22 1058 | 22 1059 | 19 1060 | 35 1061 | 22 1062 | 19 1063 | 35 1064 | 25 1065 | 20 1066 | 25 1067 | 20 1068 | 1069 | --------------------------------------------------------------------------------