├── .gitignore
├── .gitlab-ci.yml
├── LICENSE
├── README.md
├── ch_171744_maze
├── CMakeLists.txt
├── launch
│ └── start_maze.launch
├── package.xml
└── src
│ ├── maze.py
│ └── pid.py
├── maze_practice
└── model.sdf
└── mod_turtlebot_description
└── turtlebot_description.tar.gz
/.gitignore:
--------------------------------------------------------------------------------
1 | *.pyc
2 |
--------------------------------------------------------------------------------
/.gitlab-ci.yml:
--------------------------------------------------------------------------------
1 | image: 141.69.58.19:5000/iki/ros-kinetic-amr:latest
2 |
3 | before_script:
4 | - source /root/catkin_ws/devel/setup.bash
5 |
6 | stages:
7 | - catkin make
8 |
9 | catkin make:
10 | stage: catkin make
11 | script:
12 | - roscd; cd ..; catkin_make
13 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2017 Christian Högerle
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 all
13 | 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 THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Maze Solver (ROS)
2 | This repository enables a robot to leave a maze. Basically it uses wall detection and wall follow algorithms.
3 |
4 |
5 |
6 |
7 | Video: https://www.youtube.com/watch?v=Sf2yfDI60GU
8 |
9 | ## Installing / Getting started (Linux)
10 |
11 | ### Install Ros and other Tools
12 |
13 | **Warning! Please use Ubuntu 16.04 as this is the Long Term Support Version (LTS). If you are using Ubuntu 17.04 you have to use ROS Lunar release on your own risk!**
14 |
15 | First goto http://wiki.ros.org/kinetic/Installation/Ubuntu and follow the instructions there. The installation can take some time depending on your internet connection.
16 |
17 | After the ros setup is completed you should install these extra tools
18 |
19 | ```
20 | sudo apt-add-repository ppa:webupd8team/atom
21 | sudo apt-get update
22 | sudo apt-get install git gitg htop terminator atom
23 | sudo apt-get install ros-kinetic-turtlebot-simulator ros-kinetic-turtlebot-teleop
24 | ```
25 |
26 | ### Create catkin workspace
27 |
28 | All your ROS packages must be stored in a special folder called __catkin workspace__.
29 | ROS uses the [catkin](http://docs.ros.org/api/catkin/html/) build system to manage your codebase.
30 | We will not go deeper into exactly what this build system is, but for now, you need to create a catkin workspace before you create your first package.
31 |
32 | __This is very important! All your ROS code must always be located somewhere under `/src`!__
33 |
34 | ```
35 | mkdir -p ~/catkin_ws/src
36 | cd ~/catkin_ws/src
37 | catkin_init_workspace #initiates the catkin workspace
38 | cd ~/catkin_ws
39 | catkin_make #compiles the catkin workspace
40 | echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
41 | source ~/.bashrc
42 | ```
43 |
44 | ### Update your gazebo with the following commands
45 |
46 | Add OSRF package repo
47 |
48 | sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
49 |
50 | setup keys
51 |
52 | wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
53 |
54 | update gazebo
55 |
56 | sudo apt-get update
57 | sudo apt-get install gazebo7
58 |
59 | ### Mounting Hokuyo Laser Scanner onto the Turtlebot
60 |
61 | We have modified the `turtlebot_description` package that has the simulated model of the turtlebot and put in some upgrades that should make your life easier. After following these
62 | instructions, you should be able to visualise the laser ray projections in gazebo, and you will have a new stable topic that gets the laser data from the new scanner, which is `/laserscan`. We
63 | have also enhanced the field of vision of the scan to 180 degrees and the maximum range to 30 m.
64 |
65 | * Delete the existing `turtlebot_description` package using the following commands:
66 | ```
67 | cd /opt/ros/kinetic/share
68 | sudo rm -r turtlebot_description
69 | ```
70 |
71 | * Take the modified `turtlebot_description` package from `mod_turtlebot_description` to your `Downloads`
72 | folder. Extract the package from the compressed file.
73 |
74 | * Move the extracted package from the `Downloads` folder to the location of the deleted package using the following commands:
75 | ```
76 | cd ~/Downloads
77 | sudo mv turtlebot_description /opt/ros/kinetic/share
78 | ```
79 | If everything went alright, there should be a file named `hokuyo_urdf.xacro` at the location `/opt/ros/kinetic/share/turtlebot_description/urdf/sensors`
80 |
81 | * Run the following commands to setup the new modified turtlebot as the default whenever you launch it in gazebo:
82 | ```
83 | echo "export TURTLEBOT_3D_SENSOR=hokuyo" >> ~/.bashrc
84 | source ~/.bashrc
85 | ```
86 | Note that by doing this, the turtlebot will be launched with hokuyo laser scanner everytime you launch `turtlebot_gazebo`. If you want to go back to how everything was before you did all this, just delete
87 | the `export TURTLEBOT_3D_SENSOR` line in the `.bashrc` file.
88 |
89 | * Launch the `turtlebot_gazebo` package and hopefully, you should see your new turtlebot with enhanced superpowers like below and you should be able to see the scan data in the `/laserscan` topic.
90 |
91 | To launch the simulation use: `roslaunch turtlebot_gazebo turtlebot_world.launch`
92 |
93 | 
94 |
95 | ### Loading the Maze into the Simulation
96 |
97 | All you have to do to load it is run the following command after launching the `turtlebot_gazebo package`:
98 |
99 | `rosrun gazebo_ros spawn_model -file ~/catkin_ws/src//maze_practice/model.sdf -sdf -model -maze -x 16 -y 5`
100 |
101 | Be sure to enter your repository name correctly in the above command. An example:
102 |
103 | `rosrun gazebo_ros spawn_model -file ~/catkin_ws/src/ROS_maze_challenge/maze_practice/model.sdf -sdf -model -maze -x 16 -y 5`
104 |
105 | Your gazebo simulation should now look like below:
106 |
107 |
108 |
109 | ## How to use this ROS-Node (step-by-step)
110 |
111 | 1. Follow the install instructions
112 | 2. Download the repository in your catkin workspace
113 | 3. Run the simulation by using: `roslaunch turtlebot_gazebo turtlebot_world.launch`
114 | 4. Load the maze in your simulation: `rosrun gazebo_ros spawn_model -file ~/catkin_ws/src/ROS_maze_challenge/maze_practice/model.sdf -sdf -model -maze -x 16 -y 5`
115 | note: adopt the path to your system
116 | 5. Run the ROS-node to solve the maze by using: `roslaunch ch_171744_maze start_maze.launch`
117 |
118 |
119 | ## Description of the Solution
120 |
121 | ### Algorithm (pseudo code)
122 |
123 | ```
124 | save the actual x- and y-position (loop-detection)
125 | state = "WallDetection"
126 |
127 | while not rospy.is_shutdown():
128 | if(state == "WallDetection")
129 | search for a wall to follow
130 | adjust the angle to next wall
131 | drive to the wall
132 | while(not wall_arrived):
133 | drive
134 | save the actual x- and y-position (loop-detection)
135 | make a turn
136 | state = "wallFollow"
137 |
138 | elif(state == "wallFollow")
139 | if(loop_detected):
140 | state = "wallDetection"
141 | else:
142 | if(obstacles_detected)
143 | do turn ~90 degree
144 | else
145 | follow wall using PID-controller
146 | ```
147 |
148 | ### Wall Detection
149 |
150 | * In the image below you can see an example how the wall detection algorithm works. In this case the algorithm detects two walls.
151 | Among these two walls, the wall with the biggest distance will be chosen.
152 |
153 | 
154 |
155 | How does the wall detection work:
156 |
157 | There must be a predefined amount of points between the upper- and lower bound (see image below) . Another constraint is that the points must be next to each other.
158 | Otherwise it will not be detected as a wall.
159 |
160 | 
161 |
162 | * Turn and move to the detected wall.
163 |
164 | 
165 |
166 | * After the robot arrived in front of the detected wall, save the actual x- and y-position (depicted as green circle in the image below) and do a turn. After that use the wall follow algorithm.
167 |
168 | 
169 |
170 | ### Wall Follow
171 |
172 | A PID-controller is used to adjust the direction of movement .
173 |
174 | 
175 |
176 |
177 | ### Loop Detection
178 |
179 | When the wall follow algorithm starts, the robot saves it actual position into a list of positions. This position will be used for loop detection.
180 | If the robot hits any of these stored positions a loop is detected. In this case wall detection is used to reposition the robot.
181 |
182 | 
183 |
184 |
185 | ## Author
186 | Christian Högerle
187 |
188 | ## Licensing
189 | The code in this project is licensed under MIT license.
190 |
--------------------------------------------------------------------------------
/ch_171744_maze/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(ch_171744_maze)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | rospy
12 | )
13 |
14 | ## System dependencies are found with CMake's conventions
15 | # find_package(Boost REQUIRED COMPONENTS system)
16 |
17 |
18 | ## Uncomment this if the package has a setup.py. This macro ensures
19 | ## modules and global scripts declared therein get installed
20 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
21 | # catkin_python_setup()
22 |
23 | ################################################
24 | ## Declare ROS messages, services and actions ##
25 | ################################################
26 |
27 | ## To declare and build messages, services or actions from within this
28 | ## package, follow these steps:
29 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
30 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
31 | ## * In the file package.xml:
32 | ## * add a build_depend tag for "message_generation"
33 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
34 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
35 | ## but can be declared for certainty nonetheless:
36 | ## * add a run_depend tag for "message_runtime"
37 | ## * In this file (CMakeLists.txt):
38 | ## * add "message_generation" and every package in MSG_DEP_SET to
39 | ## find_package(catkin REQUIRED COMPONENTS ...)
40 | ## * add "message_runtime" and every package in MSG_DEP_SET to
41 | ## catkin_package(CATKIN_DEPENDS ...)
42 | ## * uncomment the add_*_files sections below as needed
43 | ## and list every .msg/.srv/.action file to be processed
44 | ## * uncomment the generate_messages entry below
45 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
46 |
47 | ## Generate messages in the 'msg' folder
48 | # add_message_files(
49 | # FILES
50 | # Message1.msg
51 | # Message2.msg
52 | # )
53 |
54 | ## Generate services in the 'srv' folder
55 | # add_service_files(
56 | # FILES
57 | # Service1.srv
58 | # Service2.srv
59 | # )
60 |
61 | ## Generate actions in the 'action' folder
62 | # add_action_files(
63 | # FILES
64 | # Action1.action
65 | # Action2.action
66 | # )
67 |
68 | ## Generate added messages and services with any dependencies listed here
69 | # generate_messages(
70 | # DEPENDENCIES
71 | # std_msgs # Or other packages containing msgs
72 | # )
73 |
74 | ################################################
75 | ## Declare ROS dynamic reconfigure parameters ##
76 | ################################################
77 |
78 | ## To declare and build dynamic reconfigure parameters within this
79 | ## package, follow these steps:
80 | ## * In the file package.xml:
81 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
82 | ## * In this file (CMakeLists.txt):
83 | ## * add "dynamic_reconfigure" to
84 | ## find_package(catkin REQUIRED COMPONENTS ...)
85 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
86 | ## and list every .cfg file to be processed
87 |
88 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
89 | # generate_dynamic_reconfigure_options(
90 | # cfg/DynReconf1.cfg
91 | # cfg/DynReconf2.cfg
92 | # )
93 |
94 | ###################################
95 | ## catkin specific configuration ##
96 | ###################################
97 | ## The catkin_package macro generates cmake config files for your package
98 | ## Declare things to be passed to dependent projects
99 | ## INCLUDE_DIRS: uncomment this if your package contains header files
100 | ## LIBRARIES: libraries you create in this project that dependent projects also need
101 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
102 | ## DEPENDS: system dependencies of this project that dependent projects also need
103 | catkin_package(
104 | # INCLUDE_DIRS include
105 | # LIBRARIES ch_171744_maze
106 | # CATKIN_DEPENDS rospy
107 | # DEPENDS system_lib
108 | )
109 |
110 | ###########
111 | ## Build ##
112 | ###########
113 |
114 | ## Specify additional locations of header files
115 | ## Your package locations should be listed before other locations
116 | include_directories(
117 | # include
118 | ${catkin_INCLUDE_DIRS}
119 | )
120 |
121 | ## Declare a C++ library
122 | # add_library(${PROJECT_NAME}
123 | # src/${PROJECT_NAME}/ch_171744_maze.cpp
124 | # )
125 |
126 | ## Add cmake target dependencies of the library
127 | ## as an example, code may need to be generated before libraries
128 | ## either from message generation or dynamic reconfigure
129 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
130 |
131 | ## Declare a C++ executable
132 | ## With catkin_make all packages are built within a single CMake context
133 | ## The recommended prefix ensures that target names across packages don't collide
134 | # add_executable(${PROJECT_NAME}_node src/ch_171744_maze_node.cpp)
135 |
136 | ## Rename C++ executable without prefix
137 | ## The above recommended prefix causes long target names, the following renames the
138 | ## target back to the shorter version for ease of user use
139 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
140 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
141 |
142 | ## Add cmake target dependencies of the executable
143 | ## same as for the library above
144 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
145 |
146 | ## Specify libraries to link a library or executable target against
147 | # target_link_libraries(${PROJECT_NAME}_node
148 | # ${catkin_LIBRARIES}
149 | # )
150 |
151 | #############
152 | ## Install ##
153 | #############
154 |
155 | # all install targets should use catkin DESTINATION variables
156 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
157 |
158 | ## Mark executable scripts (Python etc.) for installation
159 | ## in contrast to setup.py, you can choose the destination
160 | # install(PROGRAMS
161 | # scripts/my_python_script
162 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
163 | # )
164 |
165 | ## Mark executables and/or libraries for installation
166 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
167 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
168 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
169 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
170 | # )
171 |
172 | ## Mark cpp header files for installation
173 | # install(DIRECTORY include/${PROJECT_NAME}/
174 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
175 | # FILES_MATCHING PATTERN "*.h"
176 | # PATTERN ".svn" EXCLUDE
177 | # )
178 |
179 | ## Mark other files for installation (e.g. launch and bag files, etc.)
180 | # install(FILES
181 | # # myfile1
182 | # # myfile2
183 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
184 | # )
185 |
186 | #############
187 | ## Testing ##
188 | #############
189 |
190 | ## Add gtest based cpp test target and link libraries
191 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_ch_171744_maze.cpp)
192 | # if(TARGET ${PROJECT_NAME}-test)
193 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
194 | # endif()
195 |
196 | ## Add folders to be run by python nosetests
197 | # catkin_add_nosetests(test)
198 |
--------------------------------------------------------------------------------
/ch_171744_maze/launch/start_maze.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/ch_171744_maze/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ch_171744_maze
4 | 0.0.0
5 | The maze package
6 |
7 |
8 |
9 |
10 | ghost
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 | rospy
53 | rospy
54 | rospy
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
--------------------------------------------------------------------------------
/ch_171744_maze/src/maze.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 |
3 | import rospy
4 |
5 | from threading import Thread, Lock
6 | import math
7 |
8 | from nav_msgs.msg import Odometry
9 | from geometry_msgs.msg import Twist
10 | from sensor_msgs.msg import LaserScan
11 |
12 | from pid import PID
13 |
14 | class MazeSolver:
15 |
16 | def __init__(self):
17 | rospy.init_node('MazeSolverNode')
18 | self.rate = rospy.Rate(10)
19 |
20 | rospy.Subscriber('/laserscan', LaserScan, self.laserscan_callback)
21 | rospy.Subscriber('/odom', Odometry, self.odom_callback)
22 |
23 | self.velPub = rospy.Publisher('/mobile_base/commands/velocity', Twist, queue_size = 5)
24 |
25 | self.vel = Twist()
26 | self.laser = None
27 | self.odom = None
28 |
29 | # set up wall detection
30 | self.minLaserValues = 60 # amount of laserspoints that must be next to each other
31 | self.intervalEpsilon = 1.5 # upper- and lower-bound
32 | self.mutex2 = Lock()
33 |
34 | # set up loop detection
35 | self.knownPoints = []
36 | self.epsilonAroundPoints = 0.1 # circle around the saved points
37 | self.timeoutForDetection = 12 # delay in seconds
38 |
39 | # set up wall follower
40 | self.leftHand = True # True, if the robot uses the left sensor for wall follow
41 | self.laserIndex = 359 # left laser index
42 | self.turnSpeed = -0.3
43 | self.distanceToWall = 0.4 # distance from the wall to the robot and min distance for obstacles detection
44 | self.angle = 1.57 # around 90 degree
45 | self.minLasersSide = [150,170] # lasers used for basic obstacles detection
46 | self.mutex = Lock()
47 |
48 | # set up PID
49 | kp = 6
50 | ki = 2
51 | kd = 1.5
52 | outMin = -0.4
53 | outMax = 0.4
54 | iMin = -0.4
55 | iMax = 0.4
56 | self.pid = PID(kp, ki, kd, outMin, outMax, iMin, iMax)
57 |
58 | # actual drive state (initial: WallDetection)
59 | self.driveState = "WallDetection"
60 |
61 | def odom_callback(self, odom_msg):
62 | self.odom = odom_msg
63 |
64 | def laserscan_callback(self, laser_msg):
65 | self.laser = laser_msg
66 |
67 | def startSolver(self):
68 | rospy.loginfo("start Maze Solver Node")
69 |
70 | # if the robot uses the right sensor for wall follow
71 | if(not self.leftHand):
72 | self.laserIndex = 0
73 | self.minLasersSide = [190, 210]
74 | self.turnSpeed *= (-1)
75 |
76 | while not rospy.is_shutdown():
77 | if(self.laser and self.odom): # laser and odom data arrived from callback
78 |
79 | # append the origin to the known points
80 | if(len(self.knownPoints) == 0):
81 | self.knownPoints.append([self.odom.pose.pose.position.x, self.odom.pose.pose.position.y, rospy.Time.now().to_sec()])
82 |
83 | # take the min laser value in front of the robot (simple obstacles detection)
84 | actMinLaserValue = min(min(self.laser.ranges[170:190], self.laser.ranges[self.minLasersSide[0] : self.minLasersSide[1]]))
85 |
86 | if(self.driveState == "WallDetection"):
87 | self.vel.linear.x = 0.0
88 | self.vel.angular.z = 0.0
89 | self.wallDetection(actMinLaserValue)
90 | elif(self.driveState == "driveToWall"):
91 | if(self.mutex.locked() == False):
92 | # obstacle in front of the robot or wall arrived
93 | if(actMinLaserValue <= self.distanceToWall):
94 | # save the actual position used for loop detection
95 | self.knownPoints.append([self.odom.pose.pose.position.x,self.odom.pose.pose.position.y, rospy.Time.now().to_sec()])
96 |
97 | self.vel.linear.x = 0.0
98 | self.vel.angular.z = 0.0
99 | self.rotate_angle(self.angle, self.turnSpeed)
100 | self.driveState = "WallFollow"
101 | else:
102 | self.vel.linear.x = 0.3
103 | self.vel.angular.z = 0.0
104 | elif(self.driveState == "WallFollow"):
105 | if(self.mutex.locked() == False):
106 | # check known points (loop detection)
107 | for i in range(0, len(self.knownPoints)):
108 | if(self.odom.pose.pose.position.x - self.epsilonAroundPoints <= self.knownPoints[i][0] <= self.odom.pose.pose.position.x + self.epsilonAroundPoints and
109 | self.odom.pose.pose.position.y - self.epsilonAroundPoints <= self.knownPoints[i][1] <= self.odom.pose.pose.position.y + self.epsilonAroundPoints and
110 | self.knownPoints[i][2] + self.timeoutForDetection < rospy.Time.now().to_sec()):
111 | rospy.loginfo("Loop detected")
112 | self.driveState = "WallDetection"
113 |
114 | self.wallFollower(actMinLaserValue)
115 |
116 | self.velPub.publish(self.vel)
117 |
118 | self.rate.sleep()
119 | rospy.spin()
120 |
121 | def wallDetection(self, actMinLaserValue):
122 | self.mutex2.acquire()
123 | try:
124 | if(actMinLaserValue < self.distanceToWall):
125 | self.rotate_angle(self.angle, self.turnSpeed)
126 | else:
127 | # search for a wall to follow
128 | arrValues = []
129 | i = 0
130 | # do wall detection
131 | while(i < len(self.laser.ranges)):
132 | valCounter = 0
133 | for k in range(i+1, len(self.laser.ranges)):
134 | # check if actual value is in interval
135 | if(self.laser.ranges[i] - self.intervalEpsilon) <= self.laser.ranges[k] <= (self.laser.ranges[i] + self.intervalEpsilon):
136 | valCounter += 1
137 | else:
138 | if(valCounter > self.minLaserValues):
139 | arrValues.append([self.laser.ranges[i], i, k])
140 | valCounter = 0
141 | i = k
142 | if(k == len(self.laser.ranges) - 1):
143 | i = len(self.laser.ranges)
144 |
145 | # turn the robot to the wall (use the wall with the max distance to the robot)
146 | getLaserIndex = 180;
147 | if(arrValues):
148 | getLaserIndex = int(math.floor((max(arrValues)[1] + max(arrValues)[2]) / 2))
149 | if(getLaserIndex <= 175 or getLaserIndex >= 185):
150 | tmpAngle = self.laser.angle_min + (getLaserIndex * self.laser.angle_increment)
151 | if(getLaserIndex < 170): # rotation to the right
152 | self.rotate_angle(abs(tmpAngle), -0.3)
153 | else: # rotation to the left
154 | self.rotate_angle(abs(tmpAngle), 0.3)
155 |
156 | # wait until the robot has stopped the rotation
157 | rospy.sleep(1.5)
158 | self.driveState = "driveToWall"
159 | finally:
160 | self.mutex2.release()
161 |
162 | def wallFollower(self, actMinLaserValue):
163 | pidValue = self.pid.pidExecute(self.distanceToWall, self.laser.ranges[self.laserIndex])
164 |
165 | if(self.leftHand):
166 | pidValue = pidValue * (-1)
167 |
168 | # obstacle in front of the robot
169 | if(actMinLaserValue < self.distanceToWall):
170 | self.rotate_angle(self.angle, self.turnSpeed)
171 | elif(pidValue == 0):
172 | self.vel.linear.x = 0.3
173 | self.vel.angular.z = 0.0
174 | elif(pidValue != 0):
175 | self.vel.linear.x = 0.15
176 | self.vel.angular.z = pidValue
177 |
178 | # simple rotation function by the relativ angle in rad
179 | def rotate_angle(self, angle, speed):
180 | self.mutex.acquire()
181 | try:
182 | angular_speed = speed
183 | relative_angle = angle
184 | self.vel.linear.x = 0.0
185 | self.vel.angular.z = angular_speed
186 |
187 | # setting the current time for distance calculus
188 | t0 = rospy.Time.now().to_sec()
189 | current_angle = 0
190 |
191 | while(current_angle < relative_angle):
192 | self.velPub.publish(self.vel)
193 | t1 = rospy.Time.now().to_sec()
194 | current_angle = abs(angular_speed)*(t1-t0)
195 |
196 | # forcing the robot to stop after rotation
197 | self.vel.linear.x = 0.0
198 | self.vel.angular.z = 0
199 | self.velPub.publish(self.vel)
200 | # fixes issue #6 (Weird Driving at Wall Following)
201 | self.pid.resetValues()
202 | finally:
203 | self.mutex.release()
204 |
205 | if __name__ == "__main__":
206 | maze_solver = MazeSolver()
207 | maze_solver.startSolver()
208 |
--------------------------------------------------------------------------------
/ch_171744_maze/src/pid.py:
--------------------------------------------------------------------------------
1 | import rospy
2 |
3 | class PID:
4 |
5 | def __init__(self, kp, ki, kd, outMin, outMax, iMin, iMax):
6 | self.kp = kp
7 | self.ki = ki
8 | self.kd = kd
9 | self.outMin = outMin
10 | self.outMax = outMax
11 | self.intMin = iMin
12 | self.intMax = iMax
13 |
14 | self.lastError = 0
15 | self.sumError = 0
16 | self.lastTime = 0
17 |
18 | def resetValues(self):
19 | self.lastError = 0
20 | self.sumError = 0
21 | self.lastTime = 0
22 |
23 | def pidExecute(self, should, actValue):
24 | now = rospy.Time.now().to_nsec()
25 | timeChange = now - self.lastTime
26 | error = should - actValue
27 | newErrorSum = self.sumError + (error * timeChange)
28 |
29 | if((newErrorSum >= self.intMin) and (newErrorSum <= self.intMax)):
30 | self.sumError = newErrorSum
31 | dError = (error - self.lastError) / timeChange
32 | output = (self.kp * error) + (self.ki * self.sumError) + (self.kd * dError)
33 | self.lastError = error
34 | self.last = now
35 | if(output > self.outMax):
36 | output = self.outMax
37 | if(output < self.outMin):
38 | output = self.outMin
39 | return output
40 |
--------------------------------------------------------------------------------
/maze_practice/model.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 9.80009 2.02423 9e-06 0 -0 0
6 |
7 | 1
8 |
9 | 0.166667
10 | 0
11 | 0
12 | 0.166667
13 | 0
14 | 0.166667
15 |
16 |
17 |
18 | 0 0 0 0 -0 0
19 |
20 |
21 | 1 1 1
22 |
23 |
24 |
25 | 1
26 |
30 | 0.3 0.3 0.3 1
31 | 0.7 0.7 0.7 1
32 | 0.01 0.01 0.01 1
33 | 0 0 0 1
34 |
35 | 0
36 | 1
37 |
38 |
39 | 0
40 | 10
41 | 0 0 0 0 -0 0
42 |
43 |
44 | 1 1 1
45 |
46 |
47 |
48 |
49 |
50 | 1
51 | 1
52 | 0 0 0
53 | 0
54 | 0
55 |
56 |
57 | 1
58 | 0
59 | 0
60 | 1
61 |
62 | 0
63 |
64 |
65 |
66 |
67 | 0
68 | 1e+06
69 |
70 |
71 | 0
72 | 1
73 | 1
74 |
75 | 0
76 | 0.2
77 | 1e+13
78 | 1
79 | 0.01
80 | 0
81 |
82 |
83 | 1
84 | -0.01
85 | 0
86 | 0.2
87 | 1e+13
88 | 1
89 |
90 |
91 |
92 |
93 |
94 |
95 | 6.31823 4.34711 9e-06 0 -0 0
96 |
97 | 1
98 |
99 | 0.166667
100 | 0
101 | 0
102 | 0.166667
103 | 0
104 | 0.166667
105 |
106 |
107 |
108 | 0 0 0 0 -0 0
109 |
110 |
111 | 1 1 1
112 |
113 |
114 |
115 | 1
116 |
120 | 0.3 0.3 0.3 1
121 | 0.7 0.7 0.7 1
122 | 0.01 0.01 0.01 1
123 | 0 0 0 1
124 |
125 | 0
126 | 1
127 |
128 |
129 | 0
130 | 10
131 | 0 0 0 0 -0 0
132 |
133 |
134 | 1 1 1
135 |
136 |
137 |
138 |
139 |
140 | 1
141 | 1
142 | 0 0 0
143 | 0
144 | 0
145 |
146 |
147 | 1
148 | 0
149 | 0
150 | 1
151 |
152 | 0
153 |
154 |
155 |
156 |
157 | 0
158 | 1e+06
159 |
160 |
161 | 0
162 | 1
163 | 1
164 |
165 | 0
166 | 0.2
167 | 1e+13
168 | 1
169 | 0.01
170 | 0
171 |
172 |
173 | 1
174 | -0.01
175 | 0
176 | 0.2
177 | 1e+13
178 | 1
179 |
180 |
181 |
182 |
183 |
184 |
185 | 7.00494 5.00129 9e-06 0 -0 0
186 |
187 | 1
188 |
189 | 0.166667
190 | 0
191 | 0
192 | 0.166667
193 | 0
194 | 0.166667
195 |
196 |
197 |
198 | 0 0 0 0 -0 0
199 |
200 |
201 | 1 1 1
202 |
203 |
204 |
205 | 1
206 |
210 | 0.3 0.3 0.3 1
211 | 0.7 0.7 0.7 1
212 | 0.01 0.01 0.01 1
213 | 0 0 0 1
214 |
215 | 0
216 | 1
217 |
218 |
219 | 0
220 | 10
221 | 0 0 0 0 -0 0
222 |
223 |
224 | 1 1 1
225 |
226 |
227 |
228 |
229 |
230 | 1
231 | 1
232 | 0 0 0
233 | 0
234 | 0
235 |
236 |
237 | 1
238 | 0
239 | 0
240 | 1
241 |
242 | 0
243 |
244 |
245 |
246 |
247 | 0
248 | 1e+06
249 |
250 |
251 | 0
252 | 1
253 | 1
254 |
255 | 0
256 | 0.2
257 | 1e+13
258 | 1
259 | 0.01
260 | 0
261 |
262 |
263 | 1
264 | -0.01
265 | 0
266 | 0.2
267 | 1e+13
268 | 1
269 |
270 |
271 |
272 |
273 |
274 |
275 | 10.7124 2.54643 9e-06 0 -0 0
276 |
277 | 1
278 |
279 | 0.166667
280 | 0
281 | 0
282 | 0.166667
283 | 0
284 | 0.166667
285 |
286 |
287 |
288 | 0 0 0 0 -0 0
289 |
290 |
291 | 1 1 1
292 |
293 |
294 |
295 | 1
296 |
300 | 0.3 0.3 0.3 1
301 | 0.7 0.7 0.7 1
302 | 0.01 0.01 0.01 1
303 | 0 0 0 1
304 |
305 | 0
306 | 1
307 |
308 |
309 | 0
310 | 10
311 | 0 0 0 0 -0 0
312 |
313 |
314 | 1 1 1
315 |
316 |
317 |
318 |
319 |
320 | 1
321 | 1
322 | 0 0 0
323 | 0
324 | 0
325 |
326 |
327 | 1
328 | 0
329 | 0
330 | 1
331 |
332 | 0
333 |
334 |
335 |
336 |
337 | 0
338 | 1e+06
339 |
340 |
341 | 0
342 | 1
343 | 1
344 |
345 | 0
346 | 0.2
347 | 1e+13
348 | 1
349 | 0.01
350 | 0
351 |
352 |
353 | 1
354 | -0.01
355 | 0
356 | 0.2
357 | 1e+13
358 | 1
359 |
360 |
361 |
362 |
363 |
364 |
365 | -21.4897 -10.6297 9e-06 0 -0 0
366 |
367 | 4.30693
368 |
369 | 0.46587
370 | 0
371 | 0
372 | 22.6991
373 | 0
374 | 22.4471
375 |
376 | 0 0 0 0 -0 0
377 |
378 |
379 | 0 0 0 0 -0 0
380 |
381 |
382 | 7.88951 0.545905 1
383 |
384 |
385 |
386 | 1
387 |
391 | 0.3 0.3 0.3 1
392 | 0.7 0.7 0.7 1
393 | 0.01 0.01 0.01 1
394 | 0 0 0 1
395 |
396 |
397 | 0
398 | 1
399 |
400 |
401 | 0
402 | 10
403 | 0 0 0 0 -0 0
404 |
405 |
406 | 7.88951 0.545905 1
407 |
408 |
409 |
410 |
411 |
412 | 1
413 | 1
414 | 0 0 0
415 | 0
416 | 0
417 |
418 |
419 | 1
420 | 0
421 | 0
422 | 1
423 |
424 | 0
425 |
426 |
427 |
428 |
429 | 0
430 | 1e+06
431 |
432 |
433 | 0
434 | 1
435 | 1
436 |
437 | 0
438 | 0.2
439 | 1e+13
440 | 1
441 | 0.01
442 | 0
443 |
444 |
445 | 1
446 | -0.01
447 | 0
448 | 0.2
449 | 1e+13
450 | 1
451 |
452 |
453 |
454 |
455 |
456 |
457 | -17.8012 -10.6509 9e-06 0 -0 0
458 |
459 | 4.30693
460 |
461 | 0.46587
462 | 0
463 | 0
464 | 22.6991
465 | 0
466 | 22.4471
467 |
468 | 0 0 0 0 -0 0
469 |
470 |
471 | 0 0 0 0 -0 0
472 |
473 |
474 | 7.88951 0.545905 1
475 |
476 |
477 |
478 | 1
479 |
483 | 0.3 0.3 0.3 1
484 | 0.7 0.7 0.7 1
485 | 0.01 0.01 0.01 1
486 | 0 0 0 1
487 |
488 |
489 | 0
490 | 1
491 |
492 |
493 | 0
494 | 10
495 | 0 0 0 0 -0 0
496 |
497 |
498 | 7.88951 0.545905 1
499 |
500 |
501 |
502 |
503 |
504 | 1
505 | 1
506 | 0 0 0
507 | 0
508 | 0
509 |
510 |
511 | 1
512 | 0
513 | 0
514 | 1
515 |
516 | 0
517 |
518 |
519 |
520 |
521 | 0
522 | 1e+06
523 |
524 |
525 | 0
526 | 1
527 | 1
528 |
529 | 0
530 | 0.2
531 | 1e+13
532 | 1
533 | 0.01
534 | 0
535 |
536 |
537 | 1
538 | -0.01
539 | 0
540 | 0.2
541 | 1e+13
542 | 1
543 |
544 |
545 |
546 |
547 |
548 |
549 | -21.5718 -0.350427 9e-06 0 -0 0
550 |
551 | 4.30693
552 |
553 | 0.46587
554 | 0
555 | 0
556 | 22.6991
557 | 0
558 | 22.4471
559 |
560 | 0 0 0 0 -0 0
561 |
562 |
563 | 0 0 0 0 -0 0
564 |
565 |
566 | 7.88951 0.545905 1
567 |
568 |
569 |
570 | 1
571 |
575 | 0.3 0.3 0.3 1
576 | 0.7 0.7 0.7 1
577 | 0.01 0.01 0.01 1
578 | 0 0 0 1
579 |
580 |
581 | 0
582 | 1
583 |
584 |
585 | 0
586 | 10
587 | 0 0 0 0 -0 0
588 |
589 |
590 | 7.88951 0.545905 1
591 |
592 |
593 |
594 |
595 |
596 | 1
597 | 1
598 | 0 0 0
599 | 0
600 | 0
601 |
602 |
603 | 1
604 | 0
605 | 0
606 | 1
607 |
608 | 0
609 |
610 |
611 |
612 |
613 | 0
614 | 1e+06
615 |
616 |
617 | 0
618 | 1
619 | 1
620 |
621 | 0
622 | 0.2
623 | 1e+13
624 | 1
625 | 0.01
626 | 0
627 |
628 |
629 | 1
630 | -0.01
631 | 0
632 | 0.2
633 | 1e+13
634 | 1
635 |
636 |
637 |
638 |
639 |
640 |
641 | -14.0594 -0.346312 9e-06 0 -0 0
642 |
643 | 4.30693
644 |
645 | 0.46587
646 | 0
647 | 0
648 | 22.6991
649 | 0
650 | 22.4471
651 |
652 | 0 0 0 0 -0 0
653 |
654 |
655 | 0 0 0 0 -0 0
656 |
657 |
658 | 7.88951 0.545905 1
659 |
660 |
661 |
662 | 1
663 |
667 | 0.3 0.3 0.3 1
668 | 0.7 0.7 0.7 1
669 | 0.01 0.01 0.01 1
670 | 0 0 0 1
671 |
672 |
673 | 0
674 | 1
675 |
676 |
677 | 0
678 | 10
679 | 0 0 0 0 -0 0
680 |
681 |
682 | 7.88951 0.545905 1
683 |
684 |
685 |
686 |
687 |
688 | 1
689 | 1
690 | 0 0 0
691 | 0
692 | 0
693 |
694 |
695 | 1
696 | 0
697 | 0
698 | 1
699 |
700 | 0
701 |
702 |
703 |
704 |
705 | 0
706 | 1e+06
707 |
708 |
709 | 0
710 | 1
711 | 1
712 |
713 | 0
714 | 0.2
715 | 1e+13
716 | 1
717 | 0.01
718 | 0
719 |
720 |
721 | 1
722 | -0.01
723 | 0
724 | 0.2
725 | 1e+13
726 | 1
727 |
728 |
729 |
730 |
731 |
732 |
733 | -10.6658 -10.6545 9e-06 0 -0 0
734 |
735 | 4.30693
736 |
737 | 0.46587
738 | 0
739 | 0
740 | 22.6991
741 | 0
742 | 22.4471
743 |
744 | 0 0 0 0 -0 0
745 |
746 |
747 | 0 0 0 0 -0 0
748 |
749 |
750 | 7.88951 0.545905 1
751 |
752 |
753 |
754 | 1
755 |
759 | 0.3 0.3 0.3 1
760 | 0.7 0.7 0.7 1
761 | 0.01 0.01 0.01 1
762 | 0 0 0 1
763 |
764 |
765 | 0
766 | 1
767 |
768 |
769 | 0
770 | 10
771 | 0 0 0 0 -0 0
772 |
773 |
774 | 7.88951 0.545905 1
775 |
776 |
777 |
778 |
779 |
780 | 1
781 | 1
782 | 0 0 0
783 | 0
784 | 0
785 |
786 |
787 | 1
788 | 0
789 | 0
790 | 1
791 |
792 | 0
793 |
794 |
795 |
796 |
797 | 0
798 | 1e+06
799 |
800 |
801 | 0
802 | 1
803 | 1
804 |
805 | 0
806 | 0.2
807 | 1e+13
808 | 1
809 | 0.01
810 | 0
811 |
812 |
813 | 1
814 | -0.01
815 | 0
816 | 0.2
817 | 1e+13
818 | 1
819 |
820 |
821 |
822 |
823 |
824 |
825 | -3.41756 3.78222 9e-06 0 -0 0
826 |
827 | 3.50538
828 |
829 | 0.379168
830 | 0
831 | 0
832 | 12.3366
833 | 0
834 | 12.1315
835 |
836 | 0 0 0 0 -0 0
837 |
838 |
839 | 0 0 0 0 -0 0
840 |
841 |
842 | 6.42122 0.545905 1
843 |
844 |
845 |
846 | 1
847 |
851 | 0.3 0.3 0.3 1
852 | 0.7 0.7 0.7 1
853 | 0.01 0.01 0.01 1
854 | 0 0 0 1
855 |
856 |
857 | 0
858 | 1
859 |
860 |
861 | 0
862 | 10
863 | 0 0 0 0 -0 0
864 |
865 |
866 | 6.42122 0.545905 1
867 |
868 |
869 |
870 |
871 |
872 | 1
873 | 1
874 | 0 0 0
875 | 0
876 | 0
877 |
878 |
879 | 1
880 | 0
881 | 0
882 | 1
883 |
884 | 0
885 |
886 |
887 |
888 |
889 | 0
890 | 1e+06
891 |
892 |
893 | 0
894 | 1
895 | 1
896 |
897 | 0
898 | 0.2
899 | 1e+13
900 | 1
901 | 0.01
902 | 0
903 |
904 |
905 | 1
906 | -0.01
907 | 0
908 | 0.2
909 | 1e+13
910 | 1
911 |
912 |
913 |
914 |
915 |
916 |
917 | -2.67814 -10.6624 9e-06 0 -0 0
918 |
919 | 4.30693
920 |
921 | 0.46587
922 | 0
923 | 0
924 | 22.6991
925 | 0
926 | 22.4471
927 |
928 | 0 0 0 0 -0 0
929 |
930 |
931 | 0 0 0 0 -0 0
932 |
933 |
934 | 7.88951 0.545905 1
935 |
936 |
937 |
938 | 1
939 |
943 | 0.3 0.3 0.3 1
944 | 0.7 0.7 0.7 1
945 | 0.01 0.01 0.01 1
946 | 0 0 0 1
947 |
948 |
949 | 0
950 | 1
951 |
952 |
953 | 0
954 | 10
955 | 0 0 0 0 -0 0
956 |
957 |
958 | 7.88951 0.545905 1
959 |
960 |
961 |
962 |
963 |
964 | 1
965 | 1
966 | 0 0 0
967 | 0
968 | 0
969 |
970 |
971 | 1
972 | 0
973 | 0
974 | 1
975 |
976 | 0
977 |
978 |
979 |
980 |
981 | 0
982 | 1e+06
983 |
984 |
985 | 0
986 | 1
987 | 1
988 |
989 | 0
990 | 0.2
991 | 1e+13
992 | 1
993 | 0.01
994 | 0
995 |
996 |
997 | 1
998 | -0.01
999 | 0
1000 | 0.2
1001 | 1e+13
1002 | 1
1003 |
1004 |
1005 |
1006 |
1007 |
1008 |
1009 | 2.19804 -10.643 9e-06 0 -0 0
1010 |
1011 | 4.30693
1012 |
1013 | 0.46587
1014 | 0
1015 | 0
1016 | 22.6991
1017 | 0
1018 | 22.4471
1019 |
1020 | 0 0 0 0 -0 0
1021 |
1022 |
1023 | 0 0 0 0 -0 0
1024 |
1025 |
1026 | 7.88951 0.545905 1
1027 |
1028 |
1029 |
1030 | 1
1031 |
1035 | 0.3 0.3 0.3 1
1036 | 0.7 0.7 0.7 1
1037 | 0.01 0.01 0.01 1
1038 | 0 0 0 1
1039 |
1040 |
1041 | 0
1042 | 1
1043 |
1044 |
1045 | 0
1046 | 10
1047 | 0 0 0 0 -0 0
1048 |
1049 |
1050 | 7.88951 0.545905 1
1051 |
1052 |
1053 |
1054 |
1055 |
1056 | 1
1057 | 1
1058 | 0 0 0
1059 | 0
1060 | 0
1061 |
1062 |
1063 | 1
1064 | 0
1065 | 0
1066 | 1
1067 |
1068 | 0
1069 |
1070 |
1071 |
1072 |
1073 | 0
1074 | 1e+06
1075 |
1076 |
1077 | 0
1078 | 1
1079 | 1
1080 |
1081 | 0
1082 | 0.2
1083 | 1e+13
1084 | 1
1085 | 0.01
1086 | 0
1087 |
1088 |
1089 | 1
1090 | -0.01
1091 | 0
1092 | 0.2
1093 | 1e+13
1094 | 1
1095 |
1096 |
1097 |
1098 |
1099 |
1100 |
1101 | 0.695253 11.0512 9e-06 0 -0 0
1102 |
1103 | 4.30693
1104 |
1105 | 0.46587
1106 | 0
1107 | 0
1108 | 22.6991
1109 | 0
1110 | 22.4471
1111 |
1112 | 0 0 0 0 -0 0
1113 |
1114 |
1115 | 0 0 0 0 -0 0
1116 |
1117 |
1118 | 7.88951 0.545905 1
1119 |
1120 |
1121 |
1122 | 1
1123 |
1127 | 0.3 0.3 0.3 1
1128 | 0.7 0.7 0.7 1
1129 | 0.01 0.01 0.01 1
1130 | 0 0 0 1
1131 |
1132 |
1133 | 0
1134 | 1
1135 |
1136 |
1137 | 0
1138 | 10
1139 | 0 0 0 0 -0 0
1140 |
1141 |
1142 | 7.88951 0.545905 1
1143 |
1144 |
1145 |
1146 |
1147 |
1148 | 1
1149 | 1
1150 | 0 0 0
1151 | 0
1152 | 0
1153 |
1154 |
1155 | 1
1156 | 0
1157 | 0
1158 | 1
1159 |
1160 | 0
1161 |
1162 |
1163 |
1164 |
1165 | 0
1166 | 1e+06
1167 |
1168 |
1169 | 0
1170 | 1
1171 | 1
1172 |
1173 | 0
1174 | 0.2
1175 | 1e+13
1176 | 1
1177 | 0.01
1178 | 0
1179 |
1180 |
1181 | 1
1182 | -0.01
1183 | 0
1184 | 0.2
1185 | 1e+13
1186 | 1
1187 |
1188 |
1189 |
1190 |
1191 |
1192 |
1193 | 6.79233 11.1081 9e-06 0 -0 0
1194 |
1195 | 4.30693
1196 |
1197 | 0.46587
1198 | 0
1199 | 0
1200 | 22.6991
1201 | 0
1202 | 22.4471
1203 |
1204 | 0 0 0 0 -0 0
1205 |
1206 |
1207 | 0 0 0 0 -0 0
1208 |
1209 |
1210 | 7.88951 0.545905 1
1211 |
1212 |
1213 |
1214 | 1
1215 |
1219 | 0.3 0.3 0.3 1
1220 | 0.7 0.7 0.7 1
1221 | 0.01 0.01 0.01 1
1222 | 0 0 0 1
1223 |
1224 |
1225 | 0
1226 | 1
1227 |
1228 |
1229 | 0
1230 | 10
1231 | 0 0 0 0 -0 0
1232 |
1233 |
1234 | 7.88951 0.545905 1
1235 |
1236 |
1237 |
1238 |
1239 |
1240 | 1
1241 | 1
1242 | 0 0 0
1243 | 0
1244 | 0
1245 |
1246 |
1247 | 1
1248 | 0
1249 | 0
1250 | 1
1251 |
1252 | 0
1253 |
1254 |
1255 |
1256 |
1257 | 0
1258 | 1e+06
1259 |
1260 |
1261 | 0
1262 | 1
1263 | 1
1264 |
1265 | 0
1266 | 0.2
1267 | 1e+13
1268 | 1
1269 | 0.01
1270 | 0
1271 |
1272 |
1273 | 1
1274 | -0.01
1275 | 0
1276 | 0.2
1277 | 1e+13
1278 | 1
1279 |
1280 |
1281 |
1282 |
1283 |
1284 |
1285 | 2.76705 7.92871 9e-06 0 -0 0
1286 |
1287 | 3.50538
1288 |
1289 | 0.379168
1290 | 0
1291 | 0
1292 | 12.3366
1293 | 0
1294 | 12.1315
1295 |
1296 | 0 0 0 0 -0 0
1297 |
1298 |
1299 | 0 0 0 0 -0 0
1300 |
1301 |
1302 | 6.42122 0.545905 1
1303 |
1304 |
1305 |
1306 | 1
1307 |
1311 | 0.3 0.3 0.3 1
1312 | 0.7 0.7 0.7 1
1313 | 0.01 0.01 0.01 1
1314 | 0 0 0 1
1315 |
1316 |
1317 | 0
1318 | 1
1319 |
1320 |
1321 | 0
1322 | 10
1323 | 0 0 0 0 -0 0
1324 |
1325 |
1326 | 6.42122 0.545905 1
1327 |
1328 |
1329 |
1330 |
1331 |
1332 | 1
1333 | 1
1334 | 0 0 0
1335 | 0
1336 | 0
1337 |
1338 |
1339 | 1
1340 | 0
1341 | 0
1342 | 1
1343 |
1344 | 0
1345 |
1346 |
1347 |
1348 |
1349 | 0
1350 | 1e+06
1351 |
1352 |
1353 | 0
1354 | 1
1355 | 1
1356 |
1357 | 0
1358 | 0.2
1359 | 1e+13
1360 | 1
1361 | 0.01
1362 | 0
1363 |
1364 |
1365 | 1
1366 | -0.01
1367 | 0
1368 | 0.2
1369 | 1e+13
1370 | 1
1371 |
1372 |
1373 |
1374 |
1375 |
1376 |
1377 | 8.96944 -0.687018 9e-06 0 -0 0
1378 |
1379 | 3.50538
1380 |
1381 | 0.379168
1382 | 0
1383 | 0
1384 | 12.3366
1385 | 0
1386 | 12.1315
1387 |
1388 | 0 0 0 0 -0 0
1389 |
1390 |
1391 | 0 0 0 0 -0 0
1392 |
1393 |
1394 | 6.42122 0.545905 1
1395 |
1396 |
1397 |
1398 | 1
1399 |
1403 | 0.3 0.3 0.3 1
1404 | 0.7 0.7 0.7 1
1405 | 0.01 0.01 0.01 1
1406 | 0 0 0 1
1407 |
1408 |
1409 | 0
1410 | 1
1411 |
1412 |
1413 | 0
1414 | 10
1415 | 0 0 0 0 -0 0
1416 |
1417 |
1418 | 6.42122 0.545905 1
1419 |
1420 |
1421 |
1422 |
1423 |
1424 | 1
1425 | 1
1426 | 0 0 0
1427 | 0
1428 | 0
1429 |
1430 |
1431 | 1
1432 | 0
1433 | 0
1434 | 1
1435 |
1436 | 0
1437 |
1438 |
1439 |
1440 |
1441 | 0
1442 | 1e+06
1443 |
1444 |
1445 | 0
1446 | 1
1447 | 1
1448 |
1449 | 0
1450 | 0.2
1451 | 1e+13
1452 | 1
1453 | 0.01
1454 | 0
1455 |
1456 |
1457 | 1
1458 | -0.01
1459 | 0
1460 | 0.2
1461 | 1e+13
1462 | 1
1463 |
1464 |
1465 |
1466 |
1467 |
1468 |
1469 | 13.7042 5.43273 9e-06 0 -0 0
1470 |
1471 | 3.50538
1472 |
1473 | 0.379168
1474 | 0
1475 | 0
1476 | 12.3366
1477 | 0
1478 | 12.1315
1479 |
1480 | 0 0 0 0 -0 0
1481 |
1482 |
1483 | 0 0 0 0 -0 0
1484 |
1485 |
1486 | 6.42122 0.545905 1
1487 |
1488 |
1489 |
1490 | 1
1491 |
1495 | 0.3 0.3 0.3 1
1496 | 0.7 0.7 0.7 1
1497 | 0.01 0.01 0.01 1
1498 | 0 0 0 1
1499 |
1500 |
1501 | 0
1502 | 1
1503 |
1504 |
1505 | 0
1506 | 10
1507 | 0 0 0 0 -0 0
1508 |
1509 |
1510 | 6.42122 0.545905 1
1511 |
1512 |
1513 |
1514 |
1515 |
1516 | 1
1517 | 1
1518 | 0 0 0
1519 | 0
1520 | 0
1521 |
1522 |
1523 | 1
1524 | 0
1525 | 0
1526 | 1
1527 |
1528 | 0
1529 |
1530 |
1531 |
1532 |
1533 | 0
1534 | 1e+06
1535 |
1536 |
1537 | 0
1538 | 1
1539 | 1
1540 |
1541 | 0
1542 | 0.2
1543 | 1e+13
1544 | 1
1545 | 0.01
1546 | 0
1547 |
1548 |
1549 | 1
1550 | -0.01
1551 | 0
1552 | 0.2
1553 | 1e+13
1554 | 1
1555 |
1556 |
1557 |
1558 |
1559 |
1560 |
1561 | 16.5218 2.00661 9e-06 0 -0 0
1562 |
1563 | 3.50538
1564 |
1565 | 0.379168
1566 | 0
1567 | 0
1568 | 12.3366
1569 | 0
1570 | 12.1315
1571 |
1572 | 0 0 0 0 -0 0
1573 |
1574 |
1575 | 0 0 0 0 -0 0
1576 |
1577 |
1578 | 6.42122 0.545905 1
1579 |
1580 |
1581 |
1582 | 1
1583 |
1587 | 0.3 0.3 0.3 1
1588 | 0.7 0.7 0.7 1
1589 | 0.01 0.01 0.01 1
1590 | 0 0 0 1
1591 |
1592 |
1593 | 0
1594 | 1
1595 |
1596 |
1597 | 0
1598 | 10
1599 | 0 0 0 0 -0 0
1600 |
1601 |
1602 | 6.42122 0.545905 1
1603 |
1604 |
1605 |
1606 |
1607 |
1608 | 1
1609 | 1
1610 | 0 0 0
1611 | 0
1612 | 0
1613 |
1614 |
1615 | 1
1616 | 0
1617 | 0
1618 | 1
1619 |
1620 | 0
1621 |
1622 |
1623 |
1624 |
1625 | 0
1626 | 1e+06
1627 |
1628 |
1629 | 0
1630 | 1
1631 | 1
1632 |
1633 | 0
1634 | 0.2
1635 | 1e+13
1636 | 1
1637 | 0.01
1638 | 0
1639 |
1640 |
1641 | 1
1642 | -0.01
1643 | 0
1644 | 0.2
1645 | 1e+13
1646 | 1
1647 |
1648 |
1649 |
1650 |
1651 |
1652 |
1653 | 16.5551 5.42013 9e-06 0 -0 0
1654 |
1655 | 3.50538
1656 |
1657 | 0.379168
1658 | 0
1659 | 0
1660 | 12.3366
1661 | 0
1662 | 12.1315
1663 |
1664 | 0 0 0 0 -0 0
1665 |
1666 |
1667 | 0 0 0 0 -0 0
1668 |
1669 |
1670 | 6.42122 0.545905 1
1671 |
1672 |
1673 |
1674 | 1
1675 |
1679 | 0.3 0.3 0.3 1
1680 | 0.7 0.7 0.7 1
1681 | 0.01 0.01 0.01 1
1682 | 0 0 0 1
1683 |
1684 |
1685 | 0
1686 | 1
1687 |
1688 |
1689 | 0
1690 | 10
1691 | 0 0 0 0 -0 0
1692 |
1693 |
1694 | 6.42122 0.545905 1
1695 |
1696 |
1697 |
1698 |
1699 |
1700 | 1
1701 | 1
1702 | 0 0 0
1703 | 0
1704 | 0
1705 |
1706 |
1707 | 1
1708 | 0
1709 | 0
1710 | 1
1711 |
1712 | 0
1713 |
1714 |
1715 |
1716 |
1717 | 0
1718 | 1e+06
1719 |
1720 |
1721 | 0
1722 | 1
1723 | 1
1724 |
1725 | 0
1726 | 0.2
1727 | 1e+13
1728 | 1
1729 | 0.01
1730 | 0
1731 |
1732 |
1733 | 1
1734 | -0.01
1735 | 0
1736 | 0.2
1737 | 1e+13
1738 | 1
1739 |
1740 |
1741 |
1742 |
1743 |
1744 |
1745 | 14.7931 -0.66198 9e-06 0 -0 0
1746 |
1747 | 3.50538
1748 |
1749 | 0.379168
1750 | 0
1751 | 0
1752 | 12.3366
1753 | 0
1754 | 12.1315
1755 |
1756 | 0 0 0 0 -0 0
1757 |
1758 |
1759 | 0 0 0 0 -0 0
1760 |
1761 |
1762 | 6.42122 0.545905 1
1763 |
1764 |
1765 |
1766 | 1
1767 |
1771 | 0.3 0.3 0.3 1
1772 | 0.7 0.7 0.7 1
1773 | 0.01 0.01 0.01 1
1774 | 0 0 0 1
1775 |
1776 |
1777 | 0
1778 | 1
1779 |
1780 |
1781 | 0
1782 | 10
1783 | 0 0 0 0 -0 0
1784 |
1785 |
1786 | 6.42122 0.545905 1
1787 |
1788 |
1789 |
1790 |
1791 |
1792 | 1
1793 | 1
1794 | 0 0 0
1795 | 0
1796 | 0
1797 |
1798 |
1799 | 1
1800 | 0
1801 | 0
1802 | 1
1803 |
1804 | 0
1805 |
1806 |
1807 |
1808 |
1809 | 0
1810 | 1e+06
1811 |
1812 |
1813 | 0
1814 | 1
1815 | 1
1816 |
1817 | 0
1818 | 0.2
1819 | 1e+13
1820 | 1
1821 | 0.01
1822 | 0
1823 |
1824 |
1825 | 1
1826 | -0.01
1827 | 0
1828 | 0.2
1829 | 1e+13
1830 | 1
1831 |
1832 |
1833 |
1834 |
1835 |
1836 |
1837 | -10.3733 -0.31076 9e-06 0 -0 0
1838 |
1839 | 4.30693
1840 |
1841 | 0.46587
1842 | 0
1843 | 0
1844 | 22.6991
1845 | 0
1846 | 22.4471
1847 |
1848 | 0 0 0 0 -0 0
1849 |
1850 |
1851 | 0 0 0 0 -0 0
1852 |
1853 |
1854 | 7.88951 0.545905 1
1855 |
1856 |
1857 |
1858 | 1
1859 |
1863 | 0.3 0.3 0.3 1
1864 | 0.7 0.7 0.7 1
1865 | 0.01 0.01 0.01 1
1866 | 0 0 0 1
1867 |
1868 |
1869 | 0
1870 | 1
1871 |
1872 |
1873 | 0
1874 | 10
1875 | 0 0 0 0 -0 0
1876 |
1877 |
1878 | 7.88951 0.545905 1
1879 |
1880 |
1881 |
1882 |
1883 |
1884 | 1
1885 | 1
1886 | 0 0 0
1887 | 0
1888 | 0
1889 |
1890 |
1891 | 1
1892 | 0
1893 | 0
1894 | 1
1895 |
1896 | 0
1897 |
1898 |
1899 |
1900 |
1901 | 0
1902 | 1e+06
1903 |
1904 |
1905 | 0
1906 | 1
1907 | 1
1908 |
1909 | 0
1910 | 0.2
1911 | 1e+13
1912 | 1
1913 | 0.01
1914 | 0
1915 |
1916 |
1917 | 1
1918 | -0.01
1919 | 0
1920 | 0.2
1921 | 1e+13
1922 | 1
1923 |
1924 |
1925 |
1926 |
1927 |
1928 |
1929 | -25.335 -7.00928 9e-06 0 0 -1.56693
1930 |
1931 | 4.30693
1932 |
1933 | 0.46587
1934 | 0
1935 | 0
1936 | 22.6991
1937 | 0
1938 | 22.4471
1939 |
1940 | 0 0 0 0 -0 0
1941 |
1942 |
1943 | 0 0 0 0 -0 0
1944 |
1945 |
1946 | 7.88951 0.545905 1
1947 |
1948 |
1949 |
1950 | 1
1951 |
1955 | 0.3 0.3 0.3 1
1956 | 0.7 0.7 0.7 1
1957 | 0.01 0.01 0.01 1
1958 | 0 0 0 1
1959 |
1960 |
1961 | 0
1962 | 1
1963 |
1964 |
1965 | 0
1966 | 10
1967 | 0 0 0 0 -0 0
1968 |
1969 |
1970 | 7.88951 0.545905 1
1971 |
1972 |
1973 |
1974 |
1975 |
1976 | 1
1977 | 1
1978 | 0 0 0
1979 | 0
1980 | 0
1981 |
1982 |
1983 | 1
1984 | 0
1985 | 0
1986 | 1
1987 |
1988 | 0
1989 |
1990 |
1991 |
1992 |
1993 | 0
1994 | 1e+06
1995 |
1996 |
1997 | 0
1998 | 1
1999 | 1
2000 |
2001 | 0
2002 | 0.2
2003 | 1e+13
2004 | 1
2005 | 0.01
2006 | 0
2007 |
2008 |
2009 | 1
2010 | -0.01
2011 | 0
2012 | 0.2
2013 | 1e+13
2014 | 1
2015 |
2016 |
2017 |
2018 |
2019 |
2020 |
2021 | -25.3389 -4.07653 9e-06 0 0 -1.56693
2022 |
2023 | 4.30693
2024 |
2025 | 0.46587
2026 | 0
2027 | 0
2028 | 22.6991
2029 | 0
2030 | 22.4471
2031 |
2032 | 0 0 0 0 -0 0
2033 |
2034 |
2035 | 0 0 0 0 -0 0
2036 |
2037 |
2038 | 7.88951 0.545905 1
2039 |
2040 |
2041 |
2042 | 1
2043 |
2047 | 0.3 0.3 0.3 1
2048 | 0.7 0.7 0.7 1
2049 | 0.01 0.01 0.01 1
2050 | 0 0 0 1
2051 |
2052 |
2053 | 0
2054 | 1
2055 |
2056 |
2057 | 0
2058 | 10
2059 | 0 0 0 0 -0 0
2060 |
2061 |
2062 | 7.88951 0.545905 1
2063 |
2064 |
2065 |
2066 |
2067 |
2068 | 1
2069 | 1
2070 | 0 0 0
2071 | 0
2072 | 0
2073 |
2074 |
2075 | 1
2076 | 0
2077 | 0
2078 | 1
2079 |
2080 | 0
2081 |
2082 |
2083 |
2084 |
2085 | 0
2086 | 1e+06
2087 |
2088 |
2089 | 0
2090 | 1
2091 | 1
2092 |
2093 | 0
2094 | 0.2
2095 | 1e+13
2096 | 1
2097 | 0.01
2098 | 0
2099 |
2100 |
2101 | 1
2102 | -0.01
2103 | 0
2104 | 0.2
2105 | 1e+13
2106 | 1
2107 |
2108 |
2109 |
2110 |
2111 |
2112 |
2113 | -9.31294 -6.93569 9e-06 0 0 -1.56693
2114 |
2115 | 4.30693
2116 |
2117 | 0.46587
2118 | 0
2119 | 0
2120 | 22.6991
2121 | 0
2122 | 22.4471
2123 |
2124 | 0 0 0 0 -0 0
2125 |
2126 |
2127 | 0 0 0 0 -0 0
2128 |
2129 |
2130 | 7.88951 0.545905 1
2131 |
2132 |
2133 |
2134 | 1
2135 |
2139 | 0.3 0.3 0.3 1
2140 | 0.7 0.7 0.7 1
2141 | 0.01 0.01 0.01 1
2142 | 0 0 0 1
2143 |
2144 |
2145 | 0
2146 | 1
2147 |
2148 |
2149 | 0
2150 | 10
2151 | 0 0 0 0 -0 0
2152 |
2153 |
2154 | 7.88951 0.545905 1
2155 |
2156 |
2157 |
2158 |
2159 |
2160 | 1
2161 | 1
2162 | 0 0 0
2163 | 0
2164 | 0
2165 |
2166 |
2167 | 1
2168 | 0
2169 | 0
2170 | 1
2171 |
2172 | 0
2173 |
2174 |
2175 |
2176 |
2177 | 0
2178 | 1e+06
2179 |
2180 |
2181 | 0
2182 | 1
2183 | 1
2184 |
2185 | 0
2186 | 0.2
2187 | 1e+13
2188 | 1
2189 | 0.01
2190 | 0
2191 |
2192 |
2193 | 1
2194 | -0.01
2195 | 0
2196 | 0.2
2197 | 1e+13
2198 | 1
2199 |
2200 |
2201 |
2202 |
2203 |
2204 |
2205 | -6.43669 -6.98415 9e-06 0 0 -1.56693
2206 |
2207 | 4.30693
2208 |
2209 | 0.46587
2210 | 0
2211 | 0
2212 | 22.6991
2213 | 0
2214 | 22.4471
2215 |
2216 | 0 0 0 0 -0 0
2217 |
2218 |
2219 | 0 0 0 0 -0 0
2220 |
2221 |
2222 | 7.88951 0.545905 1
2223 |
2224 |
2225 |
2226 | 1
2227 |
2231 | 0.3 0.3 0.3 1
2232 | 0.7 0.7 0.7 1
2233 | 0.01 0.01 0.01 1
2234 | 0 0 0 1
2235 |
2236 |
2237 | 0
2238 | 1
2239 |
2240 |
2241 | 0
2242 | 10
2243 | 0 0 0 0 -0 0
2244 |
2245 |
2246 | 7.88951 0.545905 1
2247 |
2248 |
2249 |
2250 |
2251 |
2252 | 1
2253 | 1
2254 | 0 0 0
2255 | 0
2256 | 0
2257 |
2258 |
2259 | 1
2260 | 0
2261 | 0
2262 | 1
2263 |
2264 | 0
2265 |
2266 |
2267 |
2268 |
2269 | 0
2270 | 1e+06
2271 |
2272 |
2273 | 0
2274 | 1
2275 | 1
2276 |
2277 | 0
2278 | 0.2
2279 | 1e+13
2280 | 1
2281 | 0.01
2282 | 0
2283 |
2284 |
2285 | 1
2286 | -0.01
2287 | 0
2288 | 0.2
2289 | 1e+13
2290 | 1
2291 |
2292 |
2293 |
2294 |
2295 |
2296 |
2297 | -6.35585 1.56416 9e-06 0 0 -1.56693
2298 |
2299 | 2.3361
2300 |
2301 | 0.25269
2302 | 0
2303 | 0
2304 | 3.75965
2305 | 0
2306 | 3.62299
2307 |
2308 | 0 0 0 0 -0 0
2309 |
2310 |
2311 | 0 0 0 0 -0 0
2312 |
2313 |
2314 | 4.27931 0.545905 1
2315 |
2316 |
2317 |
2318 | 1
2319 |
2323 | 0.3 0.3 0.3 1
2324 | 0.7 0.7 0.7 1
2325 | 0.01 0.01 0.01 1
2326 | 0 0 0 1
2327 |
2328 |
2329 | 0
2330 | 1
2331 |
2332 |
2333 | 0
2334 | 10
2335 | 0 0 0 0 -0 0
2336 |
2337 |
2338 | 4.27931 0.545905 1
2339 |
2340 |
2341 |
2342 |
2343 |
2344 | 1
2345 | 1
2346 | 0 0 0
2347 | 0
2348 | 0
2349 |
2350 |
2351 | 1
2352 | 0
2353 | 0
2354 | 1
2355 |
2356 | 0
2357 |
2358 |
2359 |
2360 |
2361 | 0
2362 | 1e+06
2363 |
2364 |
2365 | 0
2366 | 1
2367 | 1
2368 |
2369 | 0
2370 | 0.2
2371 | 1e+13
2372 | 1
2373 | 0.01
2374 | 0
2375 |
2376 |
2377 | 1
2378 | -0.01
2379 | 0
2380 | 0.2
2381 | 1e+13
2382 | 1
2383 |
2384 |
2385 |
2386 |
2387 |
2388 |
2389 | -0.36051 -0.054697 9e-06 0 0 -1.56693
2390 |
2391 | 4.30693
2392 |
2393 | 0.46587
2394 | 0
2395 | 0
2396 | 22.6991
2397 | 0
2398 | 22.4471
2399 |
2400 | 0 0 0 0 -0 0
2401 |
2402 |
2403 | 0 0 0 0 -0 0
2404 |
2405 |
2406 | 7.88951 0.545905 1
2407 |
2408 |
2409 |
2410 | 1
2411 |
2415 | 0.3 0.3 0.3 1
2416 | 0.7 0.7 0.7 1
2417 | 0.01 0.01 0.01 1
2418 | 0 0 0 1
2419 |
2420 |
2421 | 0
2422 | 1
2423 |
2424 |
2425 | 0
2426 | 10
2427 | 0 0 0 0 -0 0
2428 |
2429 |
2430 | 7.88951 0.545905 1
2431 |
2432 |
2433 |
2434 |
2435 |
2436 | 1
2437 | 1
2438 | 0 0 0
2439 | 0
2440 | 0
2441 |
2442 |
2443 | 1
2444 | 0
2445 | 0
2446 | 1
2447 |
2448 | 0
2449 |
2450 |
2451 |
2452 |
2453 | 0
2454 | 1e+06
2455 |
2456 |
2457 | 0
2458 | 1
2459 | 1
2460 |
2461 | 0
2462 | 0.2
2463 | 1e+13
2464 | 1
2465 | 0.01
2466 | 0
2467 |
2468 |
2469 | 1
2470 | -0.01
2471 | 0
2472 | 0.2
2473 | 1e+13
2474 | 1
2475 |
2476 |
2477 |
2478 |
2479 |
2480 |
2481 | 5.88859 -2.1218 9e-06 0 0 -1.56693
2482 |
2483 | 4.30693
2484 |
2485 | 0.46587
2486 | 0
2487 | 0
2488 | 22.6991
2489 | 0
2490 | 22.4471
2491 |
2492 | 0 0 0 0 -0 0
2493 |
2494 |
2495 | 0 0 0 0 -0 0
2496 |
2497 |
2498 | 7.88951 0.545905 1
2499 |
2500 |
2501 |
2502 | 1
2503 |
2507 | 0.3 0.3 0.3 1
2508 | 0.7 0.7 0.7 1
2509 | 0.01 0.01 0.01 1
2510 | 0 0 0 1
2511 |
2512 |
2513 | 0
2514 | 1
2515 |
2516 |
2517 | 0
2518 | 10
2519 | 0 0 0 0 -0 0
2520 |
2521 |
2522 | 7.88951 0.545905 1
2523 |
2524 |
2525 |
2526 |
2527 |
2528 | 1
2529 | 1
2530 | 0 0 0
2531 | 0
2532 | 0
2533 |
2534 |
2535 | 1
2536 | 0
2537 | 0
2538 | 1
2539 |
2540 | 0
2541 |
2542 |
2543 |
2544 |
2545 | 0
2546 | 1e+06
2547 |
2548 |
2549 | 0
2550 | 1
2551 | 1
2552 |
2553 | 0
2554 | 0.2
2555 | 1e+13
2556 | 1
2557 | 0.01
2558 | 0
2559 |
2560 |
2561 | 1
2562 | -0.01
2563 | 0
2564 | 0.2
2565 | 1e+13
2566 | 1
2567 |
2568 |
2569 |
2570 |
2571 |
2572 |
2573 | 10.4715 7.44804 9e-06 0 0 -1.56693
2574 |
2575 | 4.30693
2576 |
2577 | 0.46587
2578 | 0
2579 | 0
2580 | 22.6991
2581 | 0
2582 | 22.4471
2583 |
2584 | 0 0 0 0 -0 0
2585 |
2586 |
2587 | 0 0 0 0 -0 0
2588 |
2589 |
2590 | 7.88951 0.545905 1
2591 |
2592 |
2593 |
2594 | 1
2595 |
2599 | 0.3 0.3 0.3 1
2600 | 0.7 0.7 0.7 1
2601 | 0.01 0.01 0.01 1
2602 | 0 0 0 1
2603 |
2604 |
2605 | 0
2606 | 1
2607 |
2608 |
2609 | 0
2610 | 10
2611 | 0 0 0 0 -0 0
2612 |
2613 |
2614 | 7.88951 0.545905 1
2615 |
2616 |
2617 |
2618 |
2619 |
2620 | 1
2621 | 1
2622 | 0 0 0
2623 | 0
2624 | 0
2625 |
2626 |
2627 | 1
2628 | 0
2629 | 0
2630 | 1
2631 |
2632 | 0
2633 |
2634 |
2635 |
2636 |
2637 | 0
2638 | 1e+06
2639 |
2640 |
2641 | 0
2642 | 1
2643 | 1
2644 |
2645 | 0
2646 | 0.2
2647 | 1e+13
2648 | 1
2649 | 0.01
2650 | 0
2651 |
2652 |
2653 | 1
2654 | -0.01
2655 | 0
2656 | 0.2
2657 | 1e+13
2658 | 1
2659 |
2660 |
2661 |
2662 |
2663 |
2664 |
2665 | 5.82858 4.32024 9e-06 0 0 -1.56693
2666 |
2667 | 4.30693
2668 |
2669 | 0.46587
2670 | 0
2671 | 0
2672 | 22.6991
2673 | 0
2674 | 22.4471
2675 |
2676 | 0 0 0 0 -0 0
2677 |
2678 |
2679 | 0 0 0 0 -0 0
2680 |
2681 |
2682 | 7.88951 0.545905 1
2683 |
2684 |
2685 |
2686 | 1
2687 |
2691 | 0.3 0.3 0.3 1
2692 | 0.7 0.7 0.7 1
2693 | 0.01 0.01 0.01 1
2694 | 0 0 0 1
2695 |
2696 |
2697 | 0
2698 | 1
2699 |
2700 |
2701 | 0
2702 | 10
2703 | 0 0 0 0 -0 0
2704 |
2705 |
2706 | 7.88951 0.545905 1
2707 |
2708 |
2709 |
2710 |
2711 |
2712 | 1
2713 | 1
2714 | 0 0 0
2715 | 0
2716 | 0
2717 |
2718 |
2719 | 1
2720 | 0
2721 | 0
2722 | 1
2723 |
2724 | 0
2725 |
2726 |
2727 |
2728 |
2729 | 0
2730 | 1e+06
2731 |
2732 |
2733 | 0
2734 | 1
2735 | 1
2736 |
2737 | 0
2738 | 0.2
2739 | 1e+13
2740 | 1
2741 | 0.01
2742 | 0
2743 |
2744 |
2745 | 1
2746 | -0.01
2747 | 0
2748 | 0.2
2749 | 1e+13
2750 | 1
2751 |
2752 |
2753 |
2754 |
2755 |
2756 |
2757 | -3.1358 7.42604 9e-06 0 0 -1.56693
2758 |
2759 | 4.30693
2760 |
2761 | 0.46587
2762 | 0
2763 | 0
2764 | 22.6991
2765 | 0
2766 | 22.4471
2767 |
2768 | 0 0 0 0 -0 0
2769 |
2770 |
2771 | 0 0 0 0 -0 0
2772 |
2773 |
2774 | 7.88951 0.545905 1
2775 |
2776 |
2777 |
2778 | 1
2779 |
2783 | 0.3 0.3 0.3 1
2784 | 0.7 0.7 0.7 1
2785 | 0.01 0.01 0.01 1
2786 | 0 0 0 1
2787 |
2788 |
2789 | 0
2790 | 1
2791 |
2792 |
2793 | 0
2794 | 10
2795 | 0 0 0 0 -0 0
2796 |
2797 |
2798 | 7.88951 0.545905 1
2799 |
2800 |
2801 |
2802 |
2803 |
2804 | 1
2805 | 1
2806 | 0 0 0
2807 | 0
2808 | 0
2809 |
2810 |
2811 | 1
2812 | 0
2813 | 0
2814 | 1
2815 |
2816 | 0
2817 |
2818 |
2819 |
2820 |
2821 | 0
2822 | 1e+06
2823 |
2824 |
2825 | 0
2826 | 1
2827 | 1
2828 |
2829 | 0
2830 | 0.2
2831 | 1e+13
2832 | 1
2833 | 0.01
2834 | 0
2835 |
2836 |
2837 | 1
2838 | -0.01
2839 | 0
2840 | 0.2
2841 | 1e+13
2842 | 1
2843 |
2844 |
2845 |
2846 |
2847 |
2848 |
2849 | -3.01465 -0.148136 9e-06 0 0 -1.56693
2850 |
2851 | 1.50003
2852 |
2853 | 0.162255
2854 | 0
2855 | 0
2856 | 1.06881
2857 | 0
2858 | 0.981058
2859 |
2860 | 0 0 0 0 -0 0
2861 |
2862 |
2863 | 0 0 0 0 -0 0
2864 |
2865 |
2866 | 2.74778 0.545905 1
2867 |
2868 |
2869 |
2870 | 1
2871 |
2875 | 0.3 0.3 0.3 1
2876 | 0.7 0.7 0.7 1
2877 | 0.01 0.01 0.01 1
2878 | 0 0 0 1
2879 |
2880 |
2881 | 0
2882 | 1
2883 |
2884 |
2885 | 0
2886 | 10
2887 | 0 0 0 0 -0 0
2888 |
2889 |
2890 | 2.74778 0.545905 1
2891 |
2892 |
2893 |
2894 |
2895 |
2896 | 1
2897 | 1
2898 | 0 0 0
2899 | 0
2900 | 0
2901 |
2902 |
2903 | 1
2904 | 0
2905 | 0
2906 | 1
2907 |
2908 | 0
2909 |
2910 |
2911 |
2912 |
2913 | 0
2914 | 1e+06
2915 |
2916 |
2917 | 0
2918 | 1
2919 | 1
2920 |
2921 | 0
2922 | 0.2
2923 | 1e+13
2924 | 1
2925 | 0.01
2926 | 0
2927 |
2928 |
2929 | 1
2930 | -0.01
2931 | 0
2932 | 0.2
2933 | 1e+13
2934 | 1
2935 |
2936 |
2937 |
2938 |
2939 |
2940 |
2941 | -2.95631 -3.9379 9e-06 0 0 -1.56693
2942 |
2943 | 2.3361
2944 |
2945 | 0.25269
2946 | 0
2947 | 0
2948 | 3.75965
2949 | 0
2950 | 3.62299
2951 |
2952 | 0 0 0 0 -0 0
2953 |
2954 |
2955 | 0 0 0 0 -0 0
2956 |
2957 |
2958 | 4.27931 0.545905 1
2959 |
2960 |
2961 |
2962 | 1
2963 |
2967 | 0.3 0.3 0.3 1
2968 | 0.7 0.7 0.7 1
2969 | 0.01 0.01 0.01 1
2970 | 0 0 0 1
2971 |
2972 |
2973 | 0
2974 | 1
2975 |
2976 |
2977 | 0
2978 | 10
2979 | 0 0 0 0 -0 0
2980 |
2981 |
2982 | 4.27931 0.545905 1
2983 |
2984 |
2985 |
2986 |
2987 |
2988 | 1
2989 | 1
2990 | 0 0 0
2991 | 0
2992 | 0
2993 |
2994 |
2995 | 1
2996 | 0
2997 | 0
2998 | 1
2999 |
3000 | 0
3001 |
3002 |
3003 |
3004 |
3005 | 0
3006 | 1e+06
3007 |
3008 |
3009 | 0
3010 | 1
3011 | 1
3012 |
3013 | 0
3014 | 0.2
3015 | 1e+13
3016 | 1
3017 | 0.01
3018 | 0
3019 |
3020 |
3021 | 1
3022 | -0.01
3023 | 0
3024 | 0.2
3025 | 1e+13
3026 | 1
3027 |
3028 |
3029 |
3030 |
3031 |
3032 |
3033 | 4.03057 -6.47031 9e-06 0 -0 0.2833
3034 |
3035 | 2.3361
3036 |
3037 | 0.25269
3038 | 0
3039 | 0
3040 | 3.75965
3041 | 0
3042 | 3.62299
3043 |
3044 | 0 0 0 0 -0 0
3045 |
3046 |
3047 | 0 0 0 0 -0 0
3048 |
3049 |
3050 | 4.27931 0.545905 1
3051 |
3052 |
3053 |
3054 | 1
3055 |
3059 | 0.3 0.3 0.3 1
3060 | 0.7 0.7 0.7 1
3061 | 0.01 0.01 0.01 1
3062 | 0 0 0 1
3063 |
3064 |
3065 | 0
3066 | 1
3067 |
3068 |
3069 | 0
3070 | 10
3071 | 0 0 0 0 -0 0
3072 |
3073 |
3074 | 4.27931 0.545905 1
3075 |
3076 |
3077 |
3078 |
3079 |
3080 | 1
3081 | 1
3082 | 0 0 0
3083 | 0
3084 | 0
3085 |
3086 |
3087 | 1
3088 | 0
3089 | 0
3090 | 1
3091 |
3092 | 0
3093 |
3094 |
3095 |
3096 |
3097 | 0
3098 | 1e+06
3099 |
3100 |
3101 | 0
3102 | 1
3103 | 1
3104 |
3105 | 0
3106 | 0.2
3107 | 1e+13
3108 | 1
3109 | 0.01
3110 | 0
3111 |
3112 |
3113 | 1
3114 | -0.01
3115 | 0
3116 | 0.2
3117 | 1e+13
3118 | 1
3119 |
3120 |
3121 |
3122 |
3123 |
3124 |
3125 | -0.349699 -5.56946 9e-06 0 0 -1.56693
3126 |
3127 | 2.3361
3128 |
3129 | 0.25269
3130 | 0
3131 | 0
3132 | 3.75965
3133 | 0
3134 | 3.62299
3135 |
3136 | 0 0 0 0 -0 0
3137 |
3138 |
3139 | 0 0 0 0 -0 0
3140 |
3141 |
3142 | 4.27931 0.545905 1
3143 |
3144 |
3145 |
3146 | 1
3147 |
3151 | 0.3 0.3 0.3 1
3152 | 0.7 0.7 0.7 1
3153 | 0.01 0.01 0.01 1
3154 | 0 0 0 1
3155 |
3156 |
3157 | 0
3158 | 1
3159 |
3160 |
3161 | 0
3162 | 10
3163 | 0 0 0 0 -0 0
3164 |
3165 |
3166 | 4.27931 0.545905 1
3167 |
3168 |
3169 |
3170 |
3171 |
3172 | 1
3173 | 1
3174 | 0 0 0
3175 | 0
3176 | 0
3177 |
3178 |
3179 | 1
3180 | 0
3181 | 0
3182 | 1
3183 |
3184 | 0
3185 |
3186 |
3187 |
3188 |
3189 | 0
3190 | 1e+06
3191 |
3192 |
3193 | 0
3194 | 1
3195 | 1
3196 |
3197 | 0
3198 | 0.2
3199 | 1e+13
3200 | 1
3201 | 0.01
3202 | 0
3203 |
3204 |
3205 | 1
3206 | -0.01
3207 | 0
3208 | 0.2
3209 | 1e+13
3210 | 1
3211 |
3212 |
3213 |
3214 |
3215 |
3216 |
3217 | 5.87005 -8.18932 9e-06 0 0 -1.56693
3218 |
3219 | 2.3361
3220 |
3221 | 0.25269
3222 | 0
3223 | 0
3224 | 3.75965
3225 | 0
3226 | 3.62299
3227 |
3228 | 0 0 0 0 -0 0
3229 |
3230 |
3231 | 0 0 0 0 -0 0
3232 |
3233 |
3234 | 4.27931 0.545905 1
3235 |
3236 |
3237 |
3238 | 1
3239 |
3243 | 0.3 0.3 0.3 1
3244 | 0.7 0.7 0.7 1
3245 | 0.01 0.01 0.01 1
3246 | 0 0 0 1
3247 |
3248 |
3249 | 0
3250 | 1
3251 |
3252 |
3253 | 0
3254 | 10
3255 | 0 0 0 0 -0 0
3256 |
3257 |
3258 | 4.27931 0.545905 1
3259 |
3260 |
3261 |
3262 |
3263 |
3264 | 1
3265 | 1
3266 | 0 0 0
3267 | 0
3268 | 0
3269 |
3270 |
3271 | 1
3272 | 0
3273 | 0
3274 | 1
3275 |
3276 | 0
3277 |
3278 |
3279 |
3280 |
3281 | 0
3282 | 1e+06
3283 |
3284 |
3285 | 0
3286 | 1
3287 | 1
3288 |
3289 | 0
3290 | 0.2
3291 | 1e+13
3292 | 1
3293 | 0.01
3294 | 0
3295 |
3296 |
3297 | 1
3298 | -0.01
3299 | 0
3300 | 0.2
3301 | 1e+13
3302 | 1
3303 |
3304 |
3305 |
3306 |
3307 |
3308 |
3309 | 1.7146 -4.01354 9e-06 0 -0 0.2833
3310 |
3311 | 2.3361
3312 |
3313 | 0.25269
3314 | 0
3315 | 0
3316 | 3.75965
3317 | 0
3318 | 3.62299
3319 |
3320 | 0 0 0 0 -0 0
3321 |
3322 |
3323 | 0 0 0 0 -0 0
3324 |
3325 |
3326 | 4.27931 0.545905 1
3327 |
3328 |
3329 |
3330 | 1
3331 |
3335 | 0.3 0.3 0.3 1
3336 | 0.7 0.7 0.7 1
3337 | 0.01 0.01 0.01 1
3338 | 0 0 0 1
3339 |
3340 |
3341 | 0
3342 | 1
3343 |
3344 |
3345 | 0
3346 | 10
3347 | 0 0 0 0 -0 0
3348 |
3349 |
3350 | 4.27931 0.545905 1
3351 |
3352 |
3353 |
3354 |
3355 |
3356 | 1
3357 | 1
3358 | 0 0 0
3359 | 0
3360 | 0
3361 |
3362 |
3363 | 1
3364 | 0
3365 | 0
3366 | 1
3367 |
3368 | 0
3369 |
3370 |
3371 |
3372 |
3373 | 0
3374 | 1e+06
3375 |
3376 |
3377 | 0
3378 | 1
3379 | 1
3380 |
3381 | 0
3382 | 0.2
3383 | 1e+13
3384 | 1
3385 | 0.01
3386 | 0
3387 |
3388 |
3389 | 1
3390 | -0.01
3391 | 0
3392 | 0.2
3393 | 1e+13
3394 | 1
3395 |
3396 |
3397 |
3398 |
3399 |
3400 |
3401 | 15.5955 0.999523 -0.000417 0 0 -0.405308
3402 |
3403 | 2.91384
3404 |
3405 | 0.315184
3406 | 0
3407 | 0
3408 | 7.16085
3409 | 0
3410 | 6.99039
3411 |
3412 | 0 0 0 0 -0 0
3413 |
3414 |
3415 | 0 0 0 0 -0 0
3416 |
3417 |
3418 | 5.33763 0.545905 1
3419 |
3420 |
3421 |
3422 | 1
3423 |
3427 | 0.3 0.3 0.3 1
3428 | 0.7 0.7 0.7 1
3429 | 0.01 0.01 0.01 1
3430 | 0 0 0 1
3431 |
3432 |
3433 | 0
3434 | 1
3435 |
3436 |
3437 | 0
3438 | 10
3439 | 0 0 0 0 -0 0
3440 |
3441 |
3442 | 5.33763 0.545905 1
3443 |
3444 |
3445 |
3446 |
3447 |
3448 | 1
3449 | 1
3450 | 0 0 0
3451 | 0
3452 | 0
3453 |
3454 |
3455 | 1
3456 | 0
3457 | 0
3458 | 1
3459 |
3460 | 0
3461 |
3462 |
3463 |
3464 |
3465 | 0
3466 | 1e+06
3467 |
3468 |
3469 | 0
3470 | 1
3471 | 1
3472 |
3473 | 0
3474 | 0.2
3475 | 1e+13
3476 | 1
3477 | 0.01
3478 | 0
3479 |
3480 |
3481 | 1
3482 | -0.01
3483 | 0
3484 | 0.2
3485 | 1e+13
3486 | 1
3487 |
3488 |
3489 |
3490 |
3491 |
3492 |
3493 | -12.4356 -7.69108 9e-06 0 0 -0.406538
3494 |
3495 | 1.94722
3496 |
3497 | 0.463684
3498 | 0
3499 | 0
3500 | 0.4935
3501 | 0
3502 | 0.632648
3503 |
3504 | 0 0 0 0 -0 0
3505 |
3506 |
3507 | 0 0 0 0 -0 0
3508 |
3509 |
3510 | 1.42873 1.36291 1
3511 |
3512 |
3513 |
3514 | 1
3515 |
3519 | 0.3 0.3 0.3 1
3520 | 0.7 0.7 0.7 1
3521 | 0.01 0.01 0.01 1
3522 | 0 0 0 1
3523 |
3524 | 0
3525 | 1
3526 |
3527 |
3528 | 0
3529 | 10
3530 | 0 0 0 0 -0 0
3531 |
3532 |
3533 | 1.42873 1.36291 1
3534 |
3535 |
3536 |
3537 |
3538 |
3539 | 1
3540 | 1
3541 | 0 0 0
3542 | 0
3543 | 0
3544 |
3545 |
3546 | 1
3547 | 0
3548 | 0
3549 | 1
3550 |
3551 | 0
3552 |
3553 |
3554 |
3555 |
3556 | 0
3557 | 1e+06
3558 |
3559 |
3560 | 0
3561 | 1
3562 | 1
3563 |
3564 | 0
3565 | 0.2
3566 | 1e+13
3567 | 1
3568 | 0.01
3569 | 0
3570 |
3571 |
3572 | 1
3573 | -0.01
3574 | 0
3575 | 0.2
3576 | 1e+13
3577 | 1
3578 |
3579 |
3580 |
3581 |
3582 |
3583 |
3584 | -12.1551 -2.20744 9e-06 0 0 -0.406538
3585 |
3586 | 1.94722
3587 |
3588 | 0.463684
3589 | 0
3590 | 0
3591 | 0.4935
3592 | 0
3593 | 0.632648
3594 |
3595 | 0 0 0 0 -0 0
3596 |
3597 |
3598 | 0 0 0 0 -0 0
3599 |
3600 |
3601 | 1.42873 1.36291 1
3602 |
3603 |
3604 |
3605 | 1
3606 |
3610 | 0.3 0.3 0.3 1
3611 | 0.7 0.7 0.7 1
3612 | 0.01 0.01 0.01 1
3613 | 0 0 0 1
3614 |
3615 |
3616 | 0
3617 | 1
3618 |
3619 |
3620 | 0
3621 | 10
3622 | 0 0 0 0 -0 0
3623 |
3624 |
3625 | 1.42873 1.36291 1
3626 |
3627 |
3628 |
3629 |
3630 |
3631 | 1
3632 | 1
3633 | 0 0 0
3634 | 0
3635 | 0
3636 |
3637 |
3638 | 1
3639 | 0
3640 | 0
3641 | 1
3642 |
3643 | 0
3644 |
3645 |
3646 |
3647 |
3648 | 0
3649 | 1e+06
3650 |
3651 |
3652 | 0
3653 | 1
3654 | 1
3655 |
3656 | 0
3657 | 0.2
3658 | 1e+13
3659 | 1
3660 | 0.01
3661 | 0
3662 |
3663 |
3664 | 1
3665 | -0.01
3666 | 0
3667 | 0.2
3668 | 1e+13
3669 | 1
3670 |
3671 |
3672 |
3673 |
3674 |
3675 |
3676 | 2.67865 2.83156 9e-06 0 0 -0.406538
3677 |
3678 | 1.94722
3679 |
3680 | 0.463684
3681 | 0
3682 | 0
3683 | 0.4935
3684 | 0
3685 | 0.632648
3686 |
3687 | 0 0 0 0 -0 0
3688 |
3689 |
3690 | 0 0 0 0 -0 0
3691 |
3692 |
3693 | 1.42873 1.36291 1
3694 |
3695 |
3696 |
3697 | 1
3698 |
3702 | 0.3 0.3 0.3 1
3703 | 0.7 0.7 0.7 1
3704 | 0.01 0.01 0.01 1
3705 | 0 0 0 1
3706 |
3707 |
3708 | 0
3709 | 1
3710 |
3711 |
3712 | 0
3713 | 10
3714 | 0 0 0 0 -0 0
3715 |
3716 |
3717 | 1.42873 1.36291 1
3718 |
3719 |
3720 |
3721 |
3722 |
3723 | 1
3724 | 1
3725 | 0 0 0
3726 | 0
3727 | 0
3728 |
3729 |
3730 | 1
3731 | 0
3732 | 0
3733 | 1
3734 |
3735 | 0
3736 |
3737 |
3738 |
3739 |
3740 | 0
3741 | 1e+06
3742 |
3743 |
3744 | 0
3745 | 1
3746 | 1
3747 |
3748 | 0
3749 | 0.2
3750 | 1e+13
3751 | 1
3752 | 0.01
3753 | 0
3754 |
3755 |
3756 | 1
3757 | -0.01
3758 | 0
3759 | 0.2
3760 | 1e+13
3761 | 1
3762 |
3763 |
3764 |
3765 |
3766 |
3767 |
3768 | 4.37408 3.90111 9e-06 0 0 -0.406538
3769 |
3770 | 1.94722
3771 |
3772 | 0.463684
3773 | 0
3774 | 0
3775 | 0.4935
3776 | 0
3777 | 0.632648
3778 |
3779 | 0 0 0 0 -0 0
3780 |
3781 |
3782 | 0 0 0 0 -0 0
3783 |
3784 |
3785 | 1.42873 1.36291 1
3786 |
3787 |
3788 |
3789 | 1
3790 |
3794 | 0.3 0.3 0.3 1
3795 | 0.7 0.7 0.7 1
3796 | 0.01 0.01 0.01 1
3797 | 0 0 0 1
3798 |
3799 |
3800 | 0
3801 | 1
3802 |
3803 |
3804 | 0
3805 | 10
3806 | 0 0 0 0 -0 0
3807 |
3808 |
3809 | 1.42873 1.36291 1
3810 |
3811 |
3812 |
3813 |
3814 |
3815 | 1
3816 | 1
3817 | 0 0 0
3818 | 0
3819 | 0
3820 |
3821 |
3822 | 1
3823 | 0
3824 | 0
3825 | 1
3826 |
3827 | 0
3828 |
3829 |
3830 |
3831 |
3832 | 0
3833 | 1e+06
3834 |
3835 |
3836 | 0
3837 | 1
3838 | 1
3839 |
3840 | 0
3841 | 0.2
3842 | 1e+13
3843 | 1
3844 | 0.01
3845 | 0
3846 |
3847 |
3848 | 1
3849 | -0.01
3850 | 0
3851 | 0.2
3852 | 1e+13
3853 | 1
3854 |
3855 |
3856 |
3857 |
3858 |
3859 |
3860 | 0.353494 7.24728 9e-06 0 0 -0.406538
3861 |
3862 | 1.94722
3863 |
3864 | 0.463684
3865 | 0
3866 | 0
3867 | 0.4935
3868 | 0
3869 | 0.632648
3870 |
3871 | 0 0 0 0 -0 0
3872 |
3873 |
3874 | 0 0 0 0 -0 0
3875 |
3876 |
3877 | 1.42873 1.36291 1
3878 |
3879 |
3880 |
3881 | 1
3882 |
3886 | 0.3 0.3 0.3 1
3887 | 0.7 0.7 0.7 1
3888 | 0.01 0.01 0.01 1
3889 | 0 0 0 1
3890 |
3891 |
3892 | 0
3893 | 1
3894 |
3895 |
3896 | 0
3897 | 10
3898 | 0 0 0 0 -0 0
3899 |
3900 |
3901 | 1.42873 1.36291 1
3902 |
3903 |
3904 |
3905 |
3906 |
3907 | 1
3908 | 1
3909 | 0 0 0
3910 | 0
3911 | 0
3912 |
3913 |
3914 | 1
3915 | 0
3916 | 0
3917 | 1
3918 |
3919 | 0
3920 |
3921 |
3922 |
3923 |
3924 | 0
3925 | 1e+06
3926 |
3927 |
3928 | 0
3929 | 1
3930 | 1
3931 |
3932 | 0
3933 | 0.2
3934 | 1e+13
3935 | 1
3936 | 0.01
3937 | 0
3938 |
3939 |
3940 | 1
3941 | -0.01
3942 | 0
3943 | 0.2
3944 | 1e+13
3945 | 1
3946 |
3947 |
3948 |
3949 |
3950 |
3951 |
3952 | 6.7785 8.2182 9e-06 0 0 -0.406538
3953 |
3954 | 1.94722
3955 |
3956 | 0.463684
3957 | 0
3958 | 0
3959 | 0.4935
3960 | 0
3961 | 0.632648
3962 |
3963 | 0 0 0 0 -0 0
3964 |
3965 |
3966 | 0 0 0 0 -0 0
3967 |
3968 |
3969 | 1.42873 1.36291 1
3970 |
3971 |
3972 |
3973 | 1
3974 |
3978 | 0.3 0.3 0.3 1
3979 | 0.7 0.7 0.7 1
3980 | 0.01 0.01 0.01 1
3981 | 0 0 0 1
3982 |
3983 |
3984 | 0
3985 | 1
3986 |
3987 |
3988 | 0
3989 | 10
3990 | 0 0 0 0 -0 0
3991 |
3992 |
3993 | 1.42873 1.36291 1
3994 |
3995 |
3996 |
3997 |
3998 |
3999 | 1
4000 | 1
4001 | 0 0 0
4002 | 0
4003 | 0
4004 |
4005 |
4006 | 1
4007 | 0
4008 | 0
4009 | 1
4010 |
4011 | 0
4012 |
4013 |
4014 |
4015 |
4016 | 0
4017 | 1e+06
4018 |
4019 |
4020 | 0
4021 | 1
4022 | 1
4023 |
4024 | 0
4025 | 0.2
4026 | 1e+13
4027 | 1
4028 | 0.01
4029 | 0
4030 |
4031 |
4032 | 1
4033 | -0.01
4034 | 0
4035 | 0.2
4036 | 1e+13
4037 | 1
4038 |
4039 |
4040 |
4041 |
4042 |
4043 |
4044 | 9.80695 10.1149 9e-06 0 -0 0
4045 |
4046 | 1
4047 |
4048 | 0.145833
4049 | 0
4050 | 0
4051 | 0.145833
4052 | 0
4053 | 0.125
4054 |
4055 |
4056 |
4057 | 0 0 0 0 -0 0
4058 |
4059 |
4060 | 0.5
4061 | 1
4062 |
4063 |
4064 |
4065 | 1
4066 |
4070 | 0.3 0.3 0.3 1
4071 | 0.7 0.7 0.7 1
4072 | 0.01 0.01 0.01 1
4073 | 0 0 0 1
4074 |
4075 | 0
4076 | 1
4077 |
4078 |
4079 | 0
4080 | 10
4081 | 0 0 0 0 -0 0
4082 |
4083 |
4084 | 0.5
4085 | 1
4086 |
4087 |
4088 |
4089 |
4090 |
4091 | 1
4092 | 1
4093 | 0 0 0
4094 | 0
4095 | 0
4096 |
4097 |
4098 | 1
4099 | 0
4100 | 0
4101 | 1
4102 |
4103 | 0
4104 |
4105 |
4106 |
4107 |
4108 | 0
4109 | 1e+06
4110 |
4111 |
4112 | 0
4113 | 1
4114 | 1
4115 |
4116 | 0
4117 | 0.2
4118 | 1e+13
4119 | 1
4120 | 0.01
4121 | 0
4122 |
4123 |
4124 | 1
4125 | -0.01
4126 | 0
4127 | 0.2
4128 | 1e+13
4129 | 1
4130 |
4131 |
4132 |
4133 |
4134 |
4135 |
4136 | 9.90915 3.36462 9e-06 0 -0 0
4137 |
4138 | 1
4139 |
4140 | 0.166667
4141 | 0
4142 | 0
4143 | 0.166667
4144 | 0
4145 | 0.166667
4146 |
4147 |
4148 |
4149 | 0 0 0 0 -0 0
4150 |
4151 |
4152 | 1 1 1
4153 |
4154 |
4155 |
4156 | 1
4157 |
4161 | 0.3 0.3 0.3 1
4162 | 0.7 0.7 0.7 1
4163 | 0.01 0.01 0.01 1
4164 | 0 0 0 1
4165 |
4166 | 0
4167 | 1
4168 |
4169 |
4170 | 0
4171 | 10
4172 | 0 0 0 0 -0 0
4173 |
4174 |
4175 | 1 1 1
4176 |
4177 |
4178 |
4179 |
4180 |
4181 | 1
4182 | 1
4183 | 0 0 0
4184 | 0
4185 | 0
4186 |
4187 |
4188 | 1
4189 | 0
4190 | 0
4191 | 1
4192 |
4193 | 0
4194 |
4195 |
4196 |
4197 |
4198 | 0
4199 | 1e+06
4200 |
4201 |
4202 | 0
4203 | 1
4204 | 1
4205 |
4206 | 0
4207 | 0.2
4208 | 1e+13
4209 | 1
4210 | 0.01
4211 | 0
4212 |
4213 |
4214 | 1
4215 | -0.01
4216 | 0
4217 | 0.2
4218 | 1e+13
4219 | 1
4220 |
4221 |
4222 |
4223 |
4224 |
4225 |
4226 | 9.11198 2.92169 9e-06 0 -0 0
4227 |
4228 | 1
4229 |
4230 | 0.166667
4231 | 0
4232 | 0
4233 | 0.166667
4234 | 0
4235 | 0.166667
4236 |
4237 |
4238 |
4239 | 0 0 0 0 -0 0
4240 |
4241 |
4242 | 1 1 1
4243 |
4244 |
4245 |
4246 | 1
4247 |
4251 | 0.3 0.3 0.3 1
4252 | 0.7 0.7 0.7 1
4253 | 0.01 0.01 0.01 1
4254 | 0 0 0 1
4255 |
4256 | 0
4257 | 1
4258 |
4259 |
4260 | 0
4261 | 10
4262 | 0 0 0 0 -0 0
4263 |
4264 |
4265 | 1 1 1
4266 |
4267 |
4268 |
4269 |
4270 |
4271 | 1
4272 | 1
4273 | 0 0 0
4274 | 0
4275 | 0
4276 |
4277 |
4278 | 1
4279 | 0
4280 | 0
4281 | 1
4282 |
4283 | 0
4284 |
4285 |
4286 |
4287 |
4288 | 0
4289 | 1e+06
4290 |
4291 |
4292 | 0
4293 | 1
4294 | 1
4295 |
4296 | 0
4297 | 0.2
4298 | 1e+13
4299 | 1
4300 | 0.01
4301 | 0
4302 |
4303 |
4304 | 1
4305 | -0.01
4306 | 0
4307 | 0.2
4308 | 1e+13
4309 | 1
4310 |
4311 |
4312 |
4313 |
4314 |
4315 | 0
4316 | 1
4317 |
4318 |
4319 |
--------------------------------------------------------------------------------
/mod_turtlebot_description/turtlebot_description.tar.gz:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/g40st/ROS_maze_challenge/4bf749570c25071129727de7f5a913b6eff7fe0e/mod_turtlebot_description/turtlebot_description.tar.gz
--------------------------------------------------------------------------------