diff --git a/blaser_ros/BlaserCommandsReadMe.md b/blaser_ros/BlaserCommandsReadMe.md deleted file mode 100644 index 2631115..0000000 --- a/blaser_ros/BlaserCommandsReadMe.md +++ /dev/null @@ -1,50 +0,0 @@ - -# Blaser Commands Readme - -## -------Quick start Method-------- - - ### Step 0: Plug in Blaser's USB3 and USB2 cable to NUC - You will see the LED and Blue laser pulse once, then Blue laser turns on, then the sensor is ready! - - ### Short-Step 1: Bring up Blaser sensor - `roslaunch blaser_ros bring_up_blaser.launch` - - ### Short-Step 2: Start up Blaser SLAM backend and Mapping GUI - `roslaunch blaser_ros trl6_slam.launch` - -## -------Step-by-Step Method-------- - - ### Step 0: Plug in Blaser's USB3 and USB2 cable to NUC - You will see the LED and Blue laser pulse once, then Blue laser turns on, then the sensor is ready! - - ### Step 1: open roscore at terminal #1 - `roscore` - - ### Step 2: Allow port access for Blaser low-level control - `sudo chmod 666 /dev/ttyACM0` - - ### Step 3: Turn on Blaser Camera device driver - `rosrun blaser_pcl_core handheld_blaser_v30_node --lexp_val 50` - - ### Step 4: Start up Blaser Machine Vision frontend - `roslaunch blaser_ros trl6_sensor_proc.launch` - - ### Step 5: Start up Blaser SLAM backend and Mapping GUI - `roslaunch blaser_ros trl6_slam.launch` - -## -------How to stitch point cloud-------- - - ### To use mapping GUI: - ### You need to change the "Mapping status" Slider/Parameter: - ### - 0: Stop Map Generation - ### - 1: Start Stitching Point Cloud Map - ### - 2: Clear Map - - ### Always start from 0(stop) stage, when Blaser initialized, then trun on 1(start) to stitch point cloud, and end with move back to 0 to stop. - ### you can also slide it to 2(Clear map). - -## -------How to Save point cloud-------- - - ### Save pointcloud (colorized, accumulated) - `rosrun pcl_ros pointcloud_to_pcd input:=/slam_estimator/laser_pcd` - `rosrun pcl_ros pointcloud_to_pcd input:=/laser_detector/laser_points` diff --git a/blaser_ros/CMakeLists.txt b/blaser_ros/CMakeLists.txt deleted file mode 100644 index 3d82f87..0000000 --- a/blaser_ros/CMakeLists.txt +++ /dev/null @@ -1,100 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(blaser_ros) - -set(CMAKE_BUILD_TYPE Release) - -execute_process(COMMAND lsb_release -cs - OUTPUT_VARIABLE LSB_RELEASE_ID_SHORT -) - -if(${LSB_RELEASE_ID_SHORT} MATCHES "bionic") - set(CMAKE_CXX_STANDARD_REQUIRED 11) - message("-- Systemm version: ${LSB_RELEASE_ID_SHORT}, set to C++11") -elseif(${LSB_RELEASE_ID_SHORT} MATCHES "focal") - set(CMAKE_CXX_STANDARD_REQUIRED 11) - message("-- Systemm version: ${LSB_RELEASE_ID_SHORT}, set to C++14") -endif() - -set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") - -find_package(catkin REQUIRED COMPONENTS - geometry_msgs - pcl_conversions - pcl_ros - roscpp - sensor_msgs - std_msgs - cv_bridge - camera_model - dynamic_reconfigure -) - -find_package(OpenCV REQUIRED) -find_package(Eigen3 REQUIRED) -find_package(PythonLibs 2.7) - -generate_dynamic_reconfigure_options( - cfg/LaserDetector.cfg -) - -catkin_package( - INCLUDE_DIRS include - LIBRARIES laser_stripe - CATKIN_DEPENDS geometry_msgs pcl_conversions pcl_ros roscpp sensor_msgs std_msgs - dynamic_reconfigure -# DEPENDS system_lib -) - -########### -## Build ## -########### - -## Specify additional locations of header files -## Your package locations should be listed before other locations -include_directories( - include - ${catkin_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIR} - /usr/include/python3.8 -) - -## Declare a C++ library -add_library(laser_stripe - src/laser_stripe_detector.cpp - src/laser_geometry_utils.cpp -) -target_link_libraries(laser_stripe ${catkin_LIBRARIES} ${OpenCV_LIBS}) - -add_executable(laser_stripe_detector_test - src/test/laser_stripe_detector_test.cpp - src/laser_stripe_detector.cpp) -target_link_libraries(laser_stripe_detector_test ${catkin_LIBRARIES} ${OpenCV_LIBS}) - -add_executable(laser_calib - src/laser_calib.cpp - src/laser_calib_node.cpp - src/laser_stripe_detector.cpp - src/util/cv_click_handler.cpp) -target_link_libraries(laser_calib ${catkin_LIBRARIES} ${OpenCV_LIBS} - ${PYTHON_LIBRARIES}) - - -add_executable(laser_detector - src/laser_detector.cpp - src/laser_detector_node.cpp - src/laser_geometry_utils.cpp - src/laser_stripe_detector.cpp - ) -add_dependencies(laser_detector ${PROJECT_NAME}_gencfg) -target_link_libraries(laser_detector ${catkin_LIBRARIES} ${OpenCV_LIBS}) - -add_executable(laser_rgb_estimator - src/laser_rgb_estimator.cpp - src/util/geometry_util.cpp - src/laser_rgb_estimator_node.cpp) -target_link_libraries(laser_rgb_estimator ${catkin_LIBRARIES} ${OpenCV_LIBS}) - -add_executable(resolution_analyser - src/resolution_analyser.cpp) -target_link_libraries(resolution_analyser ${catkin_LIBRARIES} ${OpenCV_LIBS} - ${PYTHON_LIBRARIES}) diff --git a/blaser_ros/README.md b/blaser_ros/README.md deleted file mode 100644 index 836c0cc..0000000 --- a/blaser_ros/README.md +++ /dev/null @@ -1,378 +0,0 @@ -# BLASER_ROS - -This ROS package contains software for hand-held Blaser, including - -* Laser plane calibration -* Laser points detection and triangulation -* Blaser resolution (sensitivity) analyzation -* Laser point cloud coloring (RGB value estimation), which is also implemented - in the SLAM package (`blaser_slam`) - -The library `camera_model` (forked from **camodocal**) is used extensively in this -package. - -This tutorial contains three sections - -0. Installing dependencies and Blaser software -1. Running SLAM (involves calibration & running triangulation) -2. Performing sensitivity evaluation - -## 0. Installation -This section is about how to set up Blaser software on a new computer. - -### 0.0 Environment -Blaser uses Ubuntu 18.04 and ROS Melodic ([Installation](http://wiki.ros.org/melodic/Installation/Ubuntu)). - -### 0.1 Install Dependencies - -1. First make a directory for all Blaser dependencies -```shell -mkdir ~/blaser_dependencies -``` - -2. Install [Matio](https://github.com/tbeu/matio) -```shell -cd ~/blaser_dependencies -git clone git://git.code.sf.net/p/matio/matio -cd matio -./autogen.sh -./configure -make -sudo make install -``` -3. Install [Ceres Solver](http://ceres-solver.org/installation.html) -```shell -cd ~/blaser_dependencies -wget http://ceres-solver.org/ceres-solver-1.14.0.tar.gz -sudo apt-get install libgoogle-glog-dev libgflags-dev libatlas-base-dev libsuitesparse-dev -tar zxf ceres-solver-1.14.0.tar.gz -mkdir ceres-bin -cd ceres-bin -cmake ../ceres-solver-1.14.0 -make -j8 -sudo make install -``` -4. Install [XIMEA Linux Software packge](https://www.ximea.com/support/wiki/apis/XIMEA_Linux_Software_Package) -```shell -cd ~/blaser_dependencies -wget https://www.ximea.com/downloads/recent/XIMEA_Linux_SP.tgz -tar xzf XIMEA_Linux_SP.tgz -mv package ximea_linux_sp -cd ximea_linux_sp -sudo ./install -``` -5. Python libraries -```sh -sudo apt-get install python-matplotlib python-numpy -``` -6. Enable high speed USB and USB permission -```shell -sudo adduser $USER dialout -# if file /etc/rc.local already exists -echo 'echo 0 > /sys/module/usbcore/parameters/usbfs_memory_mb' | sudo tee -a /etc/rc.local -# if file /etc/rc.local does not exist -printf '%s\n' '#!/bin/bash' 'echo 0 > /sys/module/usbcore/parameters/usbfs_memory_mb' | sudo tee /etc/rc.local; sudo chmod +x /etc/rc.local -# reboot for the changes to take effect -``` - -### 0.2 Install Blaser software -1. Create a catkin workspace for blaser: -```sh -mkdir -p ~/blaser_ws/src && cd ~/blaser_ws/src -``` -2. Then clone the repo `blaser_mapping`: -```sh -git clone https://github.com/biorobotics/blaser_mapping.git -``` -3. Clone the Blaser driver called `blaser-pcl-core` located in another Git repo. -```sh -git clone https://github.com/biorobotics/blaser-pcl-core.git -``` -4. build -```shell -cd ~/blaser_ws/ -catkin_make -j1 -``` -The compilation will take some time. Please wait. - -Once the compilation is done, you would be required to add a line to `~/.bashrc` file. -Open the the bashrc file by running the following command in a terminal. - -`gedit ~/.bashrc` - -This will open the text editor and add the following line at the end of the file. - - ``` - source ~/blaser_ws/devel/setup.bash - ``` - - Save and close the text editor and run `source ~/.bashrc` for the changes to take effect. - - You can test your installation by running - - ``` - roscd blaser_ros - ``` - Upon running the above commnand, your current directory should change to - `~/blaser_ws` . - -## Run Blaser -Now you can run Blaser following [this tutorial](https://github.com/biorobotics/blaser_mapping/blob/master/blaser_ros/README.md).\ -If the Blaser is already calibrated, you can skip Step 1.2 Sensor Calibration in the linked tutorial. - -## 1. Running SLAM - -Check out our [video tutorial](https://drive.google.com/file/d/15whcikrRbo9H2MsuE5pYbJ87K-Ah5hBY/view). - -To run SLAM, there are three steps involved. Firstly, you should run the sensor -driver for your specific Blaser prototype and acquire raw sensor topics. Next, -calibrate the camera intrinsics, camera-IMU extrinsics, and camera-laser extrinsics and load the -calibration results into a yaml file. Finally, -execute SLAM by running both the SLAM front-end and the back-end. - -### 1.1 Running sensor driver - -Run the driver for your specific Blaser prototype. - -For the Blaser 3.0 (sent to Boeing version), see [`blaser-pcl-core`](https://github.com/biorobotics/blaser-pcl-core). - -Make sure you have three ROS topics: - -1. Visual frames (sensor_msgs/Image, image stream observing the environment with - the laser turned off, at least 20 hz) -2. Profiling frames (sensor_msgs/Image, image stream observing the laser stripe, - at least 20 hz) -3. IMU data (sensor_msgs/Imu, at least 100 hz) - -Visualize these topics (use rqt_image_view and rqt_plot) to check if they are -valid. Adjust camera exposure, LED brightness, and laser brightness to make sure -that - -- Visual frames are neutrally exposed. -- Profiling frames are under-exposed (dark) while the laser stripe is clearly -visible but not over-exposed (RGB channel values should not reach 255). If laser -is over-exposed, shorten camera exposure time. -- The clock of the camera and the IMU are synced. - -Generally, short camera exposure time is preferred to reduce motion blur. -Therefore, it is good practice to use maximum LED and laser brightness for -SLAM. - -### 1.2 Sensor calibration - -There are three calibration tasks: camera intrinsics, camera-IMU extrinsics, and -camera-laser extrinsics. - -prepare a folder for this calibration trial and run some basic commands: - -Say you want to name your trial folder TRIAL_FOLDER (e.g. boeing-demo) -``` -$ roscd blaser_ros; mkdir -p calib_data/TRIAL_FOLDER; cd calib_data/TRIAL_FOLDER - -$ mkdir intrinsics; mkdir laser_plane; scp ~/catkin_ws/blaser_ws/src/blaser_ros/config/laser_calib.yaml . (don't forget the "." at the end!!) - -$ scp -r ~/catkin_ws/blaser_ws/src/blaser_ros/config/kalibr_data . (don't forget the "." at the end!!) - -$ scp ~/catkin_ws/blaser_ws/src/blaser_ros/config/trl6_slam.yaml .; mv trl6_slam.yaml slam.yaml -``` - -These commands create a calibration folder and copy sample yaml files, which will -be loaded with your own calibration data later. - -#### Camera intrinsics - -**First collect images observing a checkerboard from various angles.** -It is a good idea to use ROS tool **camera_calibration** to collect images. - -1. Run the Blaser driver -2. `cd ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/intrinsics` -3. Run the ros calibration tool -`rosrun camera_calibration cameracalibrator.py --size 10x7 --square 0.005 image:=/image_topic` -4. Follow its instructions to collect images to satisfy all its score bars -5. Click calibrate, and wait until it finishes -6. Click save to save the images and the calibration results as a tarball. The - terminal will say the tarball's location, usually in `/tmp/`. -7. Move the tarball to our data folder and extract the tarball -`mv /tmp/calibrationdata.tar.gz .; tar xvf calibrationdata.tar.gz; rm calibrationdata.tar.gz; rm ost.*` - -**Secondly, use package `camera_model` to perform calibration.** -`rosrun camera_model Calibration -w 7 -h 10 -s 5 -i ./ -v --camera-model mei` - -The camera model parameters will be saved to `camera_camera_calib.yaml`. - -Use help (`rosrun camera_model Calibration --help`) to see all the parameters. - -Be careful about what camera model you use. For a narrow FoV camera without huge -distortion, use `pinhole` model should suffice. If you use a large FoV camera -with a lot of distortion, use `mei` or `kannala-brandt`. Typically you can try -all the camera models and choose the one with the smallest reprojection error. - -**Finally, examine the intrinsics parameters and result** - -1. Is the reprojection error reasonable? (should be at least < 1.0 px) -2. Is fx and fy similar? -3. Is cx and cy reasonable? cx ~ width / 2, cy ~ height / 2 -4. Is image height and width correct? - -You can also generate undistorted images. All the straight lines in real world -should appear as perfectly straight on the image. - -#### Camera-IMU extrinsics - -Now we have to calibrate the Euclidean transformation between the IMU frame and -the camera frame. - -We use **Kalibr** to perform this calibration. It is a powerful calibration tool -that can calibrate camera intrinsics, camera-IMU extrinsics, multi-camera -extrinsics, etc. Follow its instructions for installation and usage. - -A few tips: - -* Use a different catkin workspace for **Kalibr**, since it uses `catkin build`. -* Since extrinsics calibration requires camera instrinsics, you may need to redo - camera intrinsics calibration using Kalibr, if the camera model used in - `camera_model` is not compatibale with Kalibr. -* You need IMU parameters (random walk and noise for accelerometer and - gyroscope) - for both extrinsics calibration and SLAM. `Kalibr`'s wiki has a tutorial on - how to determine these four parameters. You can also use `imu_utils` package - on Github to calibrate them. -* **Kalibr**'s wiki has some great tutorials on IMU modeling. - -Trouble shooting for installing Kalibr: -1. Issue 1: Cannot find package when enter `$sudo pip install python-igraph --upgrade` -Solution: Install older version of python-igraph. Still may need to `apt install bison byacc flex`. -2. Issue 2: [Cannot reach TAMU server when building Kalibr](https://github.com/h2r/kuka_brown/issues/1) -Solution: Modify CMakeList file in SuiteSparse package and add --no-check-certificate between wget and TAMU URL - -Use the following steps to calibrate -``` -$ cd ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/intrinsics - -(We recalibrate the camera intrinsics using the pinhole model. However, we only use it for imu-camera extrinsics calibration, NOT in SLAM!) -$ rosrun camera_model Calibration -w 10 -h 7 -s 5 -i ./ -v --camera-model pinhole - -$ cd ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/kalibr_data; mkdir kalibr_results - -Then update the camchain.yaml file with the new intrinsics from ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/intrinsics/camera_camera_calib.yaml - -Then collect a bag file using aprilgrid of either 8.8mm or 5.5mm grids: - -$ rosbag record --duration=100 -O data.bag /blaser_camera/image_hexp /imu - -$ cd kalibr_results; activate_kalibr - -$ rosrun kalibr kalibr_calibrate_imu_camera --bag ../data.bag --cam ../camchain.yaml --imu ../imu.yaml --target ../april_8mm.yaml -``` - -The calibration may take a long time. After it finishes, examine the rotation -and translation result. You should have a pretty good guess from the mechanical -design CAD file or by just looking at the sensor. - -#### Camera-laser extrinsics - -The extrinsics parameters between camera and laser is the 3D position of the -laser plane in the camera reference frame, defined as $ax + by + cz + d = 0$. In -order to determine the plane's position, we take sample points from this plane -and then try to fit a 3D plane to these 3D points. We obtain sample points from -images of a checkerboard where the laser stripe is projected onto the -checkerboard. Since the checkerboard defines a 3D plane, we can get a 3D point -position for each 2D laser point on the image, which is the intersection between -the checkerboard plane and the line-of-sight ray. - -We first need to make sure that the laser stripe detection is working. The laser -stripe detector basically performs an HSV filter with five parameters hue_min, -hue_max, sat_min, val_min, and val_ratio, defining a 3D range filter H in \[hue_low, -hue_high\], S in \[sat_low, 255\], and V in -\[max(val_low, image_max_val * val_ratio), 255\]. Note that V range is dynamic -and is set with every image. - -When using red laser and you want a hue range containing the hue=180 value, -set hue_min > hue_max and the program will generate two separate hue ranges: -one is \[hue_min, 180\] and the other is \[0, hue_max\]. - -To set these parameters, first use `python scripts/im_saver.py [image_topic]` to -save a couple of sample images, then use `python scripts/im_hsv_viewer.py -[image_file]` to determine the HSV value of the laser stripe and set appropriate -values for the threshold parameters. Load these values in a config file (todo -give example config and dir), which will be used in the calibration later. - -To test these parameters, run `laser_stripe_detector` node with sample images -and the config file. (todo turn on lsd visualization). - -Perform laser calibration using the following steps: - -$ cd ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER; cd laser_plane (Stay in this folder throughout Step 2!) - -$ rosrun blaser_ros im_saver.py /blaser_camera/image_lexp - -Then press 's' to save the current image. Use a [foot switch](https://www.amazon.com/s?k=foot+switch+usb) if it helps. -Collect 10~15 images with varying checkerboard depth. -Avoid collision between laser line and checkerboard corners. - -Then update the laser_calib.yaml (copy from blaser_ros/config/) file with the new camera intrinsics you got in Step 1. -The intrinsics yaml file was generated in ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/intrinsics/camera_camera_calib.yaml - -$ rosrun blaser_ros laser_calib -i ./ -c laser_calib.yaml (Press 'y' to accept, 'n' to reject current image) - -$ python ../../../scripts/vis_laser_calib_result.py calib_results.txt - -#### Finally, load your calibrated parameters to the SLAM yaml file. - -1. The big yaml file is: ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/trl6_slam.yaml -2. Camera intrinsics result is in: ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/laser_plane/laser_calib.yaml -3. Laser-camera extrinsics is in : ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/laser_plane/calib_results.txt -4. Camera-imu extrinsics is in : cd ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/kalibr_data/kalibr_results/results-imucam-..data.txt (Please copy the T_ic!) - -After updating the yaml file, here's the final command before actually running slam! -$ cd ~/catkin_ws/blaser_ws/src/blaser_ros/config; rm trl6_slam.yaml; scp ~/catkin_ws/blaser_ws/src/blaser_ros/calib_data/TRIAL_FOLDER/trl6_slam.yaml . (Don't forget the dot!!) - -If your SLAM yaml file has a different name, simply update the name in `trl6_sensor_proc.launch` and `trl6_slam.launch`. - -### 1.3 Run SLAM -1. Device driver -`rosrun blaser_pcl_core handheld_blaser_v30_node --lexp_val 50` -2. SLAM frontend -`roslaunch blaser_ros trl6_sensor_proc.launch` -3. SLAM backend -`roslaunch blaser_ros trl6_slam.launch` -4. Use `rqt_reconfigure` to control the mapping process (start / stop / clear) mapping. Mapping status: - - 0: Stop - - 1: Start - - 2: Clear -`rosrun rqt_reconfigure rqt_reconfigure` -5. Save pointcloud (colorized, accumulated) -For 3D map: `rosrun pcl_ros pointcloud_to_pcd input:=/slam_estimator/laser_pcd` -For raw laser scans `rosrun pcl_ros pointcloud_to_pcd input:=/laser_detector/laser_points` - -## 2. Perform sensitivity analysis -The sensitivity of the Blaser sensor is defined as the shift of the laser stripe -on the image in response to a 1 mm depth change. It as a unit of pixel/mm. The -higher the sensitivity, the higher the 3D measurement precision. Assuming that -the laser detection on the image has an absolute error upper bound of 0.5 pixels, -then the sensor's 3D measurement precision is 0.5 pixel / sensitivity. E.g., if -the sensitivity is 5 pixel/mm, then the precision is 0.1 mm. - -The sensitivity analysis tool can be used to theoretically analyze the sensor's -precision, but also to determine the best sensor design in terms of laser leaning -angle (angle between the laser plane and the camera optical axis, 0 being parallel). - -To perform the sensitivity analysis, run -`rosrun blaser_ros resolution_analyser `. - -A sample sensitivty_analysis_yaml_file can be found at -`blaser_ros/config/resolution_analyser/resolution_analyser.yaml`. - -## Using ROS Bag with Blaser - -If you want to record sensor data and run SLAM with recorded data offline, use -compressed image topics instead of raw image topics. This can save you GBs of -storage space. Here's what I typically do: - -1. Record: record raw sensor data only, including raw imu data and compressed -image topics. The compressed image topics are already published by the driver. -`rosbag record /imu /blaser_camera/image_hexp/compressed /blaser_camera/image_lexp/compressed` -2. Replay: since the image topics are compressed, you need to *republish* the -image topics. This is implemented in the `sensor_proc.launch` file using the -`republish_compressed_image` argument, whose default value is 0. Use the -following command when using rosbags. -`roslaunch blaser_ros xx_sensor_proc.launch republish_compressed_image:=1` diff --git a/blaser_ros/calib_result.txt b/blaser_ros/calib_result.txt deleted file mode 100644 index 5841e56..0000000 --- a/blaser_ros/calib_result.txt +++ /dev/null @@ -1,5606 +0,0 @@ -laser plane parameters (ax + by + cx + d = 0): --6494.7,31.7601,-100,151.818 -laser point positions in camera frame: -lp: 0.0223723,-0.0195598,0.0563187 -lp: 0.0223641,-0.0194623,0.0563286 -lp: 0.0223598,-0.019365,0.0563371 -lp: 0.0223556,-0.0192678,0.0563456 -lp: 0.022354,-0.0191707,0.0563532 -lp: 0.0223495,-0.0190738,0.0563618 -lp: 0.0223646,-0.0189772,0.056364 -lp: 0.0223585,-0.0188805,0.056373 -lp: 0.0223782,-0.0187842,0.0563736 -lp: 0.022372,-0.0186877,0.0563827 -lp: 0.0223696,-0.0185913,0.0563906 -lp: 0.0223683,-0.018495,0.0563981 -lp: 0.0223959,-0.0183993,0.0563961 -lp: 0.0223895,-0.0183032,0.0564052 -lp: 0.0223596,-0.0182068,0.0564221 -lp: 0.0223761,-0.0181112,0.0564237 -lp: 0.022341,-0.0180149,0.0564422 -lp: 0.0223431,-0.0179193,0.0564485 -lp: 0.0223713,-0.0178243,0.0564463 -lp: 0.0223976,-0.0177293,0.0564447 -lp: 0.022394,-0.0176339,0.0564528 -lp: 0.0223945,-0.0175387,0.0564596 -lp: 0.0223989,-0.0174436,0.0564652 -lp: 0.0224562,-0.0173495,0.0564534 -lp: 0.0224578,-0.0172546,0.0564598 -lp: 0.0224538,-0.0171597,0.0564681 -lp: 0.0224475,-0.0170648,0.0564771 -lp: 0.0224428,-0.0169701,0.0564856 -lp: 0.0224383,-0.0168755,0.056494 -lp: 0.0224683,-0.0167815,0.0564911 -lp: 0.0224371,-0.0166866,0.0565082 -lp: 0.0224586,-0.0165927,0.0565081 -lp: 0.0224541,-0.0164984,0.0565165 -lp: 0.0224476,-0.0164042,0.0565255 -lp: 0.0224468,-0.0163102,0.0565327 -lp: 0.0224726,-0.0162167,0.0565311 -lp: 0.0224663,-0.0161227,0.05654 -lp: 0.0224311,-0.0160285,0.0565584 -lp: 0.0224224,-0.0159347,0.0565681 -lp: 0.0224163,-0.0158411,0.056577 -lp: 0.0224383,-0.0157479,0.0565766 -lp: 0.0224392,-0.0156545,0.0565832 -lp: 0.0224376,-0.0155612,0.0565906 -lp: 0.0224349,-0.0154679,0.0565983 -lp: 0.0224365,-0.0153748,0.0566046 -lp: 0.0224725,-0.0152822,0.0565996 -lp: 0.022431,-0.0151886,0.05662 -lp: 0.0224225,-0.0150956,0.0566296 -lp: 0.0224196,-0.0150027,0.0566374 -lp: 0.0224785,-0.0149107,0.0566249 -lp: 0.0224842,-0.0148181,0.0566298 -lp: 0.0224785,-0.0147254,0.0566385 -lp: 0.0224756,-0.0146329,0.0566462 -lp: 0.0224635,-0.0145403,0.056657 -lp: 0.0224583,-0.0144478,0.0566654 -lp: 0.0224605,-0.0143556,0.0566715 -lp: 0.0224972,-0.0142638,0.0566662 -lp: 0.0224985,-0.0141716,0.0566726 -lp: 0.0224888,-0.0140794,0.0566825 -lp: 0.0224835,-0.0139873,0.056691 -lp: 0.0225085,-0.0138957,0.0566895 -lp: 0.0225045,-0.0138038,0.0566976 -lp: 0.0225037,-0.013712,0.0567046 -lp: 0.0224997,-0.0136202,0.0567126 -lp: 0.0224947,-0.0135284,0.0567209 -lp: 0.0225283,-0.0134372,0.0567167 -lp: 0.0225015,-0.0133454,0.0567321 -lp: 0.0224935,-0.0132538,0.0567415 -lp: 0.0224806,-0.0131623,0.0567524 -lp: 0.0224697,-0.0130708,0.0567627 -lp: 0.0224673,-0.0129795,0.0567701 -lp: 0.0224623,-0.0128883,0.0567785 -lp: 0.0224608,-0.0127971,0.0567856 -lp: 0.0224582,-0.012706,0.0567932 -lp: 0.0224559,-0.0126149,0.0568006 -lp: 0.0224532,-0.0125239,0.0568081 -lp: 0.0224499,-0.012433,0.0568159 -lp: 0.0224462,-0.0123421,0.0568237 -lp: 0.0224658,-0.0122516,0.056824 -lp: 0.0224629,-0.0121608,0.0568316 -lp: 0.0224612,-0.0120701,0.0568388 -lp: 0.0224584,-0.0119795,0.0568464 -lp: 0.0224567,-0.0118889,0.0568536 -lp: 0.0224535,-0.0117984,0.0568613 -lp: 0.0224524,-0.0117079,0.0568682 -lp: 0.0224509,-0.0116175,0.0568754 -lp: 0.0224508,-0.0115272,0.056882 -lp: 0.0224481,-0.0114369,0.0568895 -lp: 0.0224444,-0.0113466,0.0568973 -lp: 0.0224413,-0.0112564,0.0569049 -lp: 0.0224378,-0.0111663,0.0569127 -lp: 0.0224348,-0.0110762,0.0569203 -lp: 0.0224327,-0.0109862,0.0569276 -lp: 0.0224308,-0.0108962,0.0569348 -lp: 0.0224295,-0.0108062,0.0569418 -lp: 0.0224281,-0.0107164,0.0569489 -lp: 0.0224272,-0.0106265,0.0569557 -lp: 0.0224242,-0.0105367,0.0569633 -lp: 0.0224206,-0.010447,0.0569711 -lp: 0.0224178,-0.0103573,0.0569786 -lp: 0.0224163,-0.0102676,0.0569856 -lp: 0.022417,-0.010178,0.056992 -lp: 0.0224161,-0.0100885,0.0569988 -lp: 0.0224145,-0.00999898,0.0570059 -lp: 0.0224139,-0.00990952,0.0570127 -lp: 0.0224455,-0.00982035,0.0570089 -lp: 0.0224487,-0.009731,0.0570144 -lp: 0.0224482,-0.00964166,0.0570211 -lp: 0.0224669,-0.00955251,0.0570215 -lp: 0.0224653,-0.00946325,0.0570286 -lp: 0.022465,-0.00937403,0.0570352 -lp: 0.0224646,-0.00928485,0.0570419 -lp: 0.0224669,-0.00919573,0.0570477 -lp: 0.0224656,-0.00910662,0.0570546 -lp: 0.0224657,-0.00901757,0.0570611 -lp: 0.0224881,-0.0089287,0.0570603 -lp: 0.0224865,-0.0088397,0.0570674 -lp: 0.0224849,-0.00875074,0.0570744 -lp: 0.0224847,-0.00866182,0.057081 -lp: 0.0225148,-0.00857314,0.0570777 -lp: 0.0225136,-0.00848428,0.0570846 -lp: 0.0225113,-0.00839545,0.0570919 -lp: 0.022486,-0.00830649,0.0571066 -lp: 0.0224841,-0.00821773,0.0571138 -lp: 0.0224796,-0.00812898,0.0571217 -lp: 0.0224845,-0.00804033,0.0571266 -lp: 0.0225255,-0.00795193,0.0571197 -lp: 0.0225517,-0.00786347,0.0571177 -lp: 0.0225217,-0.00777468,0.057134 -lp: 0.0225152,-0.00768607,0.0571426 -lp: 0.0224791,-0.00759731,0.0571609 -lp: 0.0224751,-0.00750878,0.0571687 -lp: 0.0224772,-0.00742031,0.0571745 -lp: 0.0225394,-0.00733221,0.0571606 -lp: 0.0225411,-0.00724379,0.0571666 -lp: 0.022542,-0.00715538,0.0571728 -lp: 0.0225358,-0.00706696,0.0571813 -lp: 0.0225076,-0.00697845,0.057197 -lp: 0.0225008,-0.00689008,0.0572056 -lp: 0.0225005,-0.00680177,0.0572122 -lp: 0.0225326,-0.00671366,0.0572082 -lp: 0.0225399,-0.00662543,0.0572123 -lp: 0.0225466,-0.00653722,0.0572166 -lp: 0.0225531,-0.00644903,0.0572209 -lp: 0.0225592,-0.00636086,0.0572254 -lp: 0.0225838,-0.0062728,0.0572238 -lp: 0.0225811,-0.00618462,0.0572311 -lp: 0.0225525,-0.00609634,0.057247 -lp: 0.0225516,-0.00600821,0.0572537 -lp: 0.0225797,-0.00592023,0.057251 -lp: 0.0225795,-0.00583214,0.0572575 -lp: 0.0225759,-0.00574405,0.0572651 -lp: 0.022544,-0.00565586,0.057282 -lp: 0.0225297,-0.00556776,0.0572932 -lp: 0.0225291,-0.00547974,0.0572998 -lp: 0.0225337,-0.00539175,0.0573048 -lp: 0.0225332,-0.00530376,0.0573114 -lp: 0.0225361,-0.00521579,0.0573169 -lp: 0.0225412,-0.00512785,0.0573216 -lp: 0.0225741,-0.00504002,0.0573174 -lp: 0.0225743,-0.00495208,0.0573237 -lp: 0.0225737,-0.00486415,0.0573304 -lp: 0.0225703,-0.00477621,0.0573379 -lp: 0.0225437,-0.00468821,0.0573531 -lp: 0.0225675,-0.0046004,0.0573517 -lp: 0.0225422,-0.00451243,0.0573664 -lp: 0.0225634,-0.00442462,0.057366 -lp: 0.0225448,-0.00433669,0.0573785 -lp: 0.0225696,-0.00424891,0.0573768 -lp: 0.0225697,-0.00416105,0.0573833 -lp: 0.022571,-0.00407321,0.0573893 -lp: 0.0225739,-0.00398538,0.0573947 -lp: 0.0225751,-0.00389755,0.0574008 -lp: 0.0225726,-0.00380971,0.057408 -lp: 0.0225729,-0.00372189,0.0574144 -lp: 0.0225733,-0.00363407,0.0574207 -lp: 0.0225742,-0.00354625,0.0574268 -lp: 0.0225751,-0.00345844,0.057433 -lp: 0.0226045,-0.0033707,0.0574298 -lp: 0.0225388,-0.00328274,0.0574577 -lp: 0.0225332,-0.00319493,0.057466 -lp: 0.0225353,-0.00310713,0.0574717 -lp: 0.0225258,-0.00301931,0.0574813 -lp: 0.0225238,-0.00293151,0.0574884 -lp: 0.0225021,-0.00284367,0.0575019 -lp: 0.0225024,-0.00275587,0.0575082 -lp: 0.0225045,-0.00266808,0.057514 -lp: 0.0225084,-0.00258028,0.0575192 -lp: 0.0225127,-0.00249248,0.0575242 -lp: 0.0225157,-0.00240468,0.0575297 -lp: 0.0225151,-0.00231687,0.0575363 -lp: 0.022514,-0.00222905,0.0575431 -lp: 0.0225122,-0.00214123,0.0575501 -lp: 0.0225126,-0.0020534,0.0575564 -lp: 0.0225131,-0.00196557,0.0575627 -lp: 0.022514,-0.00187774,0.0575688 -lp: 0.0225129,-0.00178989,0.0575756 -lp: 0.0225134,-0.00170204,0.0575819 -lp: 0.0225146,-0.00161419,0.057588 -lp: 0.0225164,-0.00152632,0.0575938 -lp: 0.0225191,-0.00143845,0.0575994 -lp: 0.0225208,-0.00135056,0.0576052 -lp: 0.0225219,-0.00126267,0.0576113 -lp: 0.0225226,-0.00117477,0.0576176 -lp: 0.0225223,-0.00108685,0.0576241 -lp: 0.0225233,-0.000998925,0.0576302 -lp: 0.0225249,-0.000910987,0.0576361 -lp: 0.0225268,-0.000823037,0.057642 -lp: 0.022529,-0.000735073,0.0576477 -lp: 0.0225301,-0.000647096,0.0576538 -lp: 0.022531,-0.000559104,0.0576599 -lp: 0.0225323,-0.000471099,0.057666 -lp: 0.0225346,-0.000383077,0.0576717 -lp: 0.0225372,-0.00029504,0.0576773 -lp: 0.0225395,-0.000206986,0.057683 -lp: 0.0225417,-0.000118916,0.0576887 -lp: 0.0225438,-3.08282e-05,0.0576945 -lp: 0.0225452,5.72769e-05,0.0577005 -lp: 0.0225467,0.0001454,0.0577065 -lp: 0.0225483,0.000233543,0.0577124 -lp: 0.0225491,0.000321704,0.0577186 -lp: 0.0225495,0.000409885,0.057725 -lp: 0.0225516,0.000498087,0.0577307 -lp: 0.022555,0.000586313,0.0577361 -lp: 0.022557,0.000674558,0.0577419 -lp: 0.0225595,0.000762826,0.0577476 -lp: 0.0225626,0.000851118,0.057753 -lp: 0.0225681,0.000939436,0.0577577 -lp: 0.0225713,0.00102778,0.0577631 -lp: 0.0225726,0.00111614,0.0577692 -lp: 0.0225732,0.00120452,0.0577755 -lp: 0.0225739,0.00129293,0.0577817 -lp: 0.0225734,0.00138136,0.0577884 -lp: 0.0225758,0.00146983,0.0577941 -lp: 0.022577,0.00155832,0.0578002 -lp: 0.0225797,0.00164684,0.0578058 -lp: 0.0225822,0.00173538,0.0578115 -lp: 0.0225621,0.00182391,0.0578245 -lp: 0.022597,0.00191259,0.0578196 -lp: 0.0225657,0.00200114,0.0578363 -lp: 0.0226072,0.0020899,0.0578293 -lp: 0.0225711,0.0021785,0.0578476 -lp: 0.0225733,0.00226723,0.0578533 -lp: 0.0225761,0.00235599,0.0578589 -lp: 0.0225819,0.00244478,0.0578636 -lp: 0.0225855,0.00253361,0.0578689 -lp: 0.0225879,0.00262247,0.0578746 -lp: 0.0225908,0.00271136,0.0578802 -lp: 0.0225932,0.00280028,0.0578859 -lp: 0.0225971,0.00288925,0.0578912 -lp: 0.0225951,0.00297823,0.0578984 -lp: 0.0225639,0.00306716,0.0579151 -lp: 0.0225664,0.00315623,0.0579208 -lp: 0.022571,0.00324534,0.0579258 -lp: 0.0226061,0.00333459,0.0579209 -lp: 0.0226082,0.00342377,0.0579267 -lp: 0.0226123,0.003513,0.0579319 -lp: 0.0226162,0.00360227,0.0579372 -lp: 0.0225906,0.00369147,0.0579521 -lp: 0.0225946,0.00378081,0.0579574 -lp: 0.0225951,0.00387019,0.0579638 -lp: 0.0225977,0.00395961,0.0579695 -lp: 0.0226027,0.00404909,0.0579744 -lp: 0.0226083,0.00413861,0.0579791 -lp: 0.0226127,0.00422817,0.0579842 -lp: 0.0226156,0.00431777,0.0579899 -lp: 0.022619,0.00440742,0.0579953 -lp: 0.0225879,0.00449696,0.0580121 -lp: 0.0225918,0.0045867,0.0580174 -lp: 0.0226052,0.00467653,0.0580196 -lp: 0.0226387,0.00476649,0.0580152 -lp: 0.0226421,0.00485637,0.0580207 -lp: 0.0226128,0.00494615,0.0580369 -lp: 0.0226086,0.00503608,0.0580448 -lp: 0.0226119,0.00512611,0.0580503 -lp: 0.0226231,0.00521622,0.0580533 -lp: 0.0226286,0.00530635,0.0580581 -lp: 0.0226315,0.00539653,0.0580638 -lp: 0.0226316,0.00548674,0.0580704 -lp: 0.0226279,0.00557698,0.0580782 -lp: 0.022602,0.00566716,0.0580932 -lp: 0.0226064,0.00575755,0.0580984 -lp: 0.0226131,0.00584801,0.0581029 -lp: 0.0225849,0.00593833,0.0581187 -lp: 0.0225882,0.00602887,0.0581243 -lp: 0.0225878,0.00611945,0.0581311 -lp: 0.0225911,0.00621011,0.0581366 -lp: 0.0225939,0.00630082,0.0581424 -lp: 0.0225968,0.00639159,0.0581481 -lp: 0.0226019,0.00648243,0.0581531 -lp: 0.022605,0.00657332,0.0581587 -lp: 0.0226054,0.00666425,0.0581652 -lp: 0.0225333,0.00675481,0.0581954 -lp: 0.0225392,0.00684589,0.0582002 -lp: 0.0225748,0.00693721,0.0581952 -lp: 0.0225535,0.00702825,0.0582089 -lp: 0.0225556,0.00711949,0.0582149 -lp: 0.0225605,0.00721082,0.05822 -lp: 0.0225637,0.0073022,0.0582256 -lp: 0.0225679,0.00739364,0.058231 -lp: 0.0225707,0.00748515,0.0582368 -lp: 0.0225761,0.00757674,0.0582417 -lp: 0.0225814,0.00766839,0.0582467 -lp: 0.0225873,0.00776011,0.0582515 -lp: 0.0225678,0.00785173,0.0582646 -lp: 0.0225709,0.00794357,0.0582703 -lp: 0.0225715,0.00803546,0.0582769 -lp: 0.0225752,0.00812745,0.0582824 -lp: 0.0225765,0.00821948,0.0582887 -lp: 0.0225798,0.0083116,0.0582944 -lp: 0.0225854,0.00840381,0.0582993 -lp: 0.0225918,0.0084961,0.058304 -lp: 0.0225747,0.00858828,0.0583163 -lp: 0.022578,0.00868069,0.058322 -lp: 0.0225786,0.00877315,0.0583286 -lp: 0.0225843,0.00886573,0.0583335 -lp: 0.0225873,0.00895836,0.0583393 -lp: 0.0225914,0.00905108,0.0583448 -lp: 0.0225968,0.00914388,0.0583499 -lp: 0.0226021,0.00923676,0.0583549 -lp: 0.0225766,0.00932947,0.0583701 -lp: 0.0225477,0.00942223,0.0583863 -lp: 0.0225482,0.0095153,0.0583929 -lp: 0.0225512,0.00960848,0.0583988 -lp: 0.0225535,0.00970172,0.0584049 -lp: 0.0225599,0.00979509,0.0584096 -lp: 0.0225659,0.00988853,0.0584145 -lp: 0.0225721,0.00998205,0.0584194 -lp: 0.0225774,0.0100757,0.0584245 -lp: 0.0225838,0.0101694,0.0584293 -lp: 0.022566,0.0102629,0.0584419 -lp: 0.0225707,0.0103568,0.0584473 -lp: 0.0225732,0.0104507,0.0584534 -lp: 0.0225785,0.0105447,0.0584585 -lp: 0.0225589,0.0106386,0.0584718 -lp: 0.0225642,0.0107328,0.058477 -lp: 0.0225671,0.0108271,0.0584829 -lp: 0.0225725,0.0109215,0.0584881 -lp: 0.0225753,0.0110159,0.0584941 -lp: 0.0225817,0.0111105,0.058499 -lp: 0.0225538,0.0112049,0.058515 -lp: 0.0225589,0.0112996,0.0585203 -lp: 0.0225637,0.0113944,0.0585257 -lp: 0.0225707,0.0114894,0.0585303 -lp: 0.0225768,0.0115844,0.0585353 -lp: 0.0225877,0.0116796,0.0585387 -lp: 0.0225972,0.0117749,0.0585426 -lp: 0.0226062,0.0118702,0.0585467 -lp: 0.0226168,0.0119657,0.0585502 -lp: 0.0226585,0.0120616,0.0585436 -lp: 0.0226364,0.0121569,0.0585578 -lp: 0.0226525,0.0122528,0.0585596 -lp: 0.0226169,0.0123482,0.0585782 -lp: 0.0226156,0.012444,0.0585857 -lp: 0.022581,0.0125397,0.058604 -lp: 0.0225438,0.0126353,0.0586231 -lp: 0.022606,0.0142857,0.0587238 -lp: 0.0226078,0.0143838,0.0587304 -lp: 0.0226121,0.014482,0.0587362 -lp: 0.0225874,0.01458,0.0587515 -lp: 0.0225608,0.0146781,0.0587674 -lp: 0.0225651,0.0147767,0.0587732 -lp: 0.0225761,0.0148755,0.0587768 -lp: 0.0225907,0.0149744,0.0587793 -lp: 0.0225979,0.0150734,0.0587842 -lp: 0.0226012,0.0151725,0.0587904 -lp: 0.0226092,0.0152717,0.0587951 -lp: 0.0226205,0.0153711,0.0587987 -lp: 0.0226268,0.0154706,0.0588039 -lp: 0.0225998,0.0155698,0.05882 -lp: 0.0225728,0.0156691,0.0588361 -lp: 0.0225802,0.015769,0.058841 -lp: 0.0225861,0.015869,0.0588464 -lp: 0.0225929,0.0159691,0.0588515 -lp: 0.0225835,0.0162699,0.0588766 -lp: 0.0225474,0.0163701,0.0588958 -lp: 0.0225094,0.0164703,0.0589155 -lp: 0.022522,0.0165713,0.0589188 -lp: 0.0225272,0.0166724,0.0589245 -lp: 0.0225416,0.0167737,0.0589273 -lp: 0.0225467,0.016875,0.058933 -lp: 0.0225286,0.0169762,0.0589464 -lp: 0.0225375,0.0170779,0.0589509 -lp: 0.0225465,0.0171797,0.0589554 -lp: 0.0225521,0.0172816,0.0589611 -lp: 0.0225268,0.0173832,0.0589768 -lp: 0.0225329,0.0174855,0.0589823 -lp: 0.0225425,0.0175879,0.0589867 -lp: 0.0225495,0.0176904,0.0589919 -lp: 0.0225574,0.0177931,0.0589968 -lp: 0.0225296,0.0178954,0.0590134 -lp: 0.0225392,0.0179984,0.0590178 -lp: 0.0225208,0.0181012,0.0590314 -lp: 0.022529,0.0182045,0.0590363 -lp: 0.0225357,0.0183079,0.0590417 -lp: 0.0225427,0.0184115,0.059047 -lp: 0.02255,0.0185152,0.0590522 -lp: 0.0225606,0.0186191,0.0590564 -lp: 0.0225383,0.0187228,0.0590712 -lp: 0.0225461,0.018827,0.0590763 -lp: 0.0225184,0.0189309,0.059093 -lp: 0.0225274,0.0190355,0.0590977 -lp: 0.0225336,0.0191401,0.0591034 -lp: 0.0225423,0.019245,0.0591082 -lp: 0.0225137,0.0193496,0.0591252 -lp: 0.0225236,0.0194548,0.0591297 -lp: 0.0225328,0.0195602,0.0591344 -lp: 0.0225431,0.0196657,0.0591388 -lp: 0.0225223,0.019771,0.0591533 -lp: 0.0225296,0.0198769,0.0591587 -lp: 0.0225374,0.019983,0.0591639 -lp: 0.0225482,0.0200892,0.0591682 -lp: 0.0225598,0.0201957,0.0591722 -lp: 0.0225718,0.0203023,0.0591761 -lp: 0.0225828,0.0204091,0.0591803 -lp: 0.0225623,0.0205156,0.0591949 -lp: 0.0225326,0.0206222,0.0592124 -lp: 0.0225391,0.0207294,0.0592181 -lp: 0.0225448,0.0208369,0.0592241 -lp: 0.0225215,0.020944,0.0592396 -lp: 0.0225027,0.0210515,0.0592536 -lp: 0.0225107,0.0211595,0.0592589 -lp: 0.022521,0.0212677,0.0592635 -lp: 0.0225326,0.0213762,0.0592676 -lp: 0.0225445,0.0214848,0.0592717 -lp: 0.0225556,0.0215936,0.0592761 -lp: 0.0225614,0.0217026,0.0592822 -lp: 0.0225354,0.0218112,0.0592986 -lp: 0.0225066,0.02192,0.059316 -lp: 0.02252,0.0220296,0.0593197 -lp: 0.0225287,0.0221393,0.0593249 -lp: 0.022539,0.0222493,0.0593295 -lp: 0.0225121,0.0223589,0.0593464 -lp: 0.0225246,0.0224693,0.0593504 -lp: 0.0225054,0.0225794,0.0593647 -lp: 0.0225136,0.0226902,0.0593702 -lp: 0.0225202,0.0228011,0.0593762 -lp: 0.0224989,0.0229117,0.0593912 -lp: 0.0225105,0.0230232,0.0593956 -lp: 0.0225545,0.0231353,0.0593895 -lp: 0.0225344,0.0232466,0.0594042 -lp: 0.0225077,0.0233581,0.0594211 -lp: 0.0225125,0.0234702,0.0594277 -lp: 0.0225225,0.0235826,0.0594327 -lp: 0.0224954,0.0236947,0.0594498 -lp: 0.0225081,0.0238076,0.0594539 -lp: 0.0224896,0.0239202,0.0594682 -lp: 0.0225019,0.0240336,0.0594725 -lp: 0.0225126,0.0241471,0.0594773 -lp: 0.0225238,0.0242609,0.059482 -lp: 0.0225332,0.0243749,0.0594873 -lp: 0.0225117,0.0244886,0.0595026 -lp: 0.0224867,0.0246024,0.0595191 -lp: 0.0224977,0.0247171,0.059524 -lp: 0.0225055,0.0248319,0.0595298 -lp: 0.022516,0.0249471,0.0595349 -lp: 0.0224618,0.0250613,0.0595609 -lp: 0.0224766,0.025177,0.0595646 -lp: 0.0224898,0.0252929,0.0595688 -lp: 0.0225015,0.025409,0.0595735 -lp: 0.0225105,0.0255253,0.059579 -lp: 0.0225227,0.0256419,0.0595836 -lp: 0.0225321,0.0257587,0.0595891 -lp: 0.022475,0.0258745,0.0596162 -lp: 0.0224818,0.0259918,0.0596226 -lp: 0.0224941,0.0261094,0.0596272 -lp: 0.0225047,0.0262271,0.0596324 -lp: 0.0224809,0.0263446,0.0596488 -lp: 0.0224627,0.0264624,0.0596634 -lp: 0.022476,0.026581,0.0596677 -lp: 0.0224866,0.0266998,0.059673 -lp: 0.0224998,0.0268189,0.0596774 -lp: 0.0225119,0.0269383,0.0596822 -lp: 0.0225249,0.0270579,0.0596867 -lp: 0.0225044,0.0271772,0.0597022 -lp: 0.0224829,0.0272967,0.0597179 -lp: 0.0224936,0.0274171,0.0597233 -lp: 0.0225075,0.0275378,0.0597276 -lp: 0.0225173,0.0276588,0.0597333 -lp: 0.0224932,0.0277793,0.05975 -lp: 0.0224729,0.0279002,0.0597655 -lp: 0.0224883,0.0280221,0.0597694 -lp: 0.0225004,0.0281441,0.0597743 -lp: 0.022515,0.0282665,0.0597786 -lp: 0.0225264,0.0283892,0.0597838 -lp: 0.0225384,0.0285121,0.0597889 -lp: 0.022519,0.0286347,0.0598042 -lp: 0.0224966,0.0287575,0.0598206 -lp: 0.0225075,0.0288812,0.0598261 -lp: 0.0225205,0.0290053,0.0598309 -lp: 0.0224921,0.0291289,0.0598493 -lp: 0.0224746,0.029253,0.0598641 -lp: 0.0224879,0.029378,0.0598689 -lp: 0.0225052,0.0295033,0.0598724 -lp: 0.0225198,0.029629,0.0598769 -lp: 0.0225329,0.0297549,0.0598818 -lp: 0.0225092,0.0298803,0.0598988 -lp: 0.0224899,0.0300062,0.0599143 -lp: 0.0225016,0.030133,0.0599198 -lp: 0.0225161,0.0302601,0.0599244 -lp: 0.0225287,0.0303876,0.0599296 -lp: 0.0225467,0.0305155,0.0599331 -lp: 0.0224909,0.0306421,0.0599606 -lp: 0.0225382,0.0307712,0.0599546 -lp: 0.0225169,0.0308993,0.059971 -lp: 0.0225322,0.0310284,0.0599754 -lp: 0.0225457,0.0311578,0.0599805 -lp: 0.0225626,0.0312876,0.0599845 -lp: 0.0225014,0.0314161,0.0600139 -lp: 0.0225109,0.0315464,0.0600204 -lp: 0.0224498,0.0316756,0.0600498 -lp: 0.0224674,0.0318068,0.0600537 -lp: 0.0224841,0.0319383,0.0600579 -lp: 0.0225031,0.0320702,0.0600613 -lp: 0.0225185,0.0322023,0.060066 -lp: 0.0225363,0.0323349,0.0600699 -lp: 0.0225493,0.0324677,0.0600754 -lp: 0.0224905,0.0325994,0.0601042 -lp: 0.0225037,0.0327329,0.0601097 -lp: 0.0225205,0.0328669,0.060114 -lp: 0.0225344,0.0330012,0.0601193 -lp: 0.0225121,0.033135,0.0601364 -lp: 0.0225281,0.0332701,0.0601411 -lp: 0.0225454,0.0334056,0.0601454 -lp: 0.022528,0.0335406,0.060161 -lp: 0.0225442,0.0336768,0.0601657 -lp: 0.0225232,0.0338126,0.0601825 -lp: 0.0225349,0.0339494,0.0601887 -lp: 0.0225108,0.0340859,0.0602066 -lp: 0.0225278,0.0342237,0.0602111 -lp: 0.0225447,0.0343618,0.0602158 -lp: 0.0224917,0.0344988,0.0602431 -lp: 0.0225094,0.0346377,0.0602475 -lp: 0.0225256,0.034777,0.0602524 -lp: 0.0225398,0.0349167,0.060258 -lp: 0.0225573,0.0350569,0.0602626 -lp: 0.0225306,0.0351964,0.0602815 -lp: 0.0225109,0.0353366,0.0602982 -lp: 0.022488,0.0354771,0.060316 -lp: 0.0224639,0.0356179,0.0603342 -lp: 0.0224827,0.0357602,0.0603385 -lp: 0.0225024,0.0359029,0.0603425 -lp: 0.0225216,0.036046,0.0603468 -lp: 0.0225413,0.0361896,0.0603509 -lp: 0.0225567,0.0363335,0.0603564 -lp: 0.0224987,0.0364761,0.0603858 -lp: 0.0225126,0.0366209,0.0603918 -lp: 0.0225324,0.0367662,0.060396 -lp: 0.022515,0.0369111,0.0604124 -lp: 0.0224884,0.0370563,0.0604317 -lp: 0.0225072,0.0372029,0.0604363 -lp: 0.0225286,0.0373501,0.0604401 -lp: 0.0225471,0.0374977,0.0604449 -lp: 0.022565,0.0376457,0.0604499 -lp: 0.0225039,0.0377924,0.0604806 -lp: 0.0225219,0.0379414,0.0604856 -lp: 0.0225032,0.0380899,0.0605026 -lp: 0.0225255,0.03824,0.0605063 -lp: 0.0225018,0.0383894,0.060525 -lp: 0.0225244,0.0385404,0.0605287 -lp: 0.0225411,0.0386918,0.0605344 -lp: 0.0225592,0.0388437,0.0605396 -lp: 0.0225373,0.0389951,0.0605578 -lp: 0.0225189,0.0391471,0.060575 -lp: 0.0225393,0.0393006,0.0605796 -lp: 0.0225638,0.0394546,0.0605829 -lp: 0.0225855,0.0396092,0.0605871 -lp: 0.0225258,0.0397622,0.0606178 -lp: 0.0225423,0.0399177,0.0606239 -lp: 0.0225618,0.0400737,0.0606289 -lp: 0.0225801,0.0402302,0.0606344 -lp: 0.0225556,0.0403863,0.0606539 -lp: 0.0225331,0.0405429,0.0606727 -lp: 0.0225546,0.0407011,0.0606773 -lp: 0.0225385,0.040859,0.0606941 -lp: 0.0225196,0.0410173,0.0607119 -lp: 0.0225398,0.0411772,0.060717 -lp: 0.0225604,0.0413376,0.060722 -lp: 0.0225825,0.0414987,0.0607267 -lp: 0.0225674,0.0416594,0.0607434 -lp: 0.0225885,0.0418216,0.0607483 -lp: 0.0226105,0.0419844,0.0607531 -lp: 0.0225911,0.0421467,0.0607714 -lp: 0.0225698,0.0423095,0.0607902 -lp: 0.0225976,0.0424742,0.0607932 -lp: 0.0225787,0.0426383,0.0608114 -lp: 0.0226553,0.0428056,0.0607987 -lp: 0.0227322,0.0429735,0.0607859 -lp: 0.0227739,0.0431411,0.0607846 -lp: 0.0227526,0.0433076,0.0608037 -lp: 0.0228682,0.0434786,0.0607785 -lp: 0.0222999,-0.0203121,0.0588369 -lp: 0.022291,-0.0202102,0.0588447 -lp: 0.0222852,-0.0201084,0.0588515 -lp: 0.0222994,-0.020007,0.0588516 -lp: 0.0222954,-0.0199055,0.0588578 -lp: 0.022289,-0.019804,0.0588648 -lp: 0.0223098,-0.019703,0.0588627 -lp: 0.0223038,-0.0196019,0.0588695 -lp: 0.0223036,-0.0195009,0.0588745 -lp: 0.022299,-0.0194,0.0588808 -lp: 0.0222952,-0.0192992,0.0588869 -lp: 0.0222899,-0.0191986,0.0588934 -lp: 0.0222852,-0.019098,0.0588998 -lp: 0.0223091,-0.0189979,0.0588967 -lp: 0.0223057,-0.0188976,0.0589026 -lp: 0.022302,-0.0187974,0.0589086 -lp: 0.0223325,-0.0186977,0.0589033 -lp: 0.0223283,-0.0185977,0.0589095 -lp: 0.022327,-0.0184979,0.0589146 -lp: 0.0223223,-0.0183982,0.058921 -lp: 0.0223172,-0.0182985,0.0589274 -lp: 0.0223115,-0.018199,0.0589341 -lp: 0.0223064,-0.0180996,0.0589405 -lp: 0.0223225,-0.0180005,0.0589399 -lp: 0.0223211,-0.0179014,0.0589451 -lp: 0.022317,-0.0178023,0.0589512 -lp: 0.0223138,-0.0177033,0.058957 -lp: 0.0223092,-0.0176045,0.0589633 -lp: 0.0223261,-0.0175059,0.0589624 -lp: 0.0223221,-0.0174073,0.0589684 -lp: 0.0223192,-0.0173087,0.0589741 -lp: 0.0223148,-0.0172103,0.0589803 -lp: 0.0223132,-0.017112,0.0589855 -lp: 0.0223072,-0.0170137,0.0589922 -lp: 0.0223042,-0.0169156,0.0589979 -lp: 0.0222997,-0.0168175,0.059004 -lp: 0.0223289,-0.0167199,0.0589991 -lp: 0.0223259,-0.0166221,0.0590047 -lp: 0.0223578,-0.0165246,0.0589988 -lp: 0.0223546,-0.016427,0.0590045 -lp: 0.0223513,-0.0163294,0.0590103 -lp: 0.0223467,-0.016232,0.0590165 -lp: 0.022343,-0.0161346,0.0590224 -lp: 0.0223386,-0.0160373,0.0590285 -lp: 0.0223346,-0.0159401,0.0590344 -lp: 0.0223289,-0.015843,0.059041 -lp: 0.0223502,-0.0157462,0.0590385 -lp: 0.0223484,-0.0156494,0.0590438 -lp: 0.0223465,-0.0155526,0.059049 -lp: 0.0223438,-0.0154558,0.0590545 -lp: 0.0223409,-0.0153592,0.0590601 -lp: 0.0223371,-0.0152626,0.059066 -lp: 0.0223333,-0.0151662,0.0590719 -lp: 0.0223281,-0.0150698,0.0590782 -lp: 0.0223464,-0.0149737,0.0590767 -lp: 0.0223442,-0.0148775,0.059082 -lp: 0.022344,-0.0147814,0.0590867 -lp: 0.0223402,-0.0146853,0.0590926 -lp: 0.0223374,-0.0145894,0.0590981 -lp: 0.0223332,-0.0144935,0.0591041 -lp: 0.0223619,-0.0143979,0.0590991 -lp: 0.0223589,-0.0143022,0.0591047 -lp: 0.0223903,-0.0142068,0.0590988 -lp: 0.0223865,-0.0141113,0.0591047 -lp: 0.0223832,-0.0140158,0.0591103 -lp: 0.0223811,-0.0139204,0.0591156 -lp: 0.0223795,-0.013825,0.0591207 -lp: 0.0223759,-0.0137298,0.0591264 -lp: 0.0223757,-0.0136346,0.059131 -lp: 0.0223957,-0.0135397,0.0591289 -lp: 0.0223949,-0.0134447,0.0591338 -lp: 0.0223911,-0.0133497,0.0591396 -lp: 0.0223914,-0.0132548,0.059144 -lp: 0.022389,-0.01316,0.0591493 -lp: 0.022386,-0.0130653,0.0591548 -lp: 0.022381,-0.0129706,0.059161 -lp: 0.0223745,-0.012876,0.0591677 -lp: 0.0223687,-0.0127814,0.0591742 -lp: 0.0223647,-0.0126869,0.05918 -lp: 0.0223842,-0.0125927,0.059178 -lp: 0.0224382,-0.0124987,0.0591647 -lp: 0.0224034,-0.0124042,0.0591807 -lp: 0.0224337,-0.0123103,0.0591751 -lp: 0.022429,-0.0122161,0.0591812 -lp: 0.0224272,-0.012122,0.0591863 -lp: 0.0224271,-0.012028,0.0591908 -lp: 0.0224226,-0.0119341,0.0591968 -lp: 0.0224187,-0.0118402,0.0592026 -lp: 0.0224122,-0.0117463,0.0592092 -lp: 0.0224065,-0.0116526,0.0592156 -lp: 0.0224028,-0.0115589,0.0592213 -lp: 0.0224352,-0.0114654,0.059215 -lp: 0.022437,-0.0113719,0.0592189 -lp: 0.022429,-0.0112783,0.059226 -lp: 0.0224257,-0.0111848,0.0592316 -lp: 0.0224299,-0.0110915,0.0592347 -lp: 0.0224249,-0.0109981,0.0592408 -lp: 0.0224159,-0.0109048,0.0592482 -lp: 0.0224106,-0.0108115,0.0592545 -lp: 0.022408,-0.0107183,0.0592598 -lp: 0.0224135,-0.0106252,0.0592624 -lp: 0.0224132,-0.0105322,0.059267 -lp: 0.0224432,-0.0104393,0.0592615 -lp: 0.0224095,-0.0103462,0.0592771 -lp: 0.0224109,-0.0102533,0.0592811 -lp: 0.0224326,-0.0101605,0.0592783 -lp: 0.022465,-0.0100679,0.059272 -lp: 0.0224754,-0.00997516,0.059273 -lp: 0.0225096,-0.00988262,0.0592661 -lp: 0.0225061,-0.00978994,0.0592716 -lp: 0.0225027,-0.0096973,0.0592772 -lp: 0.0224707,-0.00960457,0.0592922 -lp: 0.0224734,-0.00951206,0.0592958 -lp: 0.022498,-0.00941969,0.059292 -lp: 0.0224948,-0.00932724,0.0592975 -lp: 0.0224897,-0.00923483,0.0593036 -lp: 0.0224584,-0.00914234,0.0593184 -lp: 0.022482,-0.00905014,0.059315 -lp: 0.0224812,-0.00895788,0.0593197 -lp: 0.022477,-0.00886564,0.0593255 -lp: 0.022475,-0.00877346,0.0593306 -lp: 0.0224749,-0.00868132,0.059335 -lp: 0.0224996,-0.00858933,0.0593312 -lp: 0.0225019,-0.00849729,0.0593348 -lp: 0.0224983,-0.00840526,0.0593405 -lp: 0.0224941,-0.00831326,0.0593462 -lp: 0.0224658,-0.00822121,0.05936 -lp: 0.0224626,-0.00812929,0.0593655 -lp: 0.0224602,-0.00803742,0.0593706 -lp: 0.0224545,-0.00794557,0.059377 -lp: 0.0224982,-0.00785395,0.0593668 -lp: 0.0224867,-0.00776215,0.059375 -lp: 0.0224472,-0.00767028,0.0593925 -lp: 0.0224452,-0.00757859,0.0593976 -lp: 0.0224399,-0.00748692,0.0594037 -lp: 0.0224384,-0.00739529,0.0594086 -lp: 0.0224383,-0.0073037,0.059413 -lp: 0.022437,-0.00721214,0.0594178 -lp: 0.0224396,-0.00712063,0.0594213 -lp: 0.0224409,-0.00702914,0.0594253 -lp: 0.0224634,-0.00693775,0.0594222 -lp: 0.0224631,-0.00684631,0.0594266 -lp: 0.0224395,-0.00675483,0.0594389 -lp: 0.0224365,-0.00666345,0.0594442 -lp: 0.0224656,-0.00657219,0.0594389 -lp: 0.0224648,-0.00648086,0.0594435 -lp: 0.0224887,-0.00638963,0.05944 -lp: 0.0224562,-0.00629827,0.0594551 -lp: 0.0224555,-0.00620702,0.0594597 -lp: 0.0224872,-0.00611589,0.0594536 -lp: 0.0224872,-0.0060247,0.059458 -lp: 0.0224857,-0.00593352,0.0594628 -lp: 0.0224857,-0.00584237,0.0594671 -lp: 0.0224863,-0.00575125,0.0594713 -lp: 0.0224864,-0.00566014,0.0594756 -lp: 0.0224854,-0.00556906,0.0594803 -lp: 0.0224841,-0.00547799,0.0594851 -lp: 0.022482,-0.00538695,0.0594901 -lp: 0.0224819,-0.00529593,0.0594945 -lp: 0.0224834,-0.00520493,0.0594984 -lp: 0.0224858,-0.00511395,0.0595019 -lp: 0.0224848,-0.00502298,0.0595066 -lp: 0.0224842,-0.00493204,0.0595112 -lp: 0.0224831,-0.00484111,0.0595159 -lp: 0.0224484,-0.00475012,0.0595317 -lp: 0.0224472,-0.00465923,0.0595365 -lp: 0.0224406,-0.00456834,0.059543 -lp: 0.0224394,-0.00447747,0.0595478 -lp: 0.0224387,-0.00438662,0.0595523 -lp: 0.0224424,-0.00429579,0.0595555 -lp: 0.022479,-0.00420503,0.0595477 -lp: 0.0224796,-0.00411422,0.0595518 -lp: 0.0224796,-0.00402342,0.0595562 -lp: 0.0224789,-0.00393264,0.0595607 -lp: 0.0224792,-0.00384186,0.059565 -lp: 0.02248,-0.0037511,0.059569 -lp: 0.0224799,-0.00366034,0.0595734 -lp: 0.0224787,-0.0035696,0.0595781 -lp: 0.0224795,-0.00347886,0.0595822 -lp: 0.0224814,-0.00338813,0.0595859 -lp: 0.0224829,-0.00329742,0.0595898 -lp: 0.0224838,-0.00320671,0.0595938 -lp: 0.0224836,-0.003116,0.0595982 -lp: 0.0224805,-0.0030253,0.0596036 -lp: 0.0224777,-0.0029346,0.0596088 -lp: 0.0224787,-0.00284391,0.0596128 -lp: 0.0224827,-0.00275323,0.0596159 -lp: 0.0225155,-0.00266258,0.0596093 -lp: 0.0225009,-0.00257189,0.0596185 -lp: 0.0225259,-0.00248124,0.0596145 -lp: 0.0225209,-0.00239056,0.0596205 -lp: 0.0225325,-0.0022999,0.059621 -lp: 0.0225403,-0.00220924,0.0596228 -lp: 0.0225683,-0.00211859,0.0596178 -lp: 0.0225682,-0.00202792,0.0596222 -lp: 0.0225385,-0.00193723,0.0596364 -lp: 0.0225407,-0.00184656,0.05964 -lp: 0.0225426,-0.0017559,0.0596437 -lp: 0.0225428,-0.00166522,0.059648 -lp: 0.0225364,-0.00157455,0.0596544 -lp: 0.0225353,-0.00148387,0.0596591 -lp: 0.0225443,-0.00139319,0.0596604 -lp: 0.0225464,-0.00130251,0.0596641 -lp: 0.0225401,-0.00121182,0.0596705 -lp: 0.0225474,-0.00112112,0.0596724 -lp: 0.0225547,-0.00103042,0.0596743 -lp: 0.0225831,-0.000939716,0.0596693 -lp: 0.0225795,-0.000849002,0.0596748 -lp: 0.0225784,-0.000758282,0.0596795 -lp: 0.0225488,-0.00066756,0.0596937 -lp: 0.0225485,-0.000576825,0.0596981 -lp: 0.0225487,-0.00048608,0.0597024 -lp: 0.0225566,-0.000395324,0.0597041 -lp: 0.0225915,-0.000304544,0.0596969 -lp: 0.0226251,-0.000213752,0.0596901 -lp: 0.0226245,-0.000122964,0.0596946 -lp: 0.0225958,-3.21805e-05,0.0597085 -lp: 0.0225617,5.86081e-05,0.0597241 -lp: 0.0225461,0.000149419,0.0597336 -lp: 0.0225172,0.000240231,0.0597475 -lp: 0.0225179,0.000331078,0.0597517 -lp: 0.0225499,0.000421965,0.0597454 -lp: 0.0225631,0.000512853,0.0597454 -lp: 0.0225686,0.000603751,0.0597479 -lp: 0.0225778,0.000694669,0.0597492 -lp: 0.0226055,0.000785623,0.0597444 -lp: 0.0225768,0.000876535,0.0597582 -lp: 0.0225697,0.000967487,0.0597649 -lp: 0.0225611,0.00105845,0.0597721 -lp: 0.0225618,0.00114945,0.0597762 -lp: 0.0225666,0.00124047,0.059779 -lp: 0.0225421,0.00133147,0.0597915 -lp: 0.0225389,0.00142252,0.0597969 -lp: 0.0225395,0.0015136,0.059801 -lp: 0.0225485,0.00160471,0.0598024 -lp: 0.0225937,0.00169589,0.0597918 -lp: 0.022599,0.00178704,0.0597944 -lp: 0.0226004,0.00187821,0.0597983 -lp: 0.0226013,0.0019694,0.0598023 -lp: 0.0226008,0.00206061,0.0598069 -lp: 0.0226001,0.00215185,0.0598115 -lp: 0.0225637,0.00224305,0.0598279 -lp: 0.0225185,0.00233425,0.0598472 -lp: 0.0225101,0.00242554,0.0598544 -lp: 0.0225195,0.0025169,0.0598556 -lp: 0.022523,0.00260827,0.0598588 -lp: 0.0225276,0.00269968,0.0598617 -lp: 0.0225307,0.0027911,0.059865 -lp: 0.0225326,0.00288256,0.0598688 -lp: 0.0225352,0.00297405,0.0598723 -lp: 0.0225374,0.00306556,0.059876 -lp: 0.0225402,0.00315711,0.0598794 -lp: 0.0225431,0.00324869,0.0598828 -lp: 0.022545,0.0033403,0.0598866 -lp: 0.0225447,0.00343194,0.059891 -lp: 0.0225451,0.00352361,0.0598953 -lp: 0.0225458,0.00361532,0.0598994 -lp: 0.0225478,0.00370706,0.0599032 -lp: 0.0225524,0.00379884,0.059906 -lp: 0.0225572,0.00389067,0.0599088 -lp: 0.0225605,0.00398252,0.0599121 -lp: 0.0225314,0.00407432,0.0599262 -lp: 0.0225311,0.00416624,0.0599306 -lp: 0.022499,0.0042581,0.0599457 -lp: 0.0225025,0.0043501,0.0599489 -lp: 0.0225053,0.00444214,0.0599524 -lp: 0.0225082,0.00453422,0.0599558 -lp: 0.0225094,0.00462633,0.0599598 -lp: 0.0225108,0.00471849,0.0599638 -lp: 0.0225141,0.00481069,0.0599671 -lp: 0.0225149,0.00490292,0.0599712 -lp: 0.0225166,0.0049952,0.0599751 -lp: 0.0225188,0.00508753,0.0599788 -lp: 0.0225213,0.0051799,0.0599824 -lp: 0.0225261,0.00527232,0.0599852 -lp: 0.0225303,0.00536478,0.0599882 -lp: 0.0225335,0.00545729,0.0599916 -lp: 0.0225366,0.00554984,0.059995 -lp: 0.022517,0.00564236,0.0600059 -lp: 0.02252,0.005735,0.0600093 -lp: 0.022521,0.00582769,0.0600134 -lp: 0.0225227,0.00592042,0.0600173 -lp: 0.0225268,0.00601322,0.0600204 -lp: 0.0225323,0.00610606,0.060023 -lp: 0.0225369,0.00619896,0.0600259 -lp: 0.0225379,0.00629189,0.06003 -lp: 0.0225374,0.00638487,0.0600346 -lp: 0.0225411,0.00647791,0.0600379 -lp: 0.0225464,0.00657102,0.0600405 -lp: 0.0225513,0.00666418,0.0600434 -lp: 0.0225552,0.00675738,0.0600466 -lp: 0.0225567,0.00685063,0.0600505 -lp: 0.022559,0.00694394,0.0600542 -lp: 0.0225636,0.00703732,0.0600572 -lp: 0.0225433,0.00713064,0.0600684 -lp: 0.0225488,0.00722413,0.060071 -lp: 0.0225426,0.00731763,0.0600775 -lp: 0.0225609,0.00741129,0.0600759 -lp: 0.0226006,0.00750511,0.0600673 -lp: 0.0225997,0.00759881,0.060072 -lp: 0.0226043,0.00769259,0.060075 -lp: 0.022575,0.00778627,0.0600892 -lp: 0.0225782,0.00788017,0.0600926 -lp: 0.02258,0.00797412,0.0600965 -lp: 0.0225824,0.00806814,0.0601002 -lp: 0.0225861,0.00816223,0.0601035 -lp: 0.02259,0.00825638,0.0601067 -lp: 0.0226029,0.00835064,0.0601069 -lp: 0.0226083,0.00844493,0.0601096 -lp: 0.022607,0.00853925,0.0601146 -lp: 0.0225752,0.00863348,0.0601296 -lp: 0.0225768,0.00872794,0.0601336 -lp: 0.0225818,0.0088225,0.0601365 -lp: 0.0225887,0.00891712,0.0601387 -lp: 0.0225948,0.00901182,0.0601412 -lp: 0.0225994,0.00910658,0.0601442 -lp: 0.0226355,0.00920158,0.0601368 -lp: 0.0226425,0.00929649,0.060139 -lp: 0.0226196,0.00939131,0.0601511 -lp: 0.0226241,0.00948635,0.0601542 -lp: 0.0226305,0.00958148,0.0601566 -lp: 0.0226001,0.00967647,0.0601712 -lp: 0.022638,0.00977193,0.0601633 -lp: 0.0226447,0.00986728,0.0601656 -lp: 0.0226186,0.00996251,0.0601788 -lp: 0.0226197,0.010058,0.060183 -lp: 0.0226234,0.0101535,0.0601863 -lp: 0.0226295,0.0102492,0.0601889 -lp: 0.0226351,0.0103449,0.0601916 -lp: 0.0226342,0.0104407,0.0601965 -lp: 0.0226052,0.0105364,0.0602107 -lp: 0.0226099,0.0106323,0.0602137 -lp: 0.0226261,0.0107285,0.0602129 -lp: 0.0226671,0.0108248,0.0602039 -lp: 0.0226742,0.010921,0.0602062 -lp: 0.0226008,0.0110168,0.0602351 -lp: 0.0226014,0.0111132,0.0602395 -lp: 0.0226031,0.0112096,0.0602435 -lp: 0.0226076,0.0113062,0.0602467 -lp: 0.0225782,0.0114026,0.060261 -lp: 0.0225855,0.0114993,0.0602633 -lp: 0.0225929,0.0115961,0.0602654 -lp: 0.0226017,0.011693,0.0602671 -lp: 0.0226092,0.01179,0.0602693 -lp: 0.0226475,0.0118873,0.0602613 -lp: 0.0226482,0.0119845,0.0602656 -lp: 0.022595,0.0120813,0.0602879 -lp: 0.0225834,0.0121786,0.0602964 -lp: 0.022576,0.0122759,0.0603035 -lp: 0.0225567,0.0123733,0.0603146 -lp: 0.0225611,0.0124709,0.0603178 -lp: 0.0225651,0.0125686,0.0603211 -lp: 0.0225478,0.0126663,0.0603315 -lp: 0.022554,0.0127642,0.0603342 -lp: 0.0225569,0.0128622,0.0603379 -lp: 0.0225617,0.0129603,0.060341 -lp: 0.0225637,0.0130585,0.060345 -lp: 0.0225344,0.0131565,0.0603594 -lp: 0.0225398,0.0132549,0.0603623 -lp: 0.0225467,0.0133534,0.0603647 -lp: 0.0225527,0.0134521,0.0603675 -lp: 0.0225579,0.0135508,0.0603705 -lp: 0.0225624,0.0136496,0.0603737 -lp: 0.0225691,0.0137485,0.0603762 -lp: 0.0225749,0.0138475,0.060379 -lp: 0.0225812,0.0139467,0.0603817 -lp: 0.0225869,0.0140459,0.0603845 -lp: 0.0225633,0.014145,0.0603971 -lp: 0.0225653,0.0142445,0.0604012 -lp: 0.0225694,0.014344,0.0604046 -lp: 0.0225451,0.0144434,0.0604174 -lp: 0.0225525,0.0145432,0.0604197 -lp: 0.0225592,0.0146431,0.0604223 -lp: 0.0225661,0.0147432,0.0604248 -lp: 0.0225462,0.0148431,0.0604362 -lp: 0.0225515,0.0149433,0.0604392 -lp: 0.0225537,0.0150436,0.0604432 -lp: 0.0225254,0.0151438,0.0604574 -lp: 0.0225308,0.0152444,0.0604604 -lp: 0.0225367,0.0153451,0.0604633 -lp: 0.0225421,0.0154459,0.0604663 -lp: 0.0225482,0.0155468,0.0604691 -lp: 0.0225532,0.0156479,0.0604723 -lp: 0.0225615,0.0157491,0.0604744 -lp: 0.0225678,0.0158504,0.0604771 -lp: 0.0225741,0.0159518,0.0604799 -lp: 0.0225801,0.0160534,0.0604828 -lp: 0.0225555,0.0161548,0.0604958 -lp: 0.0225316,0.0162563,0.0605085 -lp: 0.0225373,0.0163582,0.0605115 -lp: 0.0225409,0.0164603,0.0605152 -lp: 0.0225465,0.0165624,0.0605183 -lp: 0.0225531,0.0166648,0.0605209 -lp: 0.0225371,0.016767,0.0605311 -lp: 0.0225445,0.0168696,0.0605336 -lp: 0.022554,0.0169723,0.0605354 -lp: 0.0225552,0.0170751,0.0605399 -lp: 0.022566,0.0171781,0.0605412 -lp: 0.0225813,0.0172813,0.0605411 -lp: 0.0225943,0.0173846,0.0605417 -lp: 0.0225981,0.017488,0.0605454 -lp: 0.0226088,0.0175915,0.0605468 -lp: 0.0226163,0.0176952,0.0605493 -lp: 0.0225824,0.0177986,0.0605654 -lp: 0.0226219,0.0179028,0.0605574 -lp: 0.0226026,0.0180067,0.0605687 -lp: 0.0226478,0.0181113,0.0605587 -lp: 0.0226262,0.0182154,0.0605709 -lp: 0.0226706,0.0183202,0.0605612 -lp: 0.0226093,0.0184242,0.0605865 -lp: 0.0226106,0.018529,0.060591 -lp: 0.0226151,0.0186339,0.0605945 -lp: 0.0226265,0.018739,0.0605958 -lp: 0.0226383,0.0188443,0.0605969 -lp: 0.0226477,0.0189498,0.0605989 -lp: 0.0226126,0.0190549,0.0606155 -lp: 0.0225741,0.0191601,0.0606333 -lp: 0.0225445,0.0192656,0.0606482 -lp: 0.0225636,0.0193717,0.0606469 -lp: 0.0226112,0.0194783,0.0606362 -lp: 0.0226688,0.0195852,0.0606222 -lp: 0.0226372,0.0196913,0.0606378 -lp: 0.022639,0.0197978,0.0606423 -lp: 0.0226123,0.0199043,0.0606562 -lp: 0.0225839,0.0200109,0.0606707 -lp: 0.0225854,0.0201179,0.0606753 -lp: 0.0225584,0.0202249,0.0606894 -lp: 0.0225611,0.0203323,0.0606937 -lp: 0.0225742,0.0204399,0.0606945 -lp: 0.0225411,0.0205473,0.0607106 -lp: 0.0225562,0.0206553,0.0607107 -lp: 0.0225666,0.0207635,0.0607124 -lp: 0.0226193,0.0208723,0.0607002 -lp: 0.0226399,0.0209809,0.0606985 -lp: 0.0226942,0.0210901,0.0606858 -lp: 0.0227431,0.0211994,0.0606748 -lp: 0.0226758,0.0213075,0.0607023 -lp: 0.0226352,0.0214161,0.0607209 -lp: 0.0226092,0.0215251,0.0607347 -lp: 0.0226182,0.0216346,0.060737 -lp: 0.0225842,0.0217438,0.0607535 -lp: 0.0225442,0.0218532,0.060772 -lp: 0.0224987,0.0219627,0.0607923 -lp: 0.0224723,0.0220725,0.0608063 -lp: 0.0224856,0.022183,0.0608072 -lp: 0.0224994,0.0222937,0.0608079 -lp: 0.0225142,0.0224046,0.0608083 -lp: 0.0225292,0.0225156,0.0608086 -lp: 0.0225379,0.0226268,0.0608111 -lp: 0.0225486,0.0227382,0.0608128 -lp: 0.0225553,0.0228498,0.0608159 -lp: 0.0225326,0.0229612,0.0608288 -lp: 0.022509,0.0230728,0.0608419 -lp: 0.0225209,0.0231849,0.0608434 -lp: 0.0225303,0.0232973,0.0608456 -lp: 0.0225381,0.0234098,0.0608484 -lp: 0.0225437,0.0235225,0.060852 -lp: 0.0225555,0.0236355,0.0608535 -lp: 0.0225289,0.0237483,0.0608677 -lp: 0.0225389,0.0238616,0.0608698 -lp: 0.0225476,0.0239752,0.0608723 -lp: 0.0225256,0.0240886,0.060885 -lp: 0.0225358,0.0242026,0.0608871 -lp: 0.0225463,0.0243168,0.0608891 -lp: 0.0225571,0.0244312,0.060891 -lp: 0.0225346,0.0245455,0.0609039 -lp: 0.0225078,0.0246599,0.0609182 -lp: 0.0225173,0.0247749,0.0609206 -lp: 0.0225205,0.0248901,0.060925 -lp: 0.0225297,0.0250056,0.0609275 -lp: 0.0225025,0.0251209,0.060942 -lp: 0.0225155,0.0252368,0.0609433 -lp: 0.0224966,0.0253526,0.0609551 -lp: 0.0225068,0.025469,0.0609572 -lp: 0.0225183,0.0255856,0.060959 -lp: 0.0225317,0.0257025,0.0609601 -lp: 0.0225419,0.0258196,0.0609624 -lp: 0.0225525,0.0259369,0.0609645 -lp: 0.0225275,0.0260539,0.0609784 -lp: 0.0225041,0.0261713,0.0609917 -lp: 0.0225107,0.0262892,0.0609952 -lp: 0.02252,0.0264074,0.0609977 -lp: 0.0224902,0.0265254,0.0610133 -lp: 0.0225019,0.0266441,0.0610151 -lp: 0.0225154,0.0267631,0.0610163 -lp: 0.0224994,0.026882,0.0610273 -lp: 0.0225109,0.0270014,0.0610292 -lp: 0.0225219,0.0271211,0.0610313 -lp: 0.0225325,0.0272411,0.0610335 -lp: 0.0225446,0.0273613,0.0610352 -lp: 0.0225545,0.0274817,0.0610377 -lp: 0.0224959,0.0276015,0.0610628 -lp: 0.0225029,0.0277224,0.0610663 -lp: 0.0225144,0.0278436,0.0610683 -lp: 0.0225258,0.0279651,0.0610703 -lp: 0.0225398,0.0280869,0.0610715 -lp: 0.0224784,0.0282079,0.0610976 -lp: 0.0224864,0.0283301,0.0611008 -lp: 0.0224967,0.0284526,0.0611032 -lp: 0.0225114,0.0285755,0.0611042 -lp: 0.0225229,0.0286985,0.0611063 -lp: 0.0225351,0.0288219,0.0611082 -lp: 0.0224773,0.0289446,0.0611332 -lp: 0.0224908,0.0290685,0.0611347 -lp: 0.0225001,0.0291926,0.0611375 -lp: 0.0225113,0.029317,0.0611397 -lp: 0.0224854,0.0294413,0.0611543 -lp: 0.0224696,0.0295659,0.0611655 -lp: 0.0224817,0.0296912,0.0611674 -lp: 0.0224935,0.0298168,0.0611695 -lp: 0.0225031,0.0299426,0.0611724 -lp: 0.0225156,0.0300688,0.0611742 -lp: 0.02249,0.0301947,0.0611888 -lp: 0.0224638,0.0303209,0.0612035 -lp: 0.0224755,0.030448,0.0612057 -lp: 0.022491,0.0305754,0.0612066 -lp: 0.022463,0.0307025,0.061222 -lp: 0.0224748,0.0308304,0.0612242 -lp: 0.0224567,0.0309582,0.0612363 -lp: 0.022472,0.0310868,0.0612374 -lp: 0.0224857,0.0312157,0.061239 -lp: 0.0225005,0.031345,0.0612403 -lp: 0.0225127,0.0314745,0.0612425 -lp: 0.0225261,0.0316043,0.0612442 -lp: 0.0224652,0.0317334,0.0612706 -lp: 0.022478,0.0318639,0.0612726 -lp: 0.0224891,0.0319946,0.0612751 -lp: 0.0225051,0.0321258,0.0612761 -lp: 0.022448,0.0322562,0.0613013 -lp: 0.0224647,0.0323881,0.061302 -lp: 0.0224775,0.0325202,0.0613041 -lp: 0.0224901,0.0326526,0.0613062 -lp: 0.0224997,0.0327853,0.0613094 -lp: 0.0224796,0.032918,0.0613224 -lp: 0.0224522,0.0330508,0.0613379 -lp: 0.0224661,0.0331846,0.0613396 -lp: 0.0224759,0.0333188,0.0613428 -lp: 0.0224544,0.0334527,0.0613563 -lp: 0.022471,0.0335876,0.0613573 -lp: 0.022454,0.0337224,0.0613694 -lp: 0.0224676,0.033858,0.0613714 -lp: 0.0224843,0.033994,0.0613723 -lp: 0.0224987,0.0341303,0.0613741 -lp: 0.0225166,0.034267,0.0613747 -lp: 0.0225286,0.034404,0.0613772 -lp: 0.0224655,0.0345402,0.0614047 -lp: 0.0224735,0.0346779,0.0614086 -lp: 0.0224915,0.0348162,0.0614092 -lp: 0.0224708,0.0349542,0.0614227 -lp: 0.0224896,0.0350931,0.0614231 -lp: 0.0224673,0.0352319,0.0614371 -lp: 0.0224762,0.0353715,0.0614408 -lp: 0.0224916,0.0355116,0.0614425 -lp: 0.0225111,0.0356521,0.0614427 -lp: 0.022495,0.0357925,0.0614548 -lp: 0.0224716,0.0359332,0.0614692 -lp: 0.022486,0.0360749,0.0614713 -lp: 0.0225052,0.036217,0.0614717 -lp: 0.0225193,0.0363595,0.0614738 -lp: 0.0224562,0.0365012,0.0615015 -lp: 0.0224693,0.0366445,0.061504 -lp: 0.0224903,0.0367883,0.0615039 -lp: 0.0225061,0.0369325,0.0615056 -lp: 0.0225197,0.037077,0.061508 -lp: 0.0224594,0.0372208,0.0615349 -lp: 0.0224754,0.0373663,0.0615365 -lp: 0.0224936,0.0375122,0.0615374 -lp: 0.022514,0.0376586,0.0615377 -lp: 0.0224898,0.0378047,0.0615527 -lp: 0.0224705,0.0379513,0.0615661 -lp: 0.0224886,0.038099,0.0615671 -lp: 0.0225069,0.0382471,0.0615682 -lp: 0.0225227,0.0383957,0.0615701 -lp: 0.0225409,0.0385447,0.0615711 -lp: 0.0224759,0.0386929,0.0615998 -lp: 0.0224932,0.0388428,0.0616012 -lp: 0.0225064,0.0389932,0.061604 -lp: 0.0224502,0.0391428,0.0616298 -lp: 0.0224661,0.0392942,0.0616318 -lp: 0.0224861,0.0394461,0.0616324 -lp: 0.0225023,0.0395984,0.0616343 -lp: 0.0225153,0.0397511,0.0616373 -lp: 0.0224531,0.0399031,0.0616652 -lp: 0.0224741,0.0400569,0.0616656 -lp: 0.0224944,0.0402113,0.0616662 -lp: 0.0225132,0.0403661,0.0616674 -lp: 0.0224542,0.0405201,0.0616943 -lp: 0.0224726,0.0406759,0.0616957 -lp: 0.0224916,0.0408322,0.0616969 -lp: 0.0225081,0.0409891,0.0616989 -lp: 0.0225278,0.0411465,0.0616999 -lp: 0.0225522,0.0413045,0.0616994 -lp: 0.0224931,0.0414616,0.0617264 -lp: 0.0225131,0.0416206,0.0617274 -lp: 0.0225299,0.04178,0.0617295 -lp: 0.0225049,0.0419393,0.0617454 -lp: 0.0225259,0.0421,0.0617461 -lp: 0.0225134,0.0422606,0.0617579 -lp: 0.0225291,0.0424222,0.0617604 -lp: 0.022549,0.0425845,0.0617616 -lp: 0.0225675,0.0427474,0.0617633 -lp: 0.0225933,0.0429109,0.0617625 -lp: 0.0225355,0.0430735,0.0617894 -lp: 0.0225555,0.0432381,0.0617907 -lp: 0.0225844,0.0434035,0.061789 -lp: 0.0226181,0.0435695,0.0617858 -lp: 0.0226842,0.0437368,0.0617719 -lp: 0.0227163,0.043904,0.0617693 -lp: 0.0227468,0.0440719,0.0617672 -lp: 0.0228861,0.0442427,0.0617292 -lp: 0.0228028,0.0444093,0.0617647 -lp: 0.0223066,-0.0211904,0.0617253 -lp: 0.0222974,-0.0210838,0.0617324 -lp: 0.0222904,-0.0209773,0.0617387 -lp: 0.0222838,-0.020871,0.0617449 -lp: 0.022278,-0.0207648,0.0617508 -lp: 0.0222719,-0.0206587,0.0617568 -lp: 0.0222673,-0.0205528,0.0617623 -lp: 0.0222599,-0.020447,0.0617687 -lp: 0.0222853,-0.0203414,0.0617639 -lp: 0.0223132,-0.020236,0.0617583 -lp: 0.0223094,-0.0201306,0.0617635 -lp: 0.0223024,-0.0200253,0.0617697 -lp: 0.0222987,-0.0199201,0.0617749 -lp: 0.0222947,-0.0198151,0.0617801 -lp: 0.0222921,-0.0197102,0.0617849 -lp: 0.0222876,-0.0196055,0.0617903 -lp: 0.0222836,-0.0195008,0.0617955 -lp: 0.0223114,-0.0193964,0.0617899 -lp: 0.022308,-0.019292,0.0617949 -lp: 0.0223029,-0.0191877,0.0618005 -lp: 0.0222977,-0.0190835,0.0618061 -lp: 0.0222914,-0.0189795,0.0618121 -lp: 0.0222903,-0.0188756,0.0618163 -lp: 0.0222867,-0.0187718,0.0618214 -lp: 0.0223057,-0.0186682,0.0618187 -lp: 0.022299,-0.0185646,0.0618248 -lp: 0.0222959,-0.0184611,0.0618297 -lp: 0.0223106,-0.0183578,0.0618285 -lp: 0.0223061,-0.0182546,0.0618339 -lp: 0.0222993,-0.0181515,0.06184 -lp: 0.0222979,-0.0180485,0.0618443 -lp: 0.0222962,-0.0179456,0.0618486 -lp: 0.0222972,-0.0178428,0.0618521 -lp: 0.0222934,-0.0177401,0.0618572 -lp: 0.0223228,-0.0176376,0.0618509 -lp: 0.0223184,-0.0175352,0.0618562 -lp: 0.0223144,-0.0174328,0.0618614 -lp: 0.0223091,-0.0173306,0.0618669 -lp: 0.0223036,-0.0172284,0.0618726 -lp: 0.022297,-0.0171264,0.0618786 -lp: 0.0223273,-0.0170245,0.061872 -lp: 0.0223237,-0.0169227,0.061877 -lp: 0.0223231,-0.0168209,0.061881 -lp: 0.0223193,-0.0167193,0.061886 -lp: 0.0223418,-0.0166178,0.0618821 -lp: 0.0223397,-0.0165164,0.0618866 -lp: 0.0223379,-0.016415,0.0618909 -lp: 0.0223331,-0.0163138,0.0618963 -lp: 0.0223288,-0.0162127,0.0619015 -lp: 0.022324,-0.0161116,0.0619069 -lp: 0.0223229,-0.0160106,0.061911 -lp: 0.0223403,-0.0159098,0.0619087 -lp: 0.0223377,-0.0158091,0.0619133 -lp: 0.0223331,-0.0157084,0.0619186 -lp: 0.0223299,-0.0156078,0.0619234 -lp: 0.0223259,-0.0155073,0.0619285 -lp: 0.0223238,-0.0154069,0.0619329 -lp: 0.0223208,-0.0153066,0.0619377 -lp: 0.0223202,-0.0152064,0.0619416 -lp: 0.022318,-0.0151062,0.061946 -lp: 0.022348,-0.0150062,0.0619395 -lp: 0.022344,-0.0149063,0.0619445 -lp: 0.0223753,-0.0148065,0.0619375 -lp: 0.0223708,-0.0147067,0.0619427 -lp: 0.0223671,-0.014607,0.0619477 -lp: 0.0223621,-0.0145073,0.0619531 -lp: 0.0223603,-0.0144078,0.0619573 -lp: 0.0223583,-0.0143083,0.0619617 -lp: 0.0223592,-0.0142089,0.0619651 -lp: 0.0223557,-0.0141096,0.0619699 -lp: 0.0223758,-0.0140105,0.0619667 -lp: 0.0223708,-0.0139113,0.0619721 -lp: 0.0223692,-0.0138123,0.0619763 -lp: 0.0223672,-0.0137133,0.0619806 -lp: 0.0223663,-0.0136144,0.0619846 -lp: 0.022363,-0.0135155,0.0619894 -lp: 0.0223633,-0.0134168,0.0619929 -lp: 0.0223615,-0.0133181,0.0619972 -lp: 0.0223786,-0.0132195,0.061995 -lp: 0.0223733,-0.013121,0.0620004 -lp: 0.0223695,-0.0130225,0.0620054 -lp: 0.0223646,-0.0129241,0.0620107 -lp: 0.0223617,-0.0128258,0.0620153 -lp: 0.0223596,-0.0127276,0.0620196 -lp: 0.0223574,-0.0126294,0.062024 -lp: 0.0223648,-0.0125313,0.0620251 -lp: 0.0223978,-0.0124333,0.0620174 -lp: 0.0223943,-0.0123353,0.0620222 -lp: 0.0223911,-0.0122374,0.062027 -lp: 0.0223893,-0.0121396,0.0620312 -lp: 0.0224129,-0.0120418,0.0620268 -lp: 0.022411,-0.0119441,0.062031 -lp: 0.0224091,-0.0118465,0.0620352 -lp: 0.0224091,-0.0117489,0.0620389 -lp: 0.0224074,-0.0116513,0.062043 -lp: 0.0223993,-0.0115539,0.0620494 -lp: 0.0224009,-0.0114565,0.0620525 -lp: 0.02246,-0.0109705,0.0620502 -lp: 0.0224557,-0.0108734,0.0620552 -lp: 0.0224181,-0.0107764,0.0620717 -lp: 0.0224494,-0.0106795,0.0620646 -lp: 0.0224557,-0.0105827,0.062066 -lp: 0.0224591,-0.0104859,0.0620684 -lp: 0.0224532,-0.0103891,0.062074 -lp: 0.0224547,-0.0102924,0.062077 -lp: 0.0224593,-0.0101957,0.062079 -lp: 0.0224831,-0.0100992,0.0620745 -lp: 0.022481,-0.0100026,0.0620787 -lp: 0.022478,-0.00990611,0.0620833 -lp: 0.0224744,-0.00980966,0.0620881 -lp: 0.0224465,-0.00971323,0.0621012 -lp: 0.022462,-0.0096169,0.0620995 -lp: 0.0224668,-0.0095206,0.0621014 -lp: 0.0224634,-0.00942435,0.0621061 -lp: 0.0224622,-0.00932814,0.0621101 -lp: 0.0224636,-0.00923198,0.0621132 -lp: 0.0224604,-0.00913587,0.0621178 -lp: 0.0224563,-0.0090398,0.0621228 -lp: 0.022479,-0.0089438,0.0621185 -lp: 0.0224771,-0.00884782,0.0621227 -lp: 0.0224477,-0.00875186,0.0621363 -lp: 0.0224447,-0.00865597,0.0621409 -lp: 0.022475,-0.00856015,0.0621341 -lp: 0.02248,-0.00846435,0.0621359 -lp: 0.0224404,-0.00836855,0.062153 -lp: 0.0224357,-0.00827283,0.0621581 -lp: 0.0224321,-0.00817714,0.0621629 -lp: 0.0224309,-0.0080815,0.0621668 -lp: 0.0224654,-0.00798592,0.0621585 -lp: 0.0225047,-0.00789038,0.0621486 -lp: 0.0224657,-0.00779482,0.0621655 -lp: 0.0224146,-0.0076993,0.0621865 -lp: 0.0224197,-0.00760385,0.0621883 -lp: 0.0224131,-0.00750843,0.062194 -lp: 0.0224497,-0.00741306,0.0621851 -lp: 0.0224513,-0.00731771,0.062188 -lp: 0.022451,-0.0072224,0.0621917 -lp: 0.0224496,-0.00712711,0.0621957 -lp: 0.0224479,-0.00703186,0.0621997 -lp: 0.0224736,-0.00693666,0.0621945 -lp: 0.0224724,-0.00684147,0.0621984 -lp: 0.0224699,-0.00674632,0.0622028 -lp: 0.0224681,-0.00665119,0.0622069 -lp: 0.0224668,-0.0065561,0.0622109 -lp: 0.0224678,-0.00646104,0.062214 -lp: 0.0224684,-0.006366,0.0622173 -lp: 0.0224671,-0.00627099,0.0622213 -lp: 0.0224654,-0.00617601,0.0622254 -lp: 0.0224627,-0.00608106,0.0622298 -lp: 0.0224612,-0.00598613,0.0622338 -lp: 0.0224598,-0.00589123,0.0622378 -lp: 0.0224597,-0.00579635,0.0622413 -lp: 0.0224606,-0.0057015,0.0622445 -lp: 0.0224613,-0.00560668,0.0622478 -lp: 0.0224616,-0.00551188,0.0622512 -lp: 0.0224611,-0.0054171,0.0622548 -lp: 0.0224598,-0.00532234,0.0622588 -lp: 0.0224581,-0.0052276,0.0622629 -lp: 0.0224568,-0.00513289,0.0622668 -lp: 0.0224565,-0.00503819,0.0622704 -lp: 0.0224558,-0.00494352,0.0622741 -lp: 0.0224537,-0.00484886,0.0622784 -lp: 0.0224519,-0.00475423,0.0622825 -lp: 0.022451,-0.00465961,0.0622863 -lp: 0.0224505,-0.00456501,0.0622899 -lp: 0.0224511,-0.00447043,0.0622932 -lp: 0.0224521,-0.00437587,0.0622964 -lp: 0.0224525,-0.00428132,0.0622997 -lp: 0.0224529,-0.00418678,0.0623031 -lp: 0.0224522,-0.00409226,0.0623068 -lp: 0.0224516,-0.00399776,0.0623105 -lp: 0.0224511,-0.00390327,0.0623142 -lp: 0.022451,-0.00380879,0.0623177 -lp: 0.0224513,-0.00371433,0.0623211 -lp: 0.0224521,-0.00361987,0.0623243 -lp: 0.0224515,-0.00352543,0.062328 -lp: 0.0224518,-0.003431,0.0623314 -lp: 0.0224521,-0.00333658,0.0623347 -lp: 0.0224528,-0.00324217,0.062338 -lp: 0.0224518,-0.00314777,0.0623418 -lp: 0.0224526,-0.00305338,0.062345 -lp: 0.0224528,-0.002959,0.0623484 -lp: 0.0224769,-0.00286462,0.0623437 -lp: 0.0224845,-0.00277025,0.0623446 -lp: 0.0224954,-0.00267588,0.0623444 -lp: 0.0225327,-0.00258152,0.0623351 -lp: 0.0225343,-0.00248717,0.062338 -lp: 0.0225361,-0.00239282,0.0623409 -lp: 0.0225385,-0.00229847,0.0623435 -lp: 0.0225386,-0.00220413,0.062347 -lp: 0.0225381,-0.0021098,0.0623507 -lp: 0.0225383,-0.00201546,0.0623541 -lp: 0.0225359,-0.00192113,0.0623584 -lp: 0.0225399,-0.0018268,0.0623605 -lp: 0.0225402,-0.00173247,0.0623639 -lp: 0.0225375,-0.00163814,0.0623683 -lp: 0.0225355,-0.00154381,0.0623725 -lp: 0.0225359,-0.00144948,0.0623758 -lp: 0.0225364,-0.00135515,0.0623791 -lp: 0.0225355,-0.00126081,0.0623829 -lp: 0.0225414,-0.00116648,0.0623844 -lp: 0.0225771,-0.00107212,0.0623756 -lp: 0.0225768,-0.000977777,0.0623792 -lp: 0.022546,-0.000883443,0.0623932 -lp: 0.0225461,-0.00078909,0.0623967 -lp: 0.0225469,-0.000694732,0.0623999 -lp: 0.0225461,-0.000600369,0.0624037 -lp: 0.0225472,-0.000505999,0.0624068 -lp: 0.0225456,-0.000411623,0.0624108 -lp: 0.0225461,-0.000317238,0.0624141 -lp: 0.0225479,-0.000222844,0.062417 -lp: 0.0225499,-0.000128442,0.0624198 -lp: 0.0225765,-3.40159e-05,0.0624142 -lp: 0.0225834,6.04089e-05,0.0624153 -lp: 0.0225846,0.000154841,0.0624184 -lp: 0.0225836,0.000249282,0.0624222 -lp: 0.0225547,0.000343717,0.0624356 -lp: 0.0225552,0.000438183,0.0624389 -lp: 0.0225607,0.000532665,0.0624405 -lp: 0.022592,0.000627177,0.0624333 -lp: 0.0225935,0.000721684,0.0624363 -lp: 0.0225638,0.000816182,0.0624499 -lp: 0.0225632,0.000910716,0.0624536 -lp: 0.0225649,0.00100527,0.0624565 -lp: 0.0225654,0.00109983,0.0624598 -lp: 0.0225647,0.00119441,0.0624636 -lp: 0.0225665,0.00128901,0.0624664 -lp: 0.0225406,0.00138361,0.0624788 -lp: 0.0225707,0.00147827,0.062472 -lp: 0.022575,0.00157293,0.062474 -lp: 0.0225808,0.00166761,0.0624755 -lp: 0.0225824,0.0017623,0.0624785 -lp: 0.0225851,0.00185702,0.062481 -lp: 0.0225872,0.00195176,0.0624838 -lp: 0.0225894,0.00204651,0.0624866 -lp: 0.0225482,0.00214126,0.0625042 -lp: 0.022532,0.00223604,0.0625132 -lp: 0.0225359,0.00233087,0.0625154 -lp: 0.0225409,0.00242573,0.0625172 -lp: 0.0225289,0.00252059,0.0625248 -lp: 0.0225117,0.00261547,0.0625341 -lp: 0.0225137,0.0027104,0.0625369 -lp: 0.0225144,0.00280535,0.0625402 -lp: 0.0225154,0.00290032,0.0625434 -lp: 0.0225169,0.00299533,0.0625464 -lp: 0.0225202,0.00309037,0.0625488 -lp: 0.0225228,0.00318543,0.0625514 -lp: 0.0225253,0.00328052,0.062554 -lp: 0.0225282,0.00337565,0.0625566 -lp: 0.0225306,0.0034708,0.0625593 -lp: 0.0225325,0.00356598,0.0625621 -lp: 0.0225322,0.0036612,0.0625657 -lp: 0.0225339,0.00375644,0.0625687 -lp: 0.0225373,0.00385173,0.062571 -lp: 0.0225387,0.00394704,0.0625741 -lp: 0.0225394,0.00404238,0.0625774 -lp: 0.0225406,0.00413777,0.0625805 -lp: 0.0225434,0.00423318,0.062583 -lp: 0.0225459,0.00432864,0.0625857 -lp: 0.022548,0.00442413,0.0625885 -lp: 0.0225504,0.00451965,0.0625912 -lp: 0.0225529,0.00461522,0.0625939 -lp: 0.0225561,0.00471082,0.0625963 -lp: 0.0225602,0.00480646,0.0625985 -lp: 0.0225629,0.00490214,0.062601 -lp: 0.0225649,0.00499786,0.0626039 -lp: 0.0225431,0.00509359,0.0626149 -lp: 0.0225461,0.00518939,0.0626174 -lp: 0.0225496,0.00528523,0.0626197 -lp: 0.0225515,0.00538112,0.0626227 -lp: 0.0225518,0.00547704,0.0626261 -lp: 0.0225527,0.00557301,0.0626293 -lp: 0.022552,0.00566902,0.0626331 -lp: 0.022554,0.00576508,0.062636 -lp: 0.0225204,0.00586114,0.062651 -lp: 0.0225222,0.00595729,0.0626539 -lp: 0.0225262,0.00605348,0.0626561 -lp: 0.0225324,0.00614973,0.0626575 -lp: 0.0225715,0.00624608,0.0626477 -lp: 0.0225742,0.00634242,0.0626504 -lp: 0.0225765,0.00643881,0.0626531 -lp: 0.0225441,0.0065352,0.0626678 -lp: 0.022514,0.00663164,0.0626816 -lp: 0.0225174,0.00672818,0.062684 -lp: 0.0225207,0.00682477,0.0626865 -lp: 0.0225243,0.00692141,0.0626888 -lp: 0.0225604,0.00701816,0.06268 -lp: 0.0225633,0.00711491,0.0626826 -lp: 0.0225402,0.00721168,0.0626941 -lp: 0.0225766,0.00730859,0.0626852 -lp: 0.0225856,0.00740551,0.0626857 -lp: 0.0225932,0.00750249,0.0626867 -lp: 0.0225993,0.00759952,0.0626882 -lp: 0.022637,0.00769667,0.0626789 -lp: 0.0225767,0.0077937,0.0627031 -lp: 0.0226134,0.00789096,0.0626942 -lp: 0.0226161,0.00798822,0.0626968 -lp: 0.0226193,0.00808554,0.0626993 -lp: 0.0226244,0.00818292,0.0627012 -lp: 0.0226001,0.00828031,0.0627131 -lp: 0.0226018,0.00837781,0.0627161 -lp: 0.0226022,0.00847537,0.0627196 -lp: 0.0226064,0.008573,0.0627217 -lp: 0.0226109,0.0086707,0.0627238 -lp: 0.0226501,0.00876852,0.062714 -lp: 0.0225979,0.0109365,0.0628119 -lp: 0.0226004,0.0110359,0.0628147 -lp: 0.022603,0.0111354,0.0628175 -lp: 0.0225802,0.011235,0.062829 -lp: 0.022584,0.0113346,0.0628313 -lp: 0.0226189,0.0114345,0.0628231 -lp: 0.0226254,0.0115343,0.0628246 -lp: 0.0225945,0.0116341,0.0628388 -lp: 0.0225538,0.011734,0.0628564 -lp: 0.0225939,0.0118342,0.0628464 -lp: 0.0226025,0.0119344,0.0628472 -lp: 0.0225757,0.0120346,0.06286 -lp: 0.0225396,0.0121349,0.0628761 -lp: 0.0225373,0.0122353,0.0628805 -lp: 0.0225034,0.0123357,0.0628958 -lp: 0.0225469,0.0124364,0.0628847 -lp: 0.0225266,0.0125371,0.0628954 -lp: 0.0225331,0.0126379,0.0628969 -lp: 0.0225366,0.0127388,0.0628994 -lp: 0.0225414,0.0128398,0.0629015 -lp: 0.0225451,0.0129409,0.0629039 -lp: 0.0225503,0.013042,0.0629059 -lp: 0.0225559,0.0131433,0.0629077 -lp: 0.0225622,0.0132447,0.0629093 -lp: 0.0225675,0.0133462,0.0629112 -lp: 0.0225729,0.0134477,0.0629132 -lp: 0.0225763,0.0135494,0.0629157 -lp: 0.022548,0.0136511,0.0629292 -lp: 0.0225514,0.0137529,0.0629318 -lp: 0.0225577,0.0138549,0.0629334 -lp: 0.022563,0.013957,0.0629354 -lp: 0.0225699,0.0140592,0.0629368 -lp: 0.0225717,0.0141614,0.0629399 -lp: 0.0225737,0.0142638,0.062943 -lp: 0.0225503,0.0143662,0.0629548 -lp: 0.0225549,0.0144688,0.062957 -lp: 0.0225364,0.0145714,0.0629671 -lp: 0.0225431,0.0146743,0.0629686 -lp: 0.0225473,0.0147772,0.062971 -lp: 0.0225508,0.0148802,0.0629736 -lp: 0.022519,0.0149832,0.0629883 -lp: 0.022525,0.0150865,0.06299 -lp: 0.0225294,0.0151898,0.0629923 -lp: 0.0225346,0.0152933,0.0629944 -lp: 0.0225415,0.0153969,0.0629959 -lp: 0.0225494,0.0155006,0.062997 -lp: 0.0225556,0.0156044,0.0629987 -lp: 0.0225596,0.0157083,0.0630012 -lp: 0.0225669,0.0158124,0.0630025 -lp: 0.0225758,0.0159166,0.0630033 -lp: 0.0225838,0.0160208,0.0630044 -lp: 0.0225882,0.0161252,0.0630068 -lp: 0.022557,0.0162297,0.0630213 -lp: 0.0225349,0.0163342,0.0630327 -lp: 0.022536,0.016439,0.0630362 -lp: 0.0225416,0.0165439,0.0630382 -lp: 0.0225436,0.0166489,0.0630414 -lp: 0.0225498,0.016754,0.0630431 -lp: 0.0225327,0.0168592,0.0630529 -lp: 0.022542,0.0169646,0.0630535 -lp: 0.0225395,0.0170701,0.0630583 -lp: 0.0225469,0.0171758,0.0630597 -lp: 0.0225597,0.0172816,0.0630592 -lp: 0.0225741,0.0173875,0.0630582 -lp: 0.0226222,0.0174937,0.0630457 -lp: 0.0225934,0.0175998,0.0630594 -lp: 0.0226056,0.0177061,0.0630592 -lp: 0.0224627,0.0220784,0.0632695 -lp: 0.0224993,0.0221912,0.0632611 -lp: 0.0225121,0.022304,0.0632609 -lp: 0.0225236,0.0224171,0.0632612 -lp: 0.022493,0.0225302,0.0632758 -lp: 0.0225031,0.0226436,0.0632765 -lp: 0.0225095,0.0227572,0.0632785 -lp: 0.0225196,0.0228709,0.0632793 -lp: 0.0225294,0.0229849,0.0632801 -lp: 0.0225092,0.0230989,0.0632912 -lp: 0.0225171,0.0232133,0.0632928 -lp: 0.0225261,0.0233278,0.0632939 -lp: 0.0225363,0.0234425,0.0632947 -lp: 0.0225482,0.0235574,0.0632948 -lp: 0.0225576,0.0236725,0.0632959 -lp: 0.022534,0.0237877,0.0633082 -lp: 0.0225034,0.0239031,0.0633229 -lp: 0.022509,0.0240188,0.0633253 -lp: 0.0225123,0.0241346,0.0633284 -lp: 0.0224834,0.0242506,0.0633426 -lp: 0.0224928,0.0243669,0.0633437 -lp: 0.0225052,0.0244834,0.0633437 -lp: 0.0225176,0.0246001,0.0633438 -lp: 0.0225309,0.024717,0.0633436 -lp: 0.022509,0.024834,0.0633554 -lp: 0.0225159,0.0249513,0.0633574 -lp: 0.0225199,0.0250689,0.0633603 -lp: 0.0225298,0.0251866,0.0633613 -lp: 0.0225054,0.0253045,0.063374 -lp: 0.0224807,0.0254225,0.0633868 -lp: 0.0224879,0.0255409,0.0633887 -lp: 0.0224985,0.0256595,0.0633895 -lp: 0.0225049,0.0257783,0.0633916 -lp: 0.0224749,0.0258973,0.0634063 -lp: 0.0224839,0.0260165,0.0634076 -lp: 0.0224962,0.026136,0.0634078 -lp: 0.0225093,0.0262557,0.0634078 -lp: 0.0225233,0.0263757,0.0634074 -lp: 0.0225021,0.0264958,0.0634191 -lp: 0.0225109,0.0266162,0.0634205 -lp: 0.0225189,0.0267368,0.0634222 -lp: 0.0225304,0.0268577,0.0634228 -lp: 0.0225406,0.0269788,0.0634238 -lp: 0.0225513,0.0271001,0.0634246 -lp: 0.0224848,0.0272214,0.0634518 -lp: 0.0224917,0.0273432,0.0634539 -lp: 0.02246,0.0274652,0.0634693 -lp: 0.0224736,0.0275875,0.0634691 -lp: 0.0224854,0.02771,0.0634696 -lp: 0.0224971,0.0278328,0.0634702 -lp: 0.0224753,0.0279557,0.0634821 -lp: 0.0224872,0.028079,0.0634826 -lp: 0.0225005,0.0282026,0.0634827 -lp: 0.0225155,0.0283264,0.0634821 -lp: 0.0225279,0.0284504,0.0634824 -lp: 0.0225319,0.0285747,0.0634856 -lp: 0.022464,0.028699,0.0635134 -lp: 0.0224728,0.0288238,0.063515 -lp: 0.0224395,0.0289488,0.063531 -lp: 0.0224522,0.0290741,0.0635313 -lp: 0.022433,0.0291996,0.0635425 -lp: 0.0224451,0.0293255,0.063543 -lp: 0.0224598,0.0294516,0.0635427 -lp: 0.022475,0.0295781,0.0635421 -lp: 0.0224872,0.0297047,0.0635427 -lp: 0.0224967,0.0298317,0.0635441 -lp: 0.0225063,0.0299589,0.0635455 -lp: 0.0224812,0.0300863,0.0635588 -lp: 0.0224548,0.030214,0.0635725 -lp: 0.0224672,0.0303421,0.063573 -lp: 0.0224753,0.0304704,0.063575 -lp: 0.0224477,0.0305989,0.0635892 -lp: 0.0224596,0.0307279,0.0635898 -lp: 0.0224421,0.030857,0.0636006 -lp: 0.022454,0.0309865,0.0636013 -lp: 0.022465,0.0311163,0.0636024 -lp: 0.0224769,0.0312464,0.0636031 -lp: 0.0224923,0.0313768,0.0636026 -lp: 0.0225039,0.0315076,0.0636035 -lp: 0.0224741,0.0316384,0.0636185 -lp: 0.0224473,0.0317696,0.0636325 -lp: 0.022463,0.0319013,0.063632 -lp: 0.0224784,0.0320332,0.0636316 -lp: 0.0224936,0.0321654,0.0636313 -lp: 0.0224314,0.0322978,0.0636574 -lp: 0.022444,0.0324306,0.063658 -lp: 0.0224547,0.0325638,0.0636593 -lp: 0.0224677,0.0326973,0.0636598 -lp: 0.0224786,0.0328311,0.063661 -lp: 0.0224912,0.0329653,0.0636617 -lp: 0.0224271,0.0330995,0.0636885 -lp: 0.0224392,0.0332343,0.0636894 -lp: 0.0224491,0.0333694,0.063691 -lp: 0.0224667,0.0335049,0.06369 -lp: 0.022482,0.0336407,0.0636897 -lp: 0.0224641,0.0337768,0.0637009 -lp: 0.0224365,0.0339132,0.0637154 -lp: 0.0224493,0.03405,0.063716 -lp: 0.0224611,0.0341871,0.0637171 -lp: 0.0224755,0.0343247,0.0637172 -lp: 0.0224868,0.0344625,0.0637185 -lp: 0.022426,0.0346006,0.0637443 -lp: 0.0224391,0.0347391,0.063745 -lp: 0.0224564,0.0348781,0.0637442 -lp: 0.0224705,0.0350174,0.0637445 -lp: 0.0224852,0.0351571,0.0637446 -lp: 0.022459,0.035297,0.0637587 -lp: 0.0224421,0.0354373,0.0637697 -lp: 0.0224577,0.0355781,0.0637696 -lp: 0.02247,0.0357192,0.0637706 -lp: 0.0224818,0.0358607,0.0637718 -lp: 0.0224922,0.0360026,0.0637735 -lp: 0.0224263,0.0361447,0.0638012 -lp: 0.0224428,0.0362873,0.0638009 -lp: 0.0224573,0.0364304,0.0638012 -lp: 0.0224766,0.0365739,0.0637999 -lp: 0.0224929,0.0367177,0.0637996 -lp: 0.0225099,0.036862,0.0637991 -lp: 0.0224849,0.0370065,0.063813 -lp: 0.0224647,0.0371514,0.0638253 -lp: 0.022478,0.0372969,0.0638261 -lp: 0.0224936,0.0374428,0.0638262 -lp: 0.022507,0.037589,0.063827 -lp: 0.0224865,0.0377356,0.0638394 -lp: 0.0224553,0.0378826,0.0638555 -lp: 0.0224718,0.0380301,0.0638553 -lp: 0.0224867,0.038178,0.0638557 -lp: 0.0224271,0.0383262,0.0638815 -lp: 0.0224449,0.038475,0.0638809 -lp: 0.0224609,0.0386243,0.063881 -lp: 0.0224768,0.038774,0.0638811 -lp: 0.022496,0.0389241,0.06388 -lp: 0.0225075,0.0390746,0.0638817 -lp: 0.0224837,0.0392255,0.0638953 -lp: 0.0224573,0.0393769,0.06391 -lp: 0.0224767,0.0395288,0.063909 -lp: 0.0224931,0.0396812,0.063909 -lp: 0.0224293,0.0398338,0.0639364 -lp: 0.0224483,0.0399871,0.0639356 -lp: 0.02247,0.0401409,0.0639338 -lp: 0.0224859,0.0402951,0.0639341 -lp: 0.0225026,0.0404499,0.0639341 -lp: 0.0225162,0.0406051,0.0639352 -lp: 0.0224577,0.0407605,0.0639609 -lp: 0.0224726,0.0409167,0.0639616 -lp: 0.0224912,0.0410733,0.063961 -lp: 0.0225046,0.0412305,0.0639622 -lp: 0.0224445,0.0413879,0.0639886 -lp: 0.0224637,0.0415461,0.0639879 -lp: 0.0224833,0.0417047,0.063987 -lp: 0.022503,0.0418639,0.0639862 -lp: 0.0225217,0.0420236,0.0639857 -lp: 0.022492,0.0421837,0.0640017 -lp: 0.0225047,0.0423444,0.0640033 -lp: 0.0224817,0.0425055,0.0640172 -lp: 0.0225037,0.0426673,0.0640156 -lp: 0.0225243,0.0428297,0.0640146 -lp: 0.0224636,0.0429923,0.0640413 -lp: 0.0224784,0.0431557,0.0640423 -lp: 0.0224991,0.0433196,0.0640413 -lp: 0.0225227,0.0434842,0.0640393 -lp: 0.0225457,0.0436492,0.0640375 -lp: 0.0225666,0.0438149,0.0640365 -lp: 0.0225021,0.0439808,0.0640647 -lp: 0.0225199,0.0441476,0.0640647 -lp: 0.0225433,0.0443149,0.0640629 -lp: 0.0225619,0.0444828,0.0640627 -lp: 0.022591,0.0446514,0.064059 -lp: 0.0225681,0.0448203,0.0640731 -lp: 0.0225368,0.0449899,0.06409 -lp: 0.0225583,0.0451602,0.064089 -lp: 0.0225841,0.0453311,0.0640865 -lp: 0.0226654,0.0455029,0.064065 -lp: 0.02253,0.0456744,0.0641176 -lp: 0.0225948,0.0458473,0.0641019 -lp: 0.022569,0.0460205,0.0641171 -lp: 0.0223326,-0.0183006,0.052131 -lp: 0.0223234,-0.0182085,0.0521383 -lp: 0.0223163,-0.0181166,0.0521448 -lp: 0.0223269,-0.0180251,0.052145 -lp: 0.0223233,-0.0179335,0.0521503 -lp: 0.0223202,-0.017842,0.0521553 -lp: 0.0223163,-0.0177506,0.0521607 -lp: 0.0223098,-0.0176592,0.052167 -lp: 0.022305,-0.017568,0.0521727 -lp: 0.0223004,-0.017477,0.0521783 -lp: 0.0223239,-0.0173865,0.0521739 -lp: 0.0223475,-0.0172961,0.0521695 -lp: 0.022344,-0.0172054,0.0521747 -lp: 0.022339,-0.0171147,0.0521804 -lp: 0.0223373,-0.0170242,0.0521849 -lp: 0.0223531,-0.0169341,0.0521832 -lp: 0.0223493,-0.0168438,0.0521885 -lp: 0.022344,-0.0167536,0.0521943 -lp: 0.0223398,-0.0166635,0.0521998 -lp: 0.0223339,-0.0165735,0.0522058 -lp: 0.0223331,-0.0164836,0.05221 -lp: 0.0223288,-0.0163938,0.0522154 -lp: 0.0223247,-0.0163041,0.0522208 -lp: 0.0223181,-0.0162145,0.052227 -lp: 0.0223136,-0.016125,0.0522325 -lp: 0.0223257,-0.0160358,0.0522321 -lp: 0.0223249,-0.0159466,0.0522363 -lp: 0.0223561,-0.0158579,0.0522291 -lp: 0.0223561,-0.0157689,0.052233 -lp: 0.0223502,-0.0156798,0.0522389 -lp: 0.0223724,-0.0155913,0.0522349 -lp: 0.0223674,-0.0155025,0.0522406 -lp: 0.0223634,-0.0154138,0.0522458 -lp: 0.0223574,-0.0153251,0.0522518 -lp: 0.0223751,-0.0152369,0.0522494 -lp: 0.0223709,-0.0151484,0.0522548 -lp: 0.022368,-0.0150601,0.0522596 -lp: 0.0223625,-0.0149718,0.0522654 -lp: 0.0223587,-0.0148836,0.0522706 -lp: 0.0223541,-0.0147955,0.0522761 -lp: 0.0223539,-0.0147075,0.05228 -lp: 0.0223519,-0.0146196,0.0522845 -lp: 0.022348,-0.0145318,0.0522897 -lp: 0.022342,-0.014444,0.0522957 -lp: 0.0223368,-0.0143563,0.0523014 -lp: 0.0223306,-0.0142687,0.0523074 -lp: 0.0223477,-0.0141815,0.0523051 -lp: 0.0223774,-0.0140946,0.0522984 -lp: 0.0223722,-0.0140072,0.052304 -lp: 0.0223669,-0.0139199,0.0523097 -lp: 0.0223619,-0.0138328,0.0523153 -lp: 0.0223604,-0.0137457,0.0523196 -lp: 0.0223614,-0.0136588,0.052323 -lp: 0.0223794,-0.0135721,0.0523204 -lp: 0.022408,-0.0134857,0.052314 -lp: 0.022406,-0.0133989,0.0523185 -lp: 0.0224009,-0.0133122,0.0523241 -lp: 0.0223948,-0.0132255,0.0523301 -lp: 0.0223896,-0.013139,0.0523357 -lp: 0.0223866,-0.0130525,0.0523405 -lp: 0.022385,-0.0129661,0.0523448 -lp: 0.0223808,-0.0128798,0.0523501 -lp: 0.0223773,-0.0127936,0.0523551 -lp: 0.0223729,-0.0127074,0.0523604 -lp: 0.0223692,-0.0126213,0.0523655 -lp: 0.0223666,-0.0125352,0.0523701 -lp: 0.022366,-0.0124493,0.0523741 -lp: 0.0223628,-0.0123634,0.052379 -lp: 0.0223622,-0.0122776,0.0523829 -lp: 0.0223897,-0.0121922,0.0523769 -lp: 0.0224075,-0.0121068,0.0523743 -lp: 0.0224036,-0.0120212,0.0523794 -lp: 0.0224025,-0.0119356,0.0523835 -lp: 0.0223996,-0.0118501,0.0523883 -lp: 0.0223961,-0.0117647,0.0523932 -lp: 0.022392,-0.0116793,0.0523984 -lp: 0.0223893,-0.011594,0.0524031 -lp: 0.022386,-0.0115088,0.052408 -lp: 0.0224099,-0.0114239,0.0524032 -lp: 0.0224088,-0.0113389,0.0524073 -lp: 0.0224367,-0.0112541,0.0524011 -lp: 0.0224343,-0.0111692,0.0524057 -lp: 0.0224314,-0.0110842,0.0524104 -lp: 0.0224277,-0.0109994,0.0524154 -lp: 0.0224239,-0.0109145,0.0524204 -lp: 0.0224201,-0.0108298,0.0524255 -lp: 0.0224157,-0.0107451,0.0524307 -lp: 0.0224112,-0.0106604,0.052436 -lp: 0.022407,-0.0105759,0.0524412 -lp: 0.0224029,-0.0104913,0.0524463 -lp: 0.0223997,-0.0104069,0.0524511 -lp: 0.0223966,-0.0103225,0.0524559 -lp: 0.0223947,-0.0102381,0.0524602 -lp: 0.0223922,-0.0101538,0.0524648 -lp: 0.0223899,-0.0100696,0.0524693 -lp: 0.0223868,-0.00998539,0.0524741 -lp: 0.0224162,-0.00990155,0.0524673 -lp: 0.0224154,-0.00981748,0.0524713 -lp: 0.0224128,-0.00973344,0.0524758 -lp: 0.0224088,-0.00964945,0.0524809 -lp: 0.022408,-0.00956553,0.0524848 -lp: 0.0224078,-0.00948166,0.0524886 -lp: 0.02241,-0.00939787,0.0524914 -lp: 0.0224092,-0.0093141,0.0524954 -lp: 0.0224488,-0.00923072,0.052485 -lp: 0.0224455,-0.00914702,0.0524898 -lp: 0.0224448,-0.00906338,0.0524937 -lp: 0.0224425,-0.00897978,0.0524981 -lp: 0.0224405,-0.00889623,0.0525025 -lp: 0.0224381,-0.00881271,0.052507 -lp: 0.0224364,-0.00872925,0.0525112 -lp: 0.0224346,-0.00864583,0.0525155 -lp: 0.0224347,-0.00856247,0.0525191 -lp: 0.0224329,-0.00847914,0.0525233 -lp: 0.0224346,-0.00839587,0.0525264 -lp: 0.0224339,-0.00831263,0.0525302 -lp: 0.0224598,-0.00822964,0.0525247 -lp: 0.0224567,-0.00814646,0.0525294 -lp: 0.0224537,-0.00806332,0.0525341 -lp: 0.0224512,-0.00798022,0.0525386 -lp: 0.022449,-0.00789716,0.052543 -lp: 0.0224467,-0.00781415,0.0525474 -lp: 0.0224451,-0.00773117,0.0525516 -lp: 0.0224431,-0.00764823,0.0525559 -lp: 0.0224426,-0.00756534,0.0525597 -lp: 0.0224416,-0.00748248,0.0525637 -lp: 0.0224402,-0.00739965,0.0525678 -lp: 0.0224392,-0.00731686,0.0525718 -lp: 0.0224373,-0.0072341,0.052576 -lp: 0.022436,-0.00715138,0.0525801 -lp: 0.0224335,-0.00706869,0.0525846 -lp: 0.0224311,-0.00698602,0.052589 -lp: 0.0224288,-0.00690339,0.0525935 -lp: 0.0224596,-0.006821,0.0525861 -lp: 0.0224572,-0.00673843,0.0525906 -lp: 0.0224219,-0.0066557,0.0526067 -lp: 0.0224201,-0.0065732,0.0526109 -lp: 0.0224526,-0.00649093,0.052603 -lp: 0.0224535,-0.0064085,0.0526063 -lp: 0.0224516,-0.00632608,0.0526105 -lp: 0.0224497,-0.0062437,0.0526148 -lp: 0.0224491,-0.00616134,0.0526186 -lp: 0.0224474,-0.00607901,0.0526228 -lp: 0.0224465,-0.00599671,0.0526267 -lp: 0.0224459,-0.00591444,0.0526305 -lp: 0.0224462,-0.0058322,0.052634 -lp: 0.0224443,-0.00574997,0.0526382 -lp: 0.0224426,-0.00566777,0.0526424 -lp: 0.0224663,-0.00558572,0.0526376 -lp: 0.0224684,-0.00550358,0.0526404 -lp: 0.0224692,-0.00542146,0.0526437 -lp: 0.0224682,-0.00533936,0.0526476 -lp: 0.022467,-0.00525727,0.0526516 -lp: 0.0224654,-0.00517521,0.0526558 -lp: 0.0224656,-0.00509317,0.0526593 -lp: 0.0224665,-0.00501116,0.0526625 -lp: 0.0224678,-0.00492917,0.0526656 -lp: 0.0224672,-0.00484719,0.0526694 -lp: 0.0224618,-0.00476521,0.0526749 -lp: 0.022458,-0.00468326,0.0526798 -lp: 0.0224568,-0.00460133,0.0526838 -lp: 0.0224566,-0.00451943,0.0526875 -lp: 0.0224586,-0.00443755,0.0526903 -lp: 0.0224598,-0.00435569,0.0526935 -lp: 0.0224664,-0.00427386,0.0526947 -lp: 0.0224845,-0.00419209,0.0526918 -lp: 0.0224857,-0.00411027,0.052695 -lp: 0.0224853,-0.00402846,0.0526987 -lp: 0.0224856,-0.00394666,0.0527021 -lp: 0.0224848,-0.00386488,0.052706 -lp: 0.0224847,-0.00378311,0.0527096 -lp: 0.022484,-0.00370135,0.0527134 -lp: 0.0224822,-0.0036196,0.0527176 -lp: 0.0224805,-0.00353787,0.0527218 -lp: 0.0224794,-0.00345614,0.0527257 -lp: 0.0224806,-0.00337444,0.0527289 -lp: 0.0224814,-0.00329274,0.0527321 -lp: 0.0224812,-0.00321105,0.0527357 -lp: 0.0224816,-0.00312937,0.0527392 -lp: 0.0224825,-0.0030477,0.0527424 -lp: 0.0225121,-0.0029661,0.0527355 -lp: 0.0225139,-0.00288445,0.0527384 -lp: 0.0225163,-0.0028028,0.0527411 -lp: 0.0225171,-0.00272116,0.0527444 -lp: 0.022517,-0.00263952,0.052748 -lp: 0.0225159,-0.00255789,0.0527519 -lp: 0.0225154,-0.00247626,0.0527556 -lp: 0.0225158,-0.00239464,0.0527591 -lp: 0.0225158,-0.00231302,0.0527626 -lp: 0.0225162,-0.0022314,0.052766 -lp: 0.0225167,-0.00214979,0.0527694 -lp: 0.0225192,-0.00206819,0.0527721 -lp: 0.0225198,-0.00198658,0.0527754 -lp: 0.0225185,-0.00190498,0.0527794 -lp: 0.0225191,-0.00182338,0.0527828 -lp: 0.0225195,-0.00174178,0.0527862 -lp: 0.0225201,-0.00166018,0.0527896 -lp: 0.0225199,-0.00157857,0.0527932 -lp: 0.0225206,-0.00149697,0.0527965 -lp: 0.0225227,-0.00141537,0.0527993 -lp: 0.0225236,-0.00133377,0.0528025 -lp: 0.0225241,-0.00125216,0.0528059 -lp: 0.0225247,-0.00117055,0.0528093 -lp: 0.0225254,-0.00108894,0.0528126 -lp: 0.022526,-0.00100733,0.0528159 -lp: 0.0225259,-0.000925707,0.0528195 -lp: 0.0225261,-0.000844083,0.052823 -lp: 0.0225277,-0.000762455,0.052826 -lp: 0.0225296,-0.00068082,0.0528288 -lp: 0.0225324,-0.00059918,0.0528314 -lp: 0.0225334,-0.000517533,0.0528346 -lp: 0.0225312,-0.00043588,0.0528389 -lp: 0.0225319,-0.000354219,0.0528423 -lp: 0.022535,-0.000272549,0.0528447 -lp: 0.0225364,-0.000190871,0.0528478 -lp: 0.0225364,-0.000109185,0.0528513 -lp: 0.0225365,-2.74898e-05,0.0528549 -lp: 0.0225374,5.42159e-05,0.0528581 -lp: 0.0225385,0.000135932,0.0528613 -lp: 0.0225409,0.000217661,0.052864 -lp: 0.0225434,0.000299401,0.0528667 -lp: 0.0225459,0.000381153,0.0528693 -lp: 0.0225475,0.000462917,0.0528723 -lp: 0.0225481,0.000544692,0.0528757 -lp: 0.022549,0.000626481,0.0528789 -lp: 0.0225496,0.000708284,0.0528823 -lp: 0.0225514,0.000790102,0.0528852 -lp: 0.0225542,0.000871937,0.0528878 -lp: 0.0225568,0.000953788,0.0528904 -lp: 0.0225583,0.00103565,0.0528934 -lp: 0.0225588,0.00111753,0.0528968 -lp: 0.0225587,0.00119943,0.0529005 -lp: 0.0225596,0.00128134,0.0529037 -lp: 0.0225611,0.00136327,0.0529067 -lp: 0.0225631,0.00144522,0.0529096 -lp: 0.0225655,0.0015272,0.0529123 -lp: 0.0225685,0.00160919,0.0529148 -lp: 0.0225727,0.0016912,0.0529169 -lp: 0.0225751,0.00177324,0.0529197 -lp: 0.022574,0.00185528,0.0529236 -lp: 0.0225745,0.00193735,0.052927 -lp: 0.0225761,0.00201944,0.05293 -lp: 0.0225767,0.00210155,0.0529334 -lp: 0.0225782,0.00218369,0.0529364 -lp: 0.022552,0.00226577,0.0529493 -lp: 0.0225542,0.00234796,0.0529521 -lp: 0.0225561,0.00243017,0.052955 -lp: 0.022559,0.0025124,0.0529575 -lp: 0.0225612,0.00259466,0.0529604 -lp: 0.0225628,0.00267695,0.0529634 -lp: 0.0225651,0.00275926,0.0529661 -lp: 0.0225679,0.0028416,0.0529687 -lp: 0.0225717,0.00292397,0.052971 -lp: 0.0225746,0.00300637,0.0529735 -lp: 0.0225494,0.00308869,0.052986 -lp: 0.0225483,0.00317113,0.05299 -lp: 0.0225488,0.0032536,0.0529935 -lp: 0.0225537,0.00333612,0.0529953 -lp: 0.0225567,0.00341866,0.0529978 -lp: 0.0225593,0.00350124,0.0530005 -lp: 0.0225598,0.00358383,0.0530039 -lp: 0.0225617,0.00366646,0.0530069 -lp: 0.0225625,0.00374912,0.0530102 -lp: 0.0225458,0.00383174,0.0530197 -lp: 0.0225475,0.00391447,0.0530227 -lp: 0.0225497,0.00399723,0.0530255 -lp: 0.0225197,0.00407988,0.0530398 -lp: 0.0225218,0.00416271,0.0530426 -lp: 0.0225235,0.00424558,0.0530456 -lp: 0.0225262,0.00432849,0.0530483 -lp: 0.0225298,0.00441143,0.0530506 -lp: 0.022534,0.00449442,0.0530527 -lp: 0.0225356,0.00457744,0.0530558 -lp: 0.0225376,0.00466049,0.0530587 -lp: 0.0225395,0.00474358,0.0530617 -lp: 0.0225422,0.00482672,0.0530643 -lp: 0.0225449,0.00490989,0.053067 -lp: 0.0225476,0.00499311,0.0530697 -lp: 0.0225508,0.00507637,0.0530721 -lp: 0.0225552,0.00515967,0.0530742 -lp: 0.0225587,0.00524302,0.0530766 -lp: 0.0225619,0.0053264,0.0530791 -lp: 0.0225638,0.00540982,0.0530821 -lp: 0.022566,0.00549329,0.0530849 -lp: 0.0225692,0.00557681,0.0530874 -lp: 0.0225731,0.00566037,0.0530897 -lp: 0.0225765,0.00574398,0.0530921 -lp: 0.0225789,0.00582763,0.0530949 -lp: 0.0225828,0.00591133,0.0530972 -lp: 0.0225876,0.00599509,0.0530992 -lp: 0.0225921,0.00607889,0.0531012 -lp: 0.0225944,0.00616273,0.0531041 -lp: 0.0225965,0.00624661,0.053107 -lp: 0.0226002,0.00633055,0.0531093 -lp: 0.0226025,0.00641454,0.0531121 -lp: 0.0226056,0.00649858,0.0531147 -lp: 0.0225875,0.00658251,0.0531248 -lp: 0.0225919,0.00666666,0.0531269 -lp: 0.0225644,0.00675063,0.0531403 -lp: 0.0225648,0.00683485,0.0531438 -lp: 0.0225671,0.00691914,0.0531466 -lp: 0.022572,0.0070035,0.0531486 -lp: 0.0225775,0.00708792,0.0531503 -lp: 0.0225827,0.00717239,0.0531522 -lp: 0.0225867,0.00725691,0.0531544 -lp: 0.0225912,0.00734149,0.0531565 -lp: 0.0225925,0.0074261,0.0531598 -lp: 0.0225636,0.00751052,0.0531737 -lp: 0.0225647,0.00759524,0.053177 -lp: 0.022569,0.00768004,0.0531791 -lp: 0.0225524,0.00776473,0.0531887 -lp: 0.0225584,0.00784967,0.0531903 -lp: 0.0225622,0.00793465,0.0531926 -lp: 0.0225661,0.00801968,0.053195 -lp: 0.0225701,0.00810478,0.0531972 -lp: 0.0225748,0.00818995,0.0531993 -lp: 0.0225786,0.00827518,0.0532016 -lp: 0.0225822,0.00836046,0.0532041 -lp: 0.0225845,0.00844579,0.053207 -lp: 0.022589,0.00853121,0.0532091 -lp: 0.0225933,0.0086167,0.0532114 -lp: 0.0225978,0.00870225,0.0532135 -lp: 0.0226012,0.00878785,0.053216 -lp: 0.0226054,0.00887353,0.0532182 -lp: 0.0226102,0.00895929,0.0532203 -lp: 0.0226167,0.00904512,0.0532217 -lp: 0.022621,0.00913101,0.0532239 -lp: 0.0226023,0.00921674,0.0532343 -lp: 0.0226049,0.00930274,0.0532371 -lp: 0.0226076,0.00938882,0.0532399 -lp: 0.0226135,0.009475,0.0532416 -lp: 0.0226193,0.00956125,0.0532433 -lp: 0.0225953,0.00964727,0.0532555 -lp: 0.0225991,0.00973364,0.0532579 -lp: 0.0225675,0.00981972,0.0532729 -lp: 0.0225695,0.00990622,0.053276 -lp: 0.0225728,0.0099928,0.0532786 -lp: 0.0225787,0.0100795,0.0532803 -lp: 0.0225847,0.0101663,0.0532819 -lp: 0.0225714,0.0102529,0.0532904 -lp: 0.0225764,0.0103398,0.0532924 -lp: 0.0225819,0.0104268,0.0532942 -lp: 0.0225876,0.0105139,0.053296 -lp: 0.0225934,0.010601,0.0532977 -lp: 0.0225984,0.0106882,0.0532998 -lp: 0.0226031,0.0107755,0.0533019 -lp: 0.0226049,0.0108629,0.0533051 -lp: 0.0226095,0.0109503,0.0533073 -lp: 0.022613,0.0110379,0.0533098 -lp: 0.0226191,0.0111255,0.0533115 -lp: 0.0225985,0.0112129,0.0533226 -lp: 0.022604,0.0113007,0.0533245 -lp: 0.0226082,0.0113886,0.0533268 -lp: 0.0226141,0.0114766,0.0533286 -lp: 0.0226183,0.0115647,0.0533309 -lp: 0.0226234,0.0116528,0.0533329 -lp: 0.0225689,0.0117403,0.0533561 -lp: 0.0225752,0.0118286,0.0533577 -lp: 0.0225794,0.011917,0.0533601 -lp: 0.0225846,0.0120055,0.053362 -lp: 0.0225893,0.0120941,0.0533642 -lp: 0.0225963,0.0121828,0.0533657 -lp: 0.0225995,0.0122716,0.0533684 -lp: 0.0226056,0.0123604,0.0533701 -lp: 0.0225889,0.0124491,0.0533799 -lp: 0.0225937,0.0125382,0.053382 -lp: 0.0225969,0.0126273,0.0533848 -lp: 0.0226028,0.0127165,0.0533866 -lp: 0.0226072,0.0128059,0.0533889 -lp: 0.0226137,0.0128953,0.0533905 -lp: 0.0225934,0.0129845,0.0534016 -lp: 0.0225991,0.0130742,0.0534035 -lp: 0.0226061,0.0131639,0.0534049 -lp: 0.0226148,0.0132538,0.0534058 -lp: 0.0226213,0.0133437,0.0534074 -lp: 0.0226268,0.0134338,0.0534093 -lp: 0.0226017,0.0135235,0.0534221 -lp: 0.0226088,0.0136138,0.0534235 -lp: 0.0225843,0.0137037,0.0534362 -lp: 0.0225888,0.0137941,0.0534385 -lp: 0.0225914,0.0138846,0.0534415 -lp: 0.022598,0.0139753,0.0534431 -lp: 0.0226013,0.0140661,0.0534459 -lp: 0.0226076,0.0141569,0.0534476 -lp: 0.0226134,0.0142479,0.0534495 -lp: 0.0226006,0.0143388,0.0534581 -lp: 0.0225822,0.0144296,0.0534685 -lp: 0.0225879,0.0145209,0.0534705 -lp: 0.0225943,0.0146124,0.0534722 -lp: 0.0226029,0.0147039,0.0534731 -lp: 0.0226078,0.0147956,0.0534754 -lp: 0.0226119,0.0148873,0.0534779 -lp: 0.0225851,0.0149787,0.0534914 -lp: 0.0225926,0.0150707,0.0534928 -lp: 0.0225986,0.0151628,0.0534947 -lp: 0.0226051,0.0152551,0.0534964 -lp: 0.0226111,0.0153474,0.0534983 -lp: 0.0225904,0.0154395,0.0535096 -lp: 0.0225972,0.0155321,0.0535112 -lp: 0.0226056,0.0156249,0.0535123 -lp: 0.0226129,0.0157177,0.0535138 -lp: 0.0226223,0.0158107,0.0535145 -lp: 0.0226279,0.0159038,0.0535166 -lp: 0.0226086,0.0159966,0.0535274 -lp: 0.0225886,0.0160895,0.0535386 -lp: 0.022594,0.0161829,0.0535407 -lp: 0.0225673,0.016276,0.0535542 -lp: 0.0225754,0.0163697,0.0535554 -lp: 0.0225833,0.0164636,0.0535568 -lp: 0.0225925,0.0165576,0.0535576 -lp: 0.0225991,0.0166517,0.0535593 -lp: 0.0226047,0.0167459,0.0535615 -lp: 0.0226117,0.0168403,0.0535631 -lp: 0.0226197,0.0169348,0.0535644 -lp: 0.0226274,0.0170295,0.0535658 -lp: 0.0225776,0.0171233,0.0535875 -lp: 0.0225825,0.0172182,0.0535899 -lp: 0.0225902,0.0173132,0.0535913 -lp: 0.0225974,0.0174084,0.0535929 -lp: 0.0226066,0.0175038,0.0535938 -lp: 0.0226157,0.0175993,0.0535948 -lp: 0.0226249,0.0176949,0.0535956 -lp: 0.0226017,0.0177901,0.053608 -lp: 0.0226111,0.0178861,0.0536089 -lp: 0.0225913,0.0179816,0.05362 -lp: 0.0225984,0.0180778,0.0536217 -lp: 0.0226067,0.0181741,0.053623 -lp: 0.0226177,0.0182707,0.0536233 -lp: 0.0226259,0.0183673,0.0536246 -lp: 0.022633,0.0184641,0.0536263 -lp: 0.0226408,0.018561,0.0536278 -lp: 0.0226211,0.0186576,0.0536389 -lp: 0.0225998,0.0187543,0.0536507 -lp: 0.0226077,0.0188517,0.0536521 -lp: 0.0226125,0.0189491,0.0536547 -lp: 0.0226213,0.0190469,0.0536558 -lp: 0.0225957,0.0191441,0.0536691 -lp: 0.0226072,0.0192421,0.0536693 -lp: 0.0225902,0.0193398,0.0536796 -lp: 0.0226004,0.0194382,0.0536803 -lp: 0.0226086,0.0195367,0.0536817 -lp: 0.022618,0.0196354,0.0536826 -lp: 0.0226235,0.0197341,0.053685 -lp: 0.0226004,0.0198325,0.0536975 -lp: 0.0225755,0.019931,0.0537106 -lp: 0.0225855,0.0200303,0.0537114 -lp: 0.0225963,0.0201298,0.0537118 -lp: 0.0226082,0.0202295,0.053712 -lp: 0.0226176,0.0203294,0.053713 -lp: 0.0226265,0.0204294,0.0537142 -lp: 0.0225755,0.0205283,0.0537366 -lp: 0.0225847,0.0206287,0.0537377 -lp: 0.0225925,0.0207291,0.0537393 -lp: 0.0226005,0.0208298,0.0537409 -lp: 0.0226086,0.0209306,0.0537424 -lp: 0.0226198,0.0210317,0.0537428 -lp: 0.0226314,0.021133,0.0537431 -lp: 0.0226433,0.0212345,0.0537433 -lp: 0.0225898,0.0213347,0.0537667 -lp: 0.022598,0.0214365,0.0537682 -lp: 0.0226097,0.0215385,0.0537685 -lp: 0.0226228,0.0216407,0.0537683 -lp: 0.0226354,0.0217431,0.0537683 -lp: 0.022608,0.0218448,0.0537824 -lp: 0.0225866,0.0219468,0.0537945 -lp: 0.0225982,0.0220498,0.0537948 -lp: 0.0226084,0.0221529,0.0537957 -lp: 0.0226193,0.0222562,0.0537963 -lp: 0.0226292,0.0223596,0.0537974 -lp: 0.0226405,0.0224633,0.0537979 -lp: 0.0226208,0.0225665,0.0538094 -lp: 0.0226001,0.0226699,0.0538212 -lp: 0.0226071,0.0227741,0.0538233 -lp: 0.0226155,0.0228786,0.0538248 -lp: 0.0225621,0.0229818,0.0538482 -lp: 0.0225748,0.0230867,0.0538483 -lp: 0.0225865,0.0231918,0.0538487 -lp: 0.0225989,0.0232972,0.0538489 -lp: 0.0226093,0.0234026,0.0538498 -lp: 0.02262,0.0235083,0.0538506 -lp: 0.0226285,0.0236142,0.0538522 -lp: 0.0226088,0.0237196,0.0538638 -lp: 0.0225863,0.0238252,0.0538764 -lp: 0.0225988,0.0239318,0.0538766 -lp: 0.02261,0.0240386,0.0538773 -lp: 0.0226242,0.0241457,0.0538769 -lp: 0.0226057,0.0242522,0.0538881 -lp: 0.022582,0.0243588,0.0539012 -lp: 0.0225949,0.0244665,0.0539013 -lp: 0.0226078,0.0245744,0.0539014 -lp: 0.0226195,0.0246825,0.053902 -lp: 0.0226304,0.0247908,0.0539028 -lp: 0.0226391,0.0248993,0.0539045 -lp: 0.0226219,0.0250074,0.0539153 -lp: 0.0225977,0.0251156,0.0539286 -lp: 0.022609,0.0252249,0.0539293 -lp: 0.0226194,0.0253343,0.0539304 -lp: 0.0226348,0.0254441,0.0539298 -lp: 0.0225833,0.0255526,0.0539527 -lp: 0.022595,0.0256628,0.0539534 -lp: 0.0226064,0.0257732,0.0539542 -lp: 0.0226201,0.0258839,0.0539541 -lp: 0.0226315,0.0259949,0.0539549 -lp: 0.0226442,0.0261061,0.0539553 -lp: 0.0225912,0.0262159,0.0539788 -lp: 0.0226029,0.0263276,0.0539795 -lp: 0.022611,0.0264394,0.0539816 -lp: 0.0225879,0.0265507,0.0539946 -lp: 0.0225721,0.0266624,0.054005 -lp: 0.0225877,0.0267752,0.0540044 -lp: 0.0226007,0.0268882,0.0540047 -lp: 0.0226125,0.0270014,0.0540055 -lp: 0.0226234,0.0271148,0.0540066 -lp: 0.0226041,0.0272277,0.0540183 -lp: 0.0226132,0.0273417,0.0540201 -lp: 0.0225949,0.0274551,0.0540315 -lp: 0.0226067,0.0275697,0.0540323 -lp: 0.0226199,0.0276845,0.0540326 -lp: 0.022598,0.0277987,0.0540454 -lp: 0.0225835,0.0279133,0.0540555 -lp: 0.0225956,0.028029,0.0540563 -lp: 0.0226109,0.028145,0.0540559 -lp: 0.0226236,0.0282612,0.0540565 -lp: 0.0226372,0.0283777,0.0540567 -lp: 0.0225823,0.0284926,0.0540812 -lp: 0.0225963,0.0286097,0.0540813 -lp: 0.0226068,0.028727,0.0540827 -lp: 0.0225853,0.0288437,0.0540954 -lp: 0.0225718,0.0289609,0.0541053 -lp: 0.0225883,0.0290792,0.0541046 -lp: 0.0226002,0.0291977,0.0541055 -lp: 0.0226137,0.0293166,0.0541059 -lp: 0.0226289,0.0294357,0.0541057 -lp: 0.0226475,0.0295553,0.0541043 -lp: 0.0226604,0.0296751,0.054105 -lp: 0.0226077,0.0297933,0.0541288 -lp: 0.0226175,0.0299135,0.0541306 -lp: 0.0226323,0.0300342,0.0541306 -lp: 0.0225786,0.0301533,0.0541548 -lp: 0.0225922,0.0302746,0.0541553 -lp: 0.0226034,0.0303962,0.0541566 -lp: 0.0226179,0.0305181,0.0541568 -lp: 0.0225651,0.0306385,0.0541807 -lp: 0.0225817,0.0307612,0.0541802 -lp: 0.0225965,0.0308841,0.0541803 -lp: 0.0226134,0.0310075,0.0541797 -lp: 0.022558,0.0311291,0.0542046 -lp: 0.0225752,0.0312531,0.0542039 -lp: 0.0225905,0.0313774,0.0542039 -lp: 0.0226064,0.031502,0.0542037 -lp: 0.0226209,0.031627,0.0542041 -lp: 0.0226026,0.0317513,0.0542159 -lp: 0.0225788,0.0318759,0.0542298 -lp: 0.0225969,0.032002,0.0542289 -lp: 0.0226102,0.0321283,0.0542297 -lp: 0.0225579,0.032253,0.0542536 -lp: 0.0225724,0.0323801,0.054254 -lp: 0.0225894,0.0325076,0.0542536 -lp: 0.0226041,0.0326354,0.0542539 -lp: 0.0225896,0.0327627,0.0542646 -lp: 0.0225672,0.0328901,0.0542781 -lp: 0.0225872,0.0330191,0.0542766 -lp: 0.0225987,0.0331483,0.0542782 -lp: 0.0225795,0.0332769,0.0542906 -lp: 0.0225643,0.0334061,0.0543016 -lp: 0.0225807,0.0335365,0.0543015 -lp: 0.0225963,0.0336673,0.0543017 -lp: 0.0226135,0.0337986,0.0543013 -lp: 0.0225995,0.0339293,0.0543119 -lp: 0.0225827,0.0340603,0.0543236 -lp: 0.0225976,0.0341927,0.0543241 -lp: 0.0226162,0.0343256,0.0543233 -lp: 0.0225622,0.0344566,0.0543481 -lp: 0.0225804,0.0345903,0.0543475 -lp: 0.0225984,0.0347244,0.0543469 -lp: 0.022619,0.034859,0.0543455 -lp: 0.0225965,0.0349926,0.0543593 -lp: 0.0226145,0.035128,0.0543588 -lp: 0.0225947,0.0352625,0.0543717 -lp: 0.0226159,0.0353988,0.0543701 -lp: 0.0226002,0.0355343,0.0543816 -lp: 0.0225805,0.0356702,0.0543945 -lp: 0.022601,0.0358078,0.0543932 -lp: 0.0226247,0.0359459,0.0543908 -lp: 0.0226423,0.0360842,0.0543906 -lp: 0.022656,0.0362229,0.0543918 -lp: 0.0225967,0.0363597,0.0544188 -lp: 0.0226159,0.0364994,0.0544181 -lp: 0.0225961,0.0366384,0.0544311 -lp: 0.0225877,0.0367781,0.0544402 -lp: 0.0226058,0.0369192,0.0544399 -lp: 0.0226234,0.0370608,0.0544399 -lp: 0.0226434,0.0372029,0.054439 -lp: 0.0226671,0.0373456,0.0544368 -lp: 0.0226488,0.0374874,0.0544495 -lp: 0.0226331,0.0376298,0.0544612 -lp: 0.0226534,0.0377738,0.0544603 -lp: 0.0226777,0.0379185,0.054458 -lp: 0.022667,0.0380625,0.0544681 -lp: 0.0226883,0.0382081,0.0544669 -lp: 0.0227137,0.0383543,0.0544643 -lp: 0.0227437,0.0385013,0.05446 -lp: 0.0230088,0.0386577,0.0543729 -lp: 0.0230397,0.0388058,0.0543684 -lp: 0.0229096,0.0389481,0.0544207 -lp: 0.0229343,0.039097,0.0544185 -lp: 0.022432,-0.0184242,0.0525047 -lp: 0.0224225,-0.0183313,0.0525113 -lp: 0.0224141,-0.0182385,0.0525175 -lp: 0.0224062,-0.0181459,0.0525236 -lp: 0.0224019,-0.0180534,0.0525284 -lp: 0.0223971,-0.0179611,0.0525334 -lp: 0.0224166,-0.0178694,0.0525303 -lp: 0.0224099,-0.0177772,0.052536 -lp: 0.0224063,-0.0176853,0.0525406 -lp: 0.0224005,-0.0175934,0.0525459 -lp: 0.022397,-0.0175016,0.0525505 -lp: 0.0224072,-0.0174103,0.0525505 -lp: 0.0224037,-0.0173188,0.052555 -lp: 0.0223982,-0.0172274,0.0525602 -lp: 0.0223965,-0.0171361,0.0525642 -lp: 0.0223918,-0.0170449,0.0525691 -lp: 0.0223891,-0.0169538,0.0525734 -lp: 0.0224143,-0.0168635,0.0525683 -lp: 0.0224399,-0.0167733,0.0525632 -lp: 0.0224348,-0.0166825,0.0525682 -lp: 0.0224337,-0.0165919,0.052572 -lp: 0.0224517,-0.0165018,0.0525693 -lp: 0.0224498,-0.0164114,0.0525733 -lp: 0.0224443,-0.016321,0.0525785 -lp: 0.0224383,-0.0162307,0.0525838 -lp: 0.0224311,-0.0161404,0.0525895 -lp: 0.0224265,-0.0160504,0.0525944 -lp: 0.0224248,-0.0159605,0.0525983 -lp: 0.0224212,-0.0158706,0.0526028 -lp: 0.0224143,-0.0157808,0.0526084 -lp: 0.0224111,-0.0156912,0.0526128 -lp: 0.0224249,-0.015602,0.0526115 -lp: 0.0224206,-0.0155125,0.0526163 -lp: 0.0224138,-0.0154231,0.0526218 -lp: 0.0224098,-0.0153338,0.0526265 -lp: 0.0224367,-0.0152452,0.0526208 -lp: 0.0224359,-0.0151562,0.0526244 -lp: 0.0224316,-0.0150672,0.0526291 -lp: 0.0224593,-0.0149789,0.0526232 -lp: 0.0224562,-0.0148901,0.0526275 -lp: 0.0224723,-0.0148018,0.0526254 -lp: 0.0224657,-0.0147131,0.0526309 -lp: 0.0224398,-0.0146241,0.0526427 -lp: 0.0224324,-0.0145356,0.0526485 -lp: 0.0224223,-0.0144471,0.0526551 -lp: 0.0224142,-0.0143588,0.0526611 -lp: 0.0224089,-0.0142705,0.0526661 -lp: 0.0224102,-0.0141825,0.0526689 -lp: 0.022443,-0.0140952,0.0526613 -lp: 0.0224786,-0.0140079,0.0526527 -lp: 0.022474,-0.0139201,0.0526575 -lp: 0.0225041,-0.0138329,0.0526507 -lp: 0.0224984,-0.0137452,0.0526558 -lp: 0.0224874,-0.0136574,0.0526627 -lp: 0.02248,-0.0135698,0.0526684 -lp: 0.0224762,-0.0134823,0.0526729 -lp: 0.022503,-0.0133955,0.0526672 -lp: 0.0225091,-0.0133084,0.0526684 -lp: 0.0225398,-0.0132217,0.0526614 -lp: 0.0225596,-0.013135,0.0526581 -lp: 0.0225571,-0.0130479,0.0526621 -lp: 0.022522,-0.0129604,0.052677 -lp: 0.0225205,-0.0128735,0.0526807 -lp: 0.0225515,-0.0127872,0.0526736 -lp: 0.02255,-0.0127005,0.0526773 -lp: 0.0225429,-0.0126137,0.0526829 -lp: 0.0225337,-0.012527,0.0526892 -lp: 0.0225285,-0.0124404,0.0526941 -lp: 0.022524,-0.0123539,0.0526988 -lp: 0.0225216,-0.0122675,0.0527028 -lp: 0.0225219,-0.0121812,0.0527059 -lp: 0.0225448,-0.0120953,0.0527014 -lp: 0.022515,-0.0120087,0.0527146 -lp: 0.0225425,-0.0119231,0.0527086 -lp: 0.022512,-0.0118366,0.0527219 -lp: 0.0225231,-0.0117508,0.0527214 -lp: 0.0225183,-0.0116648,0.0527262 -lp: 0.0225157,-0.011579,0.0527302 -lp: 0.0225143,-0.0114932,0.0527339 -lp: 0.0225363,-0.0114078,0.0527297 -lp: 0.0225341,-0.0113222,0.0527336 -lp: 0.0225302,-0.0112365,0.0527381 -lp: 0.0225278,-0.011151,0.0527421 -lp: 0.0225251,-0.0110655,0.0527461 -lp: 0.0225246,-0.0109801,0.0527494 -lp: 0.0225241,-0.0108948,0.0527528 -lp: 0.0225212,-0.0108095,0.0527569 -lp: 0.0225155,-0.0107242,0.0527619 -lp: 0.0225124,-0.010639,0.0527661 -lp: 0.0225089,-0.0105539,0.0527704 -lp: 0.0225339,-0.0104692,0.0527653 -lp: 0.0225645,-0.0103846,0.0527582 -lp: 0.0225598,-0.0102996,0.0527629 -lp: 0.0225504,-0.0102147,0.0527692 -lp: 0.0225456,-0.0101298,0.0527739 -lp: 0.0225473,-0.010045,0.0527765 -lp: 0.0225428,-0.00996028,0.0527811 -lp: 0.022535,-0.00987554,0.0527869 -lp: 0.0225313,-0.00979089,0.0527912 -lp: 0.0225382,-0.00970644,0.0527921 -lp: 0.0225724,-0.00962237,0.0527838 -lp: 0.0225306,-0.00953741,0.0528008 -lp: 0.0225534,-0.0094533,0.0527964 -lp: 0.0225227,-0.00936858,0.0528097 -lp: 0.0225134,-0.00928418,0.0528159 -lp: 0.0224823,-0.00919958,0.0528294 -lp: 0.022474,-0.0091153,0.0528353 -lp: 0.0224719,-0.00903113,0.0528391 -lp: 0.0224699,-0.00894702,0.0528429 -lp: 0.0224664,-0.00886293,0.0528471 -lp: 0.0224971,-0.00877927,0.0528401 -lp: 0.0224952,-0.00869529,0.0528438 -lp: 0.0224988,-0.00861142,0.0528457 -lp: 0.0225235,-0.00852781,0.0528406 -lp: 0.0225216,-0.00844396,0.0528443 -lp: 0.0225183,-0.00836014,0.0528485 -lp: 0.0225137,-0.00827635,0.0528532 -lp: 0.0225118,-0.00819263,0.0528569 -lp: 0.0225319,-0.00810918,0.0528533 -lp: 0.0225329,-0.00802557,0.0528561 -lp: 0.0225334,-0.00794199,0.052859 -lp: 0.0225307,-0.00785843,0.052863 -lp: 0.0225265,-0.00777488,0.0528674 -lp: 0.0225236,-0.0076914,0.0528715 -lp: 0.0225223,-0.00760796,0.052875 -lp: 0.0225242,-0.00752459,0.0528775 -lp: 0.0225258,-0.00744126,0.05288 -lp: 0.0225238,-0.00735793,0.0528838 -lp: 0.0225212,-0.00727463,0.0528877 -lp: 0.0225182,-0.00719136,0.0528918 -lp: 0.0225423,-0.00710837,0.0528869 -lp: 0.0225398,-0.00702518,0.0528908 -lp: 0.0225377,-0.00694202,0.0528946 -lp: 0.0225359,-0.0068589,0.0528982 -lp: 0.0225356,-0.00677583,0.0529014 -lp: 0.0225353,-0.00669279,0.0529046 -lp: 0.0225335,-0.00660977,0.0529082 -lp: 0.0225316,-0.00652678,0.0529119 -lp: 0.0225308,-0.00644382,0.0529153 -lp: 0.0225321,-0.00636092,0.0529179 -lp: 0.0225301,-0.00627802,0.0529217 -lp: 0.0225263,-0.00619514,0.052926 -lp: 0.0225237,-0.00611229,0.0529299 -lp: 0.0225218,-0.00602948,0.0529336 -lp: 0.0225215,-0.00594671,0.0529368 -lp: 0.0225217,-0.00586397,0.0529398 -lp: 0.0225521,-0.00578147,0.0529327 -lp: 0.02255,-0.00569876,0.0529365 -lp: 0.022548,-0.00561608,0.0529402 -lp: 0.0225162,-0.00553323,0.0529538 -lp: 0.0225143,-0.0054506,0.0529575 -lp: 0.0225446,-0.00536821,0.0529505 -lp: 0.0225446,-0.00528564,0.0529536 -lp: 0.0225437,-0.00520309,0.0529569 -lp: 0.0225437,-0.00512057,0.05296 -lp: 0.0225435,-0.00503807,0.0529631 -lp: 0.022544,-0.00495559,0.052966 -lp: 0.0225425,-0.00487312,0.0529695 -lp: 0.0225688,-0.00479084,0.0529638 -lp: 0.0225675,-0.00470841,0.0529673 -lp: 0.0225692,-0.00462602,0.0529698 -lp: 0.0225699,-0.00454364,0.0529726 -lp: 0.0225702,-0.00446128,0.0529756 -lp: 0.0225717,-0.00437895,0.0529781 -lp: 0.0226066,-0.0042968,0.0529696 -lp: 0.0226088,-0.0042145,0.0529719 -lp: 0.0226484,-0.00413239,0.0529618 -lp: 0.0226138,-0.00404994,0.0529763 -lp: 0.0226099,-0.00396766,0.0529807 -lp: 0.022603,-0.00388538,0.052986 -lp: 0.0225982,-0.00380312,0.0529906 -lp: 0.0225953,-0.00372089,0.0529946 -lp: 0.0225951,-0.00363868,0.0529977 -lp: 0.0225937,-0.00355648,0.0530012 -lp: 0.0225969,-0.00347431,0.0530032 -lp: 0.0225977,-0.00339215,0.053006 -lp: 0.0225966,-0.00330999,0.0530094 -lp: 0.0225895,-0.00322782,0.0530148 -lp: 0.0225631,-0.00314559,0.0530266 -lp: 0.0225866,-0.00306355,0.0530218 -lp: 0.0225889,-0.00298144,0.0530241 -lp: 0.0225929,-0.00289935,0.0530258 -lp: 0.0225994,-0.00281727,0.0530267 -lp: 0.0226646,-0.00273538,0.0530081 -lp: 0.0226643,-0.00265329,0.0530112 -lp: 0.0226021,-0.00257104,0.0530349 -lp: 0.0225886,-0.00248893,0.0530424 -lp: 0.0225615,-0.0024068,0.0530545 -lp: 0.0225951,-0.00232483,0.0530463 -lp: 0.0226365,-0.00224288,0.0530356 -lp: 0.0226789,-0.00216093,0.0530246 -lp: 0.0226804,-0.00207888,0.0530271 -lp: 0.0226764,-0.00199683,0.0530315 -lp: 0.0226129,-0.00191466,0.0530556 -lp: 0.022605,-0.00183262,0.0530613 -lp: 0.0226361,-0.00175064,0.053054 -lp: 0.0226445,-0.00166862,0.0530542 -lp: 0.0226756,-0.00158664,0.0530469 -lp: 0.0226791,-0.00150461,0.0530488 -lp: 0.0226773,-0.00142257,0.0530524 -lp: 0.0226732,-0.00134053,0.0530568 -lp: 0.0226699,-0.0012585,0.053061 -lp: 0.0226735,-0.00117647,0.0530628 -lp: 0.0226742,-0.00109443,0.0530656 -lp: 0.0226736,-0.0010124,0.0530689 -lp: 0.0226715,-0.000930354,0.0530726 -lp: 0.0226734,-0.000848312,0.053075 -lp: 0.0226762,-0.000766266,0.0530771 -lp: 0.0226811,-0.000684216,0.0530785 -lp: 0.0226819,-0.000602161,0.0530813 -lp: 0.0226765,-0.000520099,0.0530861 -lp: 0.0226116,-0.00043804,0.0531107 -lp: 0.0226082,-0.000355976,0.0531149 -lp: 0.0226074,-0.000273905,0.0531182 -lp: 0.022607,-0.000191828,0.0531214 -lp: 0.0226013,-0.000109746,0.0531263 -lp: 0.0226008,-2.76547e-05,0.0531295 -lp: 0.0226062,5.44498e-05,0.0531307 -lp: 0.0226086,0.000136562,0.053133 -lp: 0.0226109,0.000218684,0.0531352 -lp: 0.0226117,0.000300814,0.053138 -lp: 0.022614,0.000382957,0.0531403 -lp: 0.0226259,0.000465124,0.0531394 -lp: 0.0226542,0.000547328,0.053133 -lp: 0.022618,0.000629451,0.0531481 -lp: 0.0225824,0.00071158,0.053163 -lp: 0.0225858,0.000793782,0.0531649 -lp: 0.0225854,0.000875991,0.0531681 -lp: 0.0226206,0.000958283,0.0531594 -lp: 0.0225967,0.00104047,0.0531704 -lp: 0.0225975,0.00112273,0.0531731 -lp: 0.0225981,0.001205,0.053176 -lp: 0.0225985,0.00128729,0.0531789 -lp: 0.0225998,0.00136959,0.0531815 -lp: 0.0225989,0.00145191,0.0531849 -lp: 0.0225968,0.00153424,0.0531886 -lp: 0.0225967,0.00161659,0.0531917 -lp: 0.0225981,0.00169896,0.0531943 -lp: 0.0226004,0.00178136,0.0531966 -lp: 0.0226014,0.00186377,0.0531993 -lp: 0.0226045,0.00194621,0.0532013 -lp: 0.022608,0.00202867,0.0532032 -lp: 0.0226091,0.00211115,0.0532059 -lp: 0.0226085,0.00219364,0.0532091 -lp: 0.0226108,0.00227616,0.0532114 -lp: 0.0226153,0.00235871,0.053213 -lp: 0.0226182,0.00244128,0.0532151 -lp: 0.0226193,0.00252387,0.0532178 -lp: 0.0226187,0.00260648,0.053221 -lp: 0.0226197,0.00268911,0.0532238 -lp: 0.02257,0.00277155,0.0532433 -lp: 0.022573,0.00285424,0.0532454 -lp: 0.0225755,0.00293695,0.0532476 -lp: 0.0225783,0.00301969,0.0532498 -lp: 0.0225801,0.00310246,0.0532522 -lp: 0.0225795,0.00318524,0.0532555 -lp: 0.0225804,0.00326805,0.0532582 -lp: 0.0225831,0.00335091,0.0532604 -lp: 0.0225844,0.00343378,0.053263 -lp: 0.0225864,0.00351669,0.0532654 -lp: 0.0225893,0.00359963,0.0532676 -lp: 0.0225919,0.0036826,0.0532698 -lp: 0.0225947,0.00376561,0.0532719 -lp: 0.0225958,0.00384864,0.0532746 -lp: 0.022597,0.0039317,0.0532773 -lp: 0.0226001,0.0040148,0.0532793 -lp: 0.0226036,0.00409794,0.0532813 -lp: 0.0226077,0.00418112,0.0532829 -lp: 0.0226113,0.00426433,0.0532848 -lp: 0.0226127,0.00434756,0.0532875 -lp: 0.022616,0.00443084,0.0532894 -lp: 0.0226209,0.00451416,0.0532909 -lp: 0.0226247,0.00459752,0.0532927 -lp: 0.0226274,0.0046809,0.0532949 -lp: 0.0226288,0.00476432,0.0532975 -lp: 0.0226302,0.00484777,0.0533001 -lp: 0.022633,0.00493127,0.0533023 -lp: 0.0226366,0.00501481,0.0533042 -lp: 0.0226393,0.00509839,0.0533064 -lp: 0.0226419,0.00518201,0.0533086 -lp: 0.0226447,0.00526567,0.0533108 -lp: 0.0226483,0.00534938,0.0533127 -lp: 0.0226494,0.00543311,0.0533154 -lp: 0.0226309,0.00551673,0.0533247 -lp: 0.0226364,0.00560058,0.053326 -lp: 0.022641,0.00568446,0.0533275 -lp: 0.0226837,0.00576871,0.0533165 -lp: 0.0227192,0.00585295,0.0533078 -lp: 0.0226914,0.0059367,0.0533201 -lp: 0.0226556,0.00602042,0.0533351 -lp: 0.0226538,0.00610448,0.0533388 -lp: 0.0226614,0.00618867,0.0533394 -lp: 0.0226691,0.0062729,0.05334 -lp: 0.0226727,0.00635715,0.0533419 -lp: 0.022678,0.00644146,0.0533433 -lp: 0.0226857,0.00652584,0.0533438 -lp: 0.022689,0.00661024,0.0533459 -lp: 0.0226871,0.00669463,0.0533496 -lp: 0.0226829,0.00677905,0.0533541 -lp: 0.0226592,0.00686333,0.0533651 -lp: 0.022663,0.00694793,0.053367 -lp: 0.0226706,0.00703262,0.0533676 -lp: 0.0226745,0.00711732,0.0533694 -lp: 0.0226775,0.00720207,0.0533716 -lp: 0.0226829,0.0072869,0.0533729 -lp: 0.0226859,0.00737176,0.0533751 -lp: 0.0226641,0.00745641,0.0533855 -lp: 0.0226582,0.00754128,0.0533906 -lp: 0.0226941,0.00762666,0.0533818 -lp: 0.0227033,0.00771181,0.0533819 -lp: 0.0226836,0.0077967,0.0533916 -lp: 0.0226846,0.00788188,0.0533944 -lp: 0.0226868,0.00796712,0.0533968 -lp: 0.0226874,0.00805241,0.0533998 -lp: 0.0226932,0.00813782,0.053401 -lp: 0.0227015,0.00822332,0.0534014 -lp: 0.0227083,0.00830886,0.0534023 -lp: 0.0227235,0.0085658,0.0534068 -lp: 0.0226938,0.00865115,0.0534198 -lp: 0.022656,0.00873645,0.0534355 -lp: 0.0226573,0.0088223,0.0534382 -lp: 0.0226646,0.00890829,0.053439 -lp: 0.0226729,0.00899436,0.0534394 -lp: 0.0226783,0.00908045,0.0534408 -lp: 0.022676,0.00916652,0.0534448 -lp: 0.0226533,0.00925239,0.0534555 -lp: 0.0226572,0.00933867,0.0534574 -lp: 0.022663,0.00942504,0.0534587 -lp: 0.0226709,0.00951151,0.0534593 -lp: 0.0226788,0.00959805,0.0534598 -lp: 0.0227091,0.00968497,0.053453 -lp: 0.0227152,0.00977164,0.0534541 -lp: 0.0227197,0.00985835,0.0534559 -lp: 0.0226735,0.00994444,0.0534744 -lp: 0.0226749,0.0100312,0.0534771 -lp: 0.0226798,0.0101182,0.0534787 -lp: 0.0226785,0.0102051,0.0534824 -lp: 0.0226831,0.0102922,0.0534841 -lp: 0.0226592,0.0104661,0.0534984 -lp: 0.0226173,0.0105527,0.0535156 -lp: 0.0226222,0.0106401,0.0535172 -lp: 0.0226269,0.0107276,0.0535189 -lp: 0.0226042,0.0108147,0.0535296 -lp: 0.0226411,0.0109028,0.0535206 -lp: 0.022648,0.0109905,0.0535216 -lp: 0.0226543,0.0110784,0.0535228 -lp: 0.0226285,0.0111658,0.0535346 -lp: 0.0226329,0.0112537,0.0535364 -lp: 0.0226085,0.0113413,0.0535477 -lp: 0.0226123,0.0114294,0.0535497 -lp: 0.0226186,0.0115176,0.0535509 -lp: 0.022623,0.0116059,0.0535527 -lp: 0.0226285,0.0116942,0.0535541 -lp: 0.0226327,0.0117827,0.053556 -lp: 0.022639,0.0118712,0.0535572 -lp: 0.02262,0.0119595,0.0535668 -lp: 0.0226242,0.0120482,0.0535686 -lp: 0.0226275,0.012137,0.0535709 -lp: 0.022633,0.0122259,0.0535723 -lp: 0.022639,0.0123149,0.0535736 -lp: 0.0226471,0.012404,0.0535742 -lp: 0.0226296,0.0124928,0.0535833 -lp: 0.0226339,0.0125821,0.0535852 -lp: 0.0226353,0.0126714,0.053588 -lp: 0.0226412,0.0127608,0.0535894 -lp: 0.022646,0.0128504,0.0535911 -lp: 0.0226523,0.0129401,0.0535923 -lp: 0.0226572,0.0130298,0.053594 -lp: 0.0226327,0.0131191,0.0536054 -lp: 0.0226078,0.0132085,0.053617 -lp: 0.0226132,0.0132985,0.0536186 -lp: 0.0226173,0.0133887,0.0536205 -lp: 0.0226247,0.0134789,0.0536214 -lp: 0.0226306,0.0135693,0.0536228 -lp: 0.0226375,0.0136597,0.0536239 -lp: 0.0226408,0.0137503,0.0536261 -lp: 0.0226456,0.0138409,0.0536279 -lp: 0.0226037,0.0139308,0.0536451 -lp: 0.0226099,0.0140216,0.0536464 -lp: 0.0226141,0.0141126,0.0536484 -lp: 0.0226218,0.0142037,0.0536492 -lp: 0.0226267,0.0142948,0.053651 -lp: 0.0226327,0.0143861,0.0536523 -lp: 0.0226066,0.0144769,0.0536644 -lp: 0.0226142,0.0145684,0.0536653 -lp: 0.0226198,0.01466,0.0536668 -lp: 0.0226254,0.0147518,0.0536683 -lp: 0.0226333,0.0148436,0.0536691 -lp: 0.0226425,0.0149357,0.0536694 -lp: 0.0226507,0.0150278,0.0536701 -lp: 0.0226233,0.0151193,0.0536826 -lp: 0.0226272,0.0152115,0.0536847 -lp: 0.0226359,0.015304,0.0536853 -lp: 0.0226779,0.0153973,0.0536748 -lp: 0.0226921,0.0154901,0.0536735 -lp: 0.0226799,0.0155825,0.0536809 -lp: 0.0226895,0.0156755,0.0536812 -lp: 0.0226964,0.0157685,0.0536823 -lp: 0.0227411,0.0158625,0.053671 -lp: 0.0227469,0.0159557,0.0536725 -lp: 0.0227245,0.0160485,0.0536834 -lp: 0.0225811,0.020382,0.0538914 -lp: 0.0225282,0.0204805,0.0539126 -lp: 0.0225714,0.0205816,0.053902 -lp: 0.0225865,0.0206822,0.0539007 -lp: 0.0226033,0.020783,0.0538989 -lp: 0.0226482,0.0208848,0.0538877 -lp: 0.0225975,0.0209841,0.0539083 -lp: 0.0226075,0.0210853,0.0539087 -lp: 0.0226141,0.0211865,0.0539102 -lp: 0.0226234,0.021288,0.0539109 -lp: 0.0226306,0.0213897,0.0539123 -lp: 0.0226087,0.0214907,0.0539233 -lp: 0.0225914,0.0215919,0.0539328 -lp: 0.0226014,0.0216942,0.0539332 -lp: 0.0226106,0.0217966,0.0539339 -lp: 0.0226212,0.0218992,0.0539342 -lp: 0.0226312,0.022002,0.0539347 -lp: 0.0226431,0.0221051,0.0539346 -lp: 0.022653,0.0222082,0.0539351 -lp: 0.0226623,0.0223116,0.0539358 -lp: 0.022608,0.0224133,0.0539577 -lp: 0.0226193,0.0225171,0.0539577 -lp: 0.0226258,0.0226209,0.0539594 -lp: 0.0226012,0.022724,0.0539714 -lp: 0.022582,0.0228275,0.0539816 -lp: 0.0225939,0.0229321,0.0539816 -lp: 0.0226044,0.0230368,0.0539819 -lp: 0.0226143,0.0231417,0.0539825 -lp: 0.0226238,0.0232469,0.0539832 -lp: 0.0226067,0.0233514,0.0539928 -lp: 0.0226155,0.0234569,0.0539938 -lp: 0.0225925,0.0235616,0.0540053 -lp: 0.0226015,0.0236676,0.0540062 -lp: 0.0226145,0.0237738,0.0540059 -lp: 0.0226238,0.0238802,0.0540067 -lp: 0.0225702,0.0239848,0.0540284 -lp: 0.0225796,0.0240916,0.0540292 -lp: 0.0225946,0.0241987,0.0540282 -lp: 0.0226061,0.024306,0.0540283 -lp: 0.0226156,0.0244134,0.0540292 -lp: 0.0226247,0.0245211,0.0540301 -lp: 0.0226357,0.024629,0.0540304 -lp: 0.0225868,0.0247353,0.0540506 -lp: 0.0225981,0.0248436,0.0540509 -lp: 0.0226062,0.0249521,0.0540522 -lp: 0.0226186,0.025061,0.0540521 -lp: 0.0225942,0.0251689,0.0540642 -lp: 0.0226075,0.0252782,0.0540639 -lp: 0.0225892,0.0253868,0.0540739 -lp: 0.0226013,0.0254966,0.054074 -lp: 0.0226114,0.0256065,0.0540747 -lp: 0.0226227,0.0257167,0.054075 -lp: 0.0225684,0.025825,0.0540971 -lp: 0.0225792,0.0259357,0.0540976 -lp: 0.0225909,0.0260467,0.0540978 -lp: 0.0226015,0.0261578,0.0540984 -lp: 0.0225771,0.0262681,0.0541106 -lp: 0.0225599,0.0263788,0.0541204 -lp: 0.0225716,0.0264907,0.0541206 -lp: 0.0225854,0.026603,0.0541202 -lp: 0.0225957,0.0267153,0.054121 -lp: 0.0226065,0.026828,0.0541215 -lp: 0.0225567,0.0269388,0.0541422 -lp: 0.0225702,0.0270521,0.0541419 -lp: 0.0225818,0.0271656,0.0541422 -lp: 0.0225977,0.0272794,0.0541412 -lp: 0.0226076,0.0273933,0.0541421 -lp: 0.0225838,0.0275063,0.0541542 -lp: 0.0225654,0.0276198,0.0541645 -lp: 0.0225799,0.0277347,0.0541639 -lp: 0.0225925,0.0278498,0.054164 -lp: 0.0226065,0.0279652,0.0541636 -lp: 0.0226193,0.0280808,0.0541637 -lp: 0.0225694,0.0281945,0.0541845 -lp: 0.0225815,0.0283106,0.0541847 -lp: 0.0225961,0.0284272,0.0541842 -lp: 0.0225673,0.0285424,0.054198 -lp: 0.0225491,0.0286583,0.0542084 -lp: 0.0225646,0.0287757,0.0542076 -lp: 0.0225826,0.0288935,0.0542059 -lp: 0.0225981,0.0290115,0.0542051 -lp: 0.0226064,0.0291295,0.0542068 -lp: 0.0225865,0.0292468,0.0542177 -lp: 0.0225708,0.0293645,0.0542273 -lp: 0.0225819,0.0294835,0.054228 -lp: 0.0225955,0.0296029,0.0542279 -lp: 0.0225709,0.0297212,0.0542404 -lp: 0.0225551,0.0298401,0.0542501 -lp: 0.022569,0.0299604,0.0542499 -lp: 0.0225869,0.0300812,0.0542485 -lp: 0.0226006,0.0302021,0.0542484 -lp: 0.0226113,0.0303232,0.0542493 -lp: 0.0225562,0.0304422,0.054272 -lp: 0.0225728,0.0305642,0.054271 -lp: 0.0225868,0.0306864,0.0542709 -lp: 0.0226039,0.030809,0.0542697 -lp: 0.0225494,0.0309292,0.0542923 -lp: 0.0225651,0.0310525,0.0542917 -lp: 0.0225781,0.0311759,0.0542919 -lp: 0.0225943,0.0312999,0.0542911 -lp: 0.0225733,0.0314227,0.0543026 -lp: 0.0225894,0.0315473,0.0543019 -lp: 0.0225681,0.0316707,0.0543136 -lp: 0.0225846,0.031796,0.0543127 -lp: 0.0225654,0.0319202,0.0543237 -lp: 0.022544,0.0320447,0.0543354 -lp: 0.0225612,0.0321711,0.0543343 -lp: 0.0225826,0.032298,0.0543319 -lp: 0.0225976,0.0324249,0.0543317 -lp: 0.0226095,0.0325522,0.0543324 -lp: 0.0225532,0.0326769,0.0543557 -lp: 0.0225708,0.0328051,0.0543546 -lp: 0.0225867,0.0329336,0.0543541 -lp: 0.0225657,0.0330609,0.0543658 -lp: 0.0225825,0.0331901,0.054365 -lp: 0.0225701,0.0333185,0.0543739 -lp: 0.0225862,0.0334485,0.0543733 -lp: 0.0226058,0.033579,0.0543716 -lp: 0.0226203,0.0337096,0.0543717 -lp: 0.0225999,0.0338392,0.0543832 -lp: 0.0225766,0.033969,0.0543958 -lp: 0.0225524,0.0340992,0.0544086 -lp: 0.0225355,0.0342301,0.0544191 -lp: 0.0225548,0.0343629,0.0544176 -lp: 0.0225732,0.0344961,0.0544164 -lp: 0.0225947,0.0346298,0.0544142 -lp: 0.0226132,0.0347637,0.054413 -lp: 0.022595,0.0348966,0.054424 -lp: 0.0225737,0.0350296,0.054436 -lp: 0.0225932,0.0351649,0.0544345 -lp: 0.0226096,0.0353005,0.0544341 -lp: 0.0225588,0.0354335,0.0544559 -lp: 0.0225754,0.0355699,0.0544554 -lp: 0.0225944,0.0357068,0.0544542 -lp: 0.0226116,0.0358441,0.0544536 -lp: 0.0226298,0.0359819,0.0544526 -lp: 0.0225722,0.0361167,0.0544767 -lp: 0.0225898,0.0362554,0.054476 -lp: 0.0226091,0.0363945,0.0544747 -lp: 0.0226324,0.0365343,0.0544722 -lp: 0.0225761,0.0366709,0.0544959 -lp: 0.0225922,0.0368113,0.0544958 -lp: 0.0226095,0.0369522,0.0544952 -lp: 0.0226339,0.0370938,0.0544924 -lp: 0.0226143,0.0372339,0.0545041 -lp: 0.0225981,0.0373747,0.0545147 -lp: 0.0226138,0.0375174,0.0545147 -lp: 0.0226364,0.0376608,0.0545125 -lp: 0.0226202,0.037803,0.0545232 -lp: 0.0226072,0.0379458,0.0545328 -lp: 0.0226306,0.0380908,0.0545304 -lp: 0.0226983,0.0382384,0.0545133 -lp: 0.0227237,0.0383845,0.0545103 -lp: 0.0226552,0.0385266,0.0545383 -lp: 0.0226386,0.0386716,0.0545492 -lp: 0.0228572,0.0388288,0.0544824 -lp: 0.0227958,0.0389726,0.0545081 -lp: 0.0228146,0.039121,0.0545074 -lp: 0.022693,0.0392629,0.054553 -lp: 0.022715,0.0394124,0.0545512 -lp: 0.0221071,-0.0237626,0.0701727 -lp: 0.0220967,-0.0236417,0.0701759 -lp: 0.0220891,-0.023521,0.0701782 -lp: 0.0220825,-0.0234005,0.0701802 -lp: 0.0221154,-0.0232799,0.0701692 -lp: 0.0221087,-0.0231597,0.0701712 -lp: 0.022107,-0.0230396,0.0701715 -lp: 0.0221371,-0.0229195,0.0701614 -lp: 0.0221349,-0.0227997,0.070162 -lp: 0.0221294,-0.0226802,0.0701636 -lp: 0.0221248,-0.0225608,0.0701649 -lp: 0.0221171,-0.0224416,0.0701672 -lp: 0.0221393,-0.0223223,0.0701597 -lp: 0.0221337,-0.0222034,0.0701613 -lp: 0.0221275,-0.0220846,0.0701632 -lp: 0.022121,-0.021966,0.0701651 -lp: 0.0221161,-0.0218476,0.0701665 -lp: 0.0221108,-0.0217293,0.0701681 -lp: 0.0221076,-0.0216111,0.0701689 -lp: 0.0221027,-0.0214931,0.0701703 -lp: 0.0221005,-0.0213752,0.0701708 -lp: 0.0221332,-0.0212573,0.0701599 -lp: 0.0221281,-0.0211397,0.0701614 -lp: 0.0221431,-0.0210222,0.0701563 -lp: 0.022136,-0.020905,0.0701584 -lp: 0.0221291,-0.0207879,0.0701604 -lp: 0.0221276,-0.0206708,0.0701608 -lp: 0.0221218,-0.020554,0.0701625 -lp: 0.0221205,-0.0204373,0.0701627 -lp: 0.0221155,-0.0203207,0.0701641 -lp: 0.0221745,-0.0202039,0.0701446 -lp: 0.0221694,-0.0200877,0.070146 -lp: 0.0221648,-0.0199715,0.0701473 -lp: 0.0221581,-0.0198555,0.0701494 -lp: 0.022154,-0.0197396,0.0701505 -lp: 0.0221485,-0.0196239,0.0701521 -lp: 0.0221451,-0.0195083,0.070153 -lp: 0.0221409,-0.0193928,0.0701542 -lp: 0.022138,-0.0192775,0.070155 -lp: 0.0221329,-0.0191622,0.0701565 -lp: 0.022129,-0.0190472,0.0701576 -lp: 0.0221246,-0.0189322,0.0701588 -lp: 0.0221562,-0.0188172,0.0701482 -lp: 0.0221513,-0.0187025,0.0701496 -lp: 0.0221498,-0.0185879,0.0701499 -lp: 0.0221464,-0.0184734,0.0701509 -lp: 0.0221417,-0.0183591,0.0701522 -lp: 0.0221349,-0.0182449,0.0701542 -lp: 0.0221534,-0.0181306,0.070148 -lp: 0.0221486,-0.0180167,0.0701494 -lp: 0.0221458,-0.0179028,0.0701501 -lp: 0.0221398,-0.0177891,0.0701519 -lp: 0.0221355,-0.0176755,0.0701531 -lp: 0.022158,-0.0175618,0.0701455 -lp: 0.022157,-0.0174484,0.0701456 -lp: 0.0221534,-0.0173352,0.0701466 -lp: 0.0221857,-0.0172218,0.0701358 -lp: 0.0221798,-0.0171088,0.0701376 -lp: 0.022177,-0.0169959,0.0701383 -lp: 0.0221738,-0.016883,0.0701392 -lp: 0.022172,-0.0167703,0.0701396 -lp: 0.0221689,-0.0166577,0.0701404 -lp: 0.0221658,-0.0165452,0.0701412 -lp: 0.0221613,-0.0164328,0.0701425 -lp: 0.0221576,-0.0163206,0.0701435 -lp: 0.0221535,-0.0162084,0.0701447 -lp: 0.0221498,-0.0160963,0.0701457 -lp: 0.0221826,-0.0159842,0.0701347 -lp: 0.0221806,-0.0158723,0.0701352 -lp: 0.0221758,-0.0157606,0.0701366 -lp: 0.0221725,-0.0156489,0.0701375 -lp: 0.0221681,-0.0155374,0.0701388 -lp: 0.0221676,-0.0154259,0.0701387 -lp: 0.0221648,-0.0153145,0.0701395 -lp: 0.0221863,-0.0152032,0.0701322 -lp: 0.022181,-0.015092,0.0701338 -lp: 0.0221768,-0.0149809,0.0701349 -lp: 0.0221718,-0.01487,0.0701364 -lp: 0.0221949,-0.014759,0.0701286 -lp: 0.0221916,-0.0146482,0.0701295 -lp: 0.0221918,-0.0145375,0.0701293 -lp: 0.0221899,-0.0144269,0.0701297 -lp: 0.0221906,-0.0143164,0.0701293 -lp: 0.0221873,-0.014206,0.0701302 -lp: 0.0221848,-0.0140957,0.0701308 -lp: 0.0221803,-0.0139854,0.0701321 -lp: 0.0222112,-0.0138752,0.0701218 -lp: 0.0222067,-0.0137651,0.0701231 -lp: 0.0222043,-0.0136551,0.0701236 -lp: 0.022203,-0.0135452,0.0701239 -lp: 0.0222012,-0.0134354,0.0701243 -lp: 0.0221975,-0.0133257,0.0701253 -lp: 0.0221942,-0.0132161,0.0701262 -lp: 0.0221896,-0.0131066,0.0701276 -lp: 0.0222254,-0.012997,0.0701156 -lp: 0.0222252,-0.0128876,0.0701155 -lp: 0.0222255,-0.0127783,0.0701152 -lp: 0.0222217,-0.012669,0.0701163 -lp: 0.022221,-0.0125599,0.0701163 -lp: 0.0222177,-0.0124508,0.0701172 -lp: 0.0222135,-0.0123419,0.0701184 -lp: 0.0222097,-0.0122329,0.0701195 -lp: 0.0222062,-0.0121241,0.0701204 -lp: 0.0222267,-0.0120153,0.0701135 -lp: 0.0222254,-0.0119066,0.0701138 -lp: 0.0222211,-0.011798,0.070115 -lp: 0.0222219,-0.0116894,0.0701145 -lp: 0.0222196,-0.011581,0.0701151 -lp: 0.0222424,-0.0114725,0.0701074 -lp: 0.0222397,-0.0113642,0.0701081 -lp: 0.0222367,-0.0112559,0.070109 -lp: 0.0222334,-0.0111478,0.0701098 -lp: 0.0222309,-0.0110396,0.0701105 -lp: 0.022227,-0.0109316,0.0701116 -lp: 0.0222333,-0.0108236,0.0701093 -lp: 0.0222353,-0.0107157,0.0701085 -lp: 0.0222715,-0.0106077,0.0700964 -lp: 0.0222704,-0.0104999,0.0700966 -lp: 0.0222704,-0.0103922,0.0700964 -lp: 0.0222938,-0.0102845,0.0700886 -lp: 0.022264,-0.010177,0.0700981 -lp: 0.0222598,-0.0100695,0.0700994 -lp: 0.022284,-0.00996192,0.0700912 -lp: 0.0222546,-0.0098546,0.0701007 -lp: 0.0222814,-0.00974718,0.0700917 -lp: 0.0222808,-0.00963989,0.0700917 -lp: 0.0222826,-0.00953265,0.0700909 -lp: 0.0222896,-0.00942546,0.0700884 -lp: 0.0222845,-0.00931836,0.07009 -lp: 0.0222788,-0.00921132,0.0700917 -lp: 0.0222704,-0.00910434,0.0700942 -lp: 0.0222677,-0.00899741,0.0700949 -lp: 0.0222685,-0.00889051,0.0700945 -lp: 0.0222751,-0.00878366,0.0700921 -lp: 0.022311,-0.00867678,0.0700802 -lp: 0.0223027,-0.00857007,0.0700827 -lp: 0.0223006,-0.0084634,0.0700832 -lp: 0.0222975,-0.00835678,0.0700841 -lp: 0.0223019,-0.00825019,0.0700824 -lp: 0.0223346,-0.00814359,0.0700715 -lp: 0.0223331,-0.00803712,0.0700718 -lp: 0.0223306,-0.00793069,0.0700725 -lp: 0.0223272,-0.00782432,0.0700734 -lp: 0.022324,-0.007718,0.0700743 -lp: 0.0223207,-0.00761172,0.0700752 -lp: 0.0223154,-0.00750549,0.0700767 -lp: 0.0223127,-0.0073993,0.0700774 -lp: 0.0223096,-0.00729315,0.0700783 -lp: 0.022313,-0.00718704,0.070077 -lp: 0.0223176,-0.00708096,0.0700753 -lp: 0.0223234,-0.00697493,0.0700732 -lp: 0.0223527,-0.00686889,0.0700634 -lp: 0.0223479,-0.00676296,0.0700648 -lp: 0.0223449,-0.00665707,0.0700656 -lp: 0.0223421,-0.00655122,0.0700663 -lp: 0.0223403,-0.0064454,0.0700668 -lp: 0.02234,-0.00633963,0.0700667 -lp: 0.0223389,-0.00623389,0.0700668 -lp: 0.0223093,-0.00612824,0.0700764 -lp: 0.0223359,-0.00602252,0.0700675 -lp: 0.0223334,-0.00591689,0.0700681 -lp: 0.0223304,-0.0058113,0.0700689 -lp: 0.0223191,-0.00570576,0.0700725 -lp: 0.0223243,-0.00560022,0.0700706 -lp: 0.0223149,-0.00549474,0.0700735 -lp: 0.0223131,-0.00538928,0.0700739 -lp: 0.0222739,-0.00528392,0.0700866 -lp: 0.0222705,-0.00517853,0.0700875 -lp: 0.0222679,-0.00507316,0.0700882 -lp: 0.0222655,-0.00496783,0.0700888 -lp: 0.0222627,-0.00486252,0.0700896 -lp: 0.0222965,-0.00475719,0.0700783 -lp: 0.0222738,-0.00465197,0.0700856 -lp: 0.0222742,-0.00454675,0.0700852 -lp: 0.0222982,-0.00444151,0.0700772 -lp: 0.0222974,-0.00433634,0.0700773 -lp: 0.0222959,-0.0042312,0.0700776 -lp: 0.0222944,-0.00412608,0.0700779 -lp: 0.0223038,-0.00402097,0.0700746 -lp: 0.0223373,-0.00391585,0.0700634 -lp: 0.0223376,-0.0038108,0.0700632 -lp: 0.0223355,-0.00370578,0.0700637 -lp: 0.0223345,-0.00360078,0.0700638 -lp: 0.0223336,-0.0034958,0.0700639 -lp: 0.0223336,-0.00339084,0.0700638 -lp: 0.0223347,-0.00328589,0.0700632 -lp: 0.0223345,-0.00318097,0.0700631 -lp: 0.0223334,-0.00307607,0.0700633 -lp: 0.0223322,-0.00297118,0.0700635 -lp: 0.0223307,-0.00286632,0.0700638 -lp: 0.0223297,-0.00276147,0.070064 -lp: 0.0223287,-0.00265663,0.0700641 -lp: 0.0223278,-0.00255181,0.0700643 -lp: 0.0223278,-0.00244701,0.0700641 -lp: 0.0223274,-0.00234222,0.070064 -lp: 0.0223271,-0.00223744,0.0700639 -lp: 0.022327,-0.00213268,0.0700638 -lp: 0.0223271,-0.00202793,0.0700636 -lp: 0.0223295,-0.00192318,0.0700626 -lp: 0.0223316,-0.00181845,0.0700618 -lp: 0.0223336,-0.00171373,0.0700609 -lp: 0.0223337,-0.00160903,0.0700607 -lp: 0.0223342,-0.00150433,0.0700604 -lp: 0.0223338,-0.00139964,0.0700603 -lp: 0.0223559,-0.00129494,0.0700529 -lp: 0.0223568,-0.00119026,0.0700524 -lp: 0.0223574,-0.0010856,0.070052 -lp: 0.0223358,-0.000980952,0.0700589 -lp: 0.0223397,-0.000876294,0.0700575 -lp: 0.0223239,-0.000771654,0.0700625 -lp: 0.0223681,-0.000666978,0.0700478 -lp: 0.0223693,-0.000562336,0.0700472 -lp: 0.0223742,-0.000457694,0.0700455 -lp: 0.0223702,-0.000353061,0.0700466 -lp: 0.0224086,-0.000248405,0.0700338 -lp: 0.0224092,-0.000143772,0.0700334 -lp: 0.0224065,-3.91422e-05,0.0700341 -lp: 0.0223701,6.54709e-05,0.0700459 -lp: 0.0223344,0.000170087,0.0700575 -lp: 0.0223352,0.000274722,0.070057 -lp: 0.022366,0.000379372,0.0700467 -lp: 0.0224047,0.000484027,0.0700338 -lp: 0.0224135,0.000588671,0.0700308 -lp: 0.0224151,0.000693316,0.0700301 -lp: 0.0224199,0.000797967,0.0700283 -lp: 0.0224192,0.00090262,0.0700283 -lp: 0.0224191,0.00100728,0.0700282 -lp: 0.0224154,0.00111194,0.0700293 -lp: 0.022414,0.00121662,0.0700295 -lp: 0.0224181,0.0013213,0.070028 -lp: 0.0224213,0.00142598,0.0700268 -lp: 0.0224195,0.00153068,0.0700272 -lp: 0.0224143,0.00163539,0.0700287 -lp: 0.0224129,0.0017401,0.070029 -lp: 0.0223407,0.00184482,0.0700525 -lp: 0.0223415,0.00194956,0.0700521 -lp: 0.0224157,0.00205432,0.0700276 -lp: 0.0224217,0.00215908,0.0700254 -lp: 0.0224326,0.00226385,0.0700216 -lp: 0.0224016,0.00415276,0.0700286 -lp: 0.022401,0.0042579,0.0700287 -lp: 0.0223701,0.00436308,0.0700386 -lp: 0.0223567,0.00446829,0.0700428 -lp: 0.0223373,0.00457352,0.070049 -lp: 0.0223754,0.00467875,0.0700364 -lp: 0.0223811,0.00478403,0.0700343 -lp: 0.0223843,0.00488933,0.0700331 -lp: 0.0223873,0.00499467,0.0700319 -lp: 0.0223885,0.00510003,0.0700313 -lp: 0.0223881,0.00520543,0.0700313 -lp: 0.0223891,0.00531086,0.0700308 -lp: 0.0223891,0.00541632,0.0700306 -lp: 0.0223903,0.00552181,0.07003 -lp: 0.0223899,0.00562734,0.07003 -lp: 0.022391,0.0057329,0.0700294 -lp: 0.0223914,0.0058385,0.0700291 -lp: 0.0223932,0.00594413,0.0700284 -lp: 0.0223934,0.0060498,0.0700281 -lp: 0.0223948,0.0061555,0.0700275 -lp: 0.0223975,0.00626124,0.0700264 -lp: 0.0223998,0.00636702,0.0700255 -lp: 0.0224005,0.00647283,0.0700251 -lp: 0.0223633,0.00657872,0.0700371 -lp: 0.0223666,0.00668462,0.0700359 -lp: 0.0224072,0.00679052,0.0700223 -lp: 0.0224128,0.00689649,0.0700203 -lp: 0.0224159,0.00700251,0.0700191 -lp: 0.0224179,0.00710857,0.0700183 -lp: 0.0223794,0.00721472,0.0700307 -lp: 0.0223796,0.00732087,0.0700305 -lp: 0.022382,0.00742706,0.0700295 -lp: 0.0223855,0.0075333,0.0700282 -lp: 0.0223889,0.00763958,0.0700269 -lp: 0.0223918,0.00774591,0.0700257 -lp: 0.0223923,0.00785229,0.0700254 -lp: 0.0223943,0.00795872,0.0700246 -lp: 0.0223975,0.00806519,0.0700233 -lp: 0.0224008,0.00817172,0.0700221 -lp: 0.0224037,0.00827829,0.070021 -lp: 0.0224058,0.00838491,0.0700201 -lp: 0.0224083,0.00849159,0.0700191 -lp: 0.0224106,0.00859832,0.0700181 -lp: 0.0224127,0.0087051,0.0700173 -lp: 0.0224145,0.00881193,0.0700165 -lp: 0.0224171,0.00891882,0.0700155 -lp: 0.0224187,0.00902576,0.0700148 -lp: 0.0224237,0.00913276,0.0700129 -lp: 0.0224318,0.0092398,0.0700101 -lp: 0.0224344,0.00934691,0.0700091 -lp: 0.0224383,0.00945408,0.0700076 -lp: 0.0224808,0.00956125,0.0699934 -lp: 0.0224515,0.00966858,0.0700029 -lp: 0.0224904,0.00977587,0.0699899 -lp: 0.0224614,0.00988332,0.0699993 -lp: 0.0224657,0.00999078,0.0699977 -lp: 0.0224717,0.0100983,0.0699955 -lp: 0.0224751,0.0102059,0.0699942 -lp: 0.0224818,0.0103135,0.0699918 -lp: 0.0224852,0.0104213,0.0699905 -lp: 0.0225231,0.010529,0.0699779 -lp: 0.0225316,0.0106368,0.0699749 -lp: 0.0225349,0.0107447,0.0699736 -lp: 0.0224996,0.0108528,0.0699851 -lp: 0.0224993,0.0109608,0.069985 -lp: 0.0224654,0.011069,0.0699959 -lp: 0.0224597,0.0111772,0.0699976 -lp: 0.0224652,0.0112854,0.0699956 -lp: 0.0224529,0.0141272,0.0699949 -lp: 0.0224044,0.0142377,0.0700106 -lp: 0.022417,0.0143482,0.0700063 -lp: 0.0224613,0.0144587,0.0699915 -lp: 0.022426,0.0145695,0.070003 -lp: 0.0224582,0.0146802,0.0699922 -lp: 0.0224629,0.0147911,0.0699904 -lp: 0.0224668,0.0149021,0.069989 -lp: 0.0224722,0.0150132,0.069987 -lp: 0.0224141,0.0151245,0.0700059 -lp: 0.0224186,0.0152358,0.0700043 -lp: 0.0224207,0.0153471,0.0700034 -lp: 0.0224241,0.0154586,0.0700021 -lp: 0.0224234,0.0155702,0.0700021 -lp: 0.0224265,0.0156819,0.0700009 -lp: 0.0224277,0.0157936,0.0700003 -lp: 0.0224327,0.0159055,0.0699985 -lp: 0.0223986,0.0160176,0.0700095 -lp: 0.0224037,0.0161297,0.0700076 -lp: 0.0224101,0.0162419,0.0700053 -lp: 0.0224171,0.0163542,0.0700029 -lp: 0.0224238,0.0164666,0.0700005 -lp: 0.0224296,0.0165791,0.0699984 -lp: 0.0224358,0.0166917,0.0699961 -lp: 0.0224424,0.0168044,0.0699938 -lp: 0.0224481,0.0169173,0.0699917 -lp: 0.0224216,0.0170303,0.0700002 -lp: 0.0224243,0.0171434,0.0699992 -lp: 0.0224293,0.0172565,0.0699973 -lp: 0.0224339,0.0173698,0.0699956 -lp: 0.0224402,0.0174832,0.0699933 -lp: 0.0224455,0.0175968,0.0699914 -lp: 0.0224514,0.0177104,0.0699893 -lp: 0.0224545,0.0178242,0.0699881 -lp: 0.0224573,0.0179381,0.0699869 -lp: 0.0224632,0.0180521,0.0699848 -lp: 0.0224701,0.0181662,0.0699824 -lp: 0.0224775,0.0182804,0.0699797 -lp: 0.0224537,0.0183949,0.0699874 -lp: 0.0224579,0.0185093,0.0699858 -lp: 0.0224621,0.018624,0.0699842 -lp: 0.0224255,0.0187388,0.069996 -lp: 0.0224304,0.0188537,0.0699942 -lp: 0.0224351,0.0189687,0.0699925 -lp: 0.0224448,0.0190838,0.0699891 -lp: 0.0224517,0.019199,0.0699866 -lp: 0.0224974,0.0193143,0.0699715 -lp: 0.0225106,0.0194298,0.0699669 -lp: 0.0225144,0.0195454,0.0699655 -lp: 0.0224135,0.0240495,0.069991 -lp: 0.0223867,0.0241713,0.0699996 -lp: 0.0223887,0.0242931,0.0699987 -lp: 0.0223915,0.0244151,0.0699976 -lp: 0.0223994,0.0245373,0.0699948 -lp: 0.022407,0.0246596,0.0699921 -lp: 0.0224178,0.0247822,0.0699883 -lp: 0.022427,0.0249049,0.0699851 -lp: 0.0224345,0.0250278,0.0699824 -lp: 0.0224414,0.0251509,0.06998 -lp: 0.0224162,0.0252743,0.069988 -lp: 0.0224276,0.0253977,0.0699841 -lp: 0.0224382,0.0255213,0.0699804 -lp: 0.0224472,0.0256452,0.0699772 -lp: 0.0224475,0.0257692,0.0699769 -lp: 0.0224186,0.0258936,0.0699862 -lp: 0.0224292,0.026018,0.0699825 -lp: 0.0224368,0.0261427,0.0699798 -lp: 0.0224453,0.0262675,0.0699768 -lp: 0.0224098,0.0263927,0.0699882 -lp: 0.0224184,0.0265179,0.0699852 -lp: 0.0224255,0.0266433,0.0699826 -lp: 0.0224344,0.0267689,0.0699795 -lp: 0.0224413,0.0268947,0.069977 -lp: 0.0224083,0.027021,0.0699877 -lp: 0.0224159,0.0271472,0.0699849 -lp: 0.0224257,0.0272736,0.0699815 -lp: 0.0224353,0.0274003,0.0699781 -lp: 0.0224113,0.0275273,0.0699858 -lp: 0.0224198,0.0276544,0.0699828 -lp: 0.0224276,0.0277817,0.06998 -lp: 0.0224351,0.0279092,0.0699773 -lp: 0.0224442,0.0280369,0.0699741 -lp: 0.0224529,0.0281649,0.069971 -lp: 0.0224631,0.028293,0.0699675 -lp: 0.0224374,0.0284216,0.0699757 -lp: 0.0224064,0.0285504,0.0699857 -lp: 0.0224098,0.0286792,0.0699844 -lp: 0.0224179,0.0288083,0.0699815 -lp: 0.0224275,0.0289376,0.0699781 -lp: 0.0224378,0.0290671,0.0699745 -lp: 0.0224018,0.0291971,0.0699861 -lp: 0.0224097,0.0293271,0.0699833 -lp: 0.0224198,0.0294573,0.0699797 -lp: 0.0224317,0.0295877,0.0699756 -lp: 0.0224061,0.0297186,0.0699838 -lp: 0.0224154,0.0298495,0.0699805 -lp: 0.0224248,0.0299807,0.0699772 -lp: 0.0224349,0.0301121,0.0699737 -lp: 0.0224437,0.0302438,0.0699706 -lp: 0.0224538,0.0303757,0.069967 -lp: 0.0224257,0.030508,0.069976 -lp: 0.0224348,0.0306404,0.0699728 -lp: 0.0224043,0.0307733,0.0699826 -lp: 0.0224159,0.0309062,0.0699786 -lp: 0.0224227,0.0310394,0.0699761 -lp: 0.0223863,0.031173,0.0699878 -lp: 0.0223942,0.0313067,0.069985 -lp: 0.0224031,0.0314407,0.0699819 -lp: 0.0223812,0.031575,0.0699888 -lp: 0.0223937,0.0317095,0.0699845 -lp: 0.022406,0.0318442,0.0699802 -lp: 0.0224165,0.0319792,0.0699766 -lp: 0.0224261,0.0321145,0.0699732 -lp: 0.0224385,0.03225,0.0699689 -lp: 0.0224477,0.0323858,0.0699656 -lp: 0.0224569,0.0325219,0.0699623 -lp: 0.022428,0.0326585,0.0699716 -lp: 0.0223983,0.0327954,0.0699812 -lp: 0.0224028,0.0329323,0.0699794 -lp: 0.0223687,0.0330698,0.0699904 -lp: 0.0223798,0.0332073,0.0699865 -lp: 0.0223932,0.033345,0.0699819 -lp: 0.0224067,0.0334831,0.0699772 -lp: 0.0224197,0.0336214,0.0699727 -lp: 0.0223971,0.0337602,0.0699799 -lp: 0.022408,0.0338992,0.0699761 -lp: 0.0224164,0.0340384,0.0699731 -lp: 0.0224261,0.034178,0.0699697 -lp: 0.0224321,0.0343179,0.0699675 -lp: 0.0224427,0.034458,0.0699637 -lp: 0.0223762,0.0345989,0.0699853 -lp: 0.0223871,0.0347397,0.0699815 -lp: 0.0223982,0.0348807,0.0699776 -lp: 0.02241,0.0350221,0.0699735 -lp: 0.0223753,0.0351641,0.0699847 -lp: 0.0223863,0.0353061,0.0699808 -lp: 0.0223999,0.0354484,0.0699761 -lp: 0.0224157,0.035591,0.0699707 -lp: 0.0223915,0.0357342,0.0699784 -lp: 0.0224021,0.0358775,0.0699747 -lp: 0.0224145,0.0360211,0.0699704 -lp: 0.022431,0.036165,0.0699647 -lp: 0.0224452,0.0363093,0.0699598 -lp: 0.0224568,0.0364539,0.0699557 -lp: 0.0224269,0.0365991,0.0699653 -lp: 0.022401,0.0367447,0.0699736 -lp: 0.0224083,0.0368903,0.0699709 -lp: 0.0224182,0.0370363,0.0699674 -lp: 0.0223826,0.037183,0.0699789 -lp: 0.0223976,0.0373296,0.0699737 -lp: 0.0224114,0.0374766,0.0699689 -lp: 0.0223902,0.0376242,0.0699756 -lp: 0.0224016,0.037772,0.0699716 -lp: 0.0224103,0.0379201,0.0699685 -lp: 0.0224199,0.0380686,0.0699651 -lp: 0.0224315,0.0382174,0.069961 -lp: 0.022446,0.0383666,0.069956 -lp: 0.0224639,0.0385161,0.0699499 -lp: 0.0223967,0.0386666,0.0699717 -lp: 0.0224088,0.0388169,0.0699675 -lp: 0.0224198,0.0389676,0.0699636 -lp: 0.0224335,0.0391187,0.0699589 -lp: 0.0224008,0.0392704,0.0699693 -lp: 0.0224162,0.0394222,0.069964 -lp: 0.0224303,0.0395745,0.0699591 -lp: 0.022448,0.0397271,0.0699531 -lp: 0.0224268,0.0398803,0.0699598 -lp: 0.0224396,0.0400337,0.0699553 -lp: 0.0224504,0.0401875,0.0699515 -lp: 0.0224601,0.0403418,0.0699481 -lp: 0.0223902,0.040497,0.0699707 -lp: 0.0224088,0.040652,0.0699644 -lp: 0.022421,0.0408074,0.0699601 -lp: 0.0224321,0.0409633,0.0699562 -lp: 0.0223576,0.0411202,0.0699804 -lp: 0.0224114,0.0412766,0.0699625 -lp: 0.0223875,0.041434,0.06997 -lp: 0.0224046,0.0415915,0.0699641 -lp: 0.0224209,0.0417495,0.0699585 -lp: 0.0224338,0.041908,0.069954 -lp: 0.0224495,0.0420668,0.0699486 -lp: 0.0224648,0.0422261,0.0699433 -lp: 0.0224418,0.0423861,0.0699506 -lp: 0.0224119,0.0425466,0.0699601 -lp: 0.022424,0.0427073,0.0699559 -lp: 0.0224392,0.0428684,0.0699506 -lp: 0.0224034,0.0430303,0.0699621 -lp: 0.0223851,0.0431926,0.0699678 -lp: 0.0224006,0.043355,0.0699625 -lp: 0.0224168,0.043518,0.0699569 -lp: 0.022436,0.0436814,0.0699503 -lp: 0.0224523,0.0438453,0.0699446 -lp: 0.0224695,0.0440097,0.0699387 -lp: 0.0224808,0.0441746,0.0699347 -lp: 0.0224997,0.0443399,0.0699282 -lp: 0.0224753,0.0445061,0.069936 -lp: 0.0224472,0.0446727,0.0699449 -lp: 0.0224644,0.0448395,0.069939 -lp: 0.0224771,0.0450069,0.0699345 -lp: 0.0224436,0.0451751,0.0699453 -lp: 0.0224191,0.0453437,0.069953 -lp: 0.0224363,0.0455126,0.0699471 -lp: 0.0224526,0.045682,0.0699415 -lp: 0.0224696,0.0458519,0.0699356 -lp: 0.0224836,0.0460224,0.0699307 -lp: 0.0224619,0.0461936,0.0699375 -lp: 0.0225239,0.0463649,0.0699169 -lp: 0.0225471,0.0465369,0.0699089 -lp: 0.0225182,0.0467098,0.0699182 -lp: 0.0224941,0.0468832,0.0699258 -lp: 0.0225089,0.0470569,0.0699206 -lp: 0.0225283,0.0472312,0.0699139 -lp: 0.0224587,0.0474066,0.0699365 -lp: 0.022474,0.047582,0.0699312 -lp: 0.0224883,0.0477579,0.0699262 -lp: 0.0225019,0.0479345,0.0699214 -lp: 0.0224267,0.0481123,0.0699458 -lp: 0.0224489,0.0482899,0.0699382 -lp: 0.0224685,0.0484682,0.0699315 -lp: 0.0225355,0.0486467,0.0699092 -lp: 0.0225149,0.0488264,0.0699157 -lp: 0.0225398,0.0490065,0.0699072 -lp: 0.022565,0.0491871,0.0698986 -lp: 0.0225856,0.0493684,0.0698915 -lp: 0.0225489,0.0495507,0.0699032 -lp: 0.0225159,0.0497336,0.0699138 -lp: 0.0223612,0.0499181,0.0699643 -lp: 0.0226258,0.0501001,0.0698771 -lp: 0.022424,0.0502861,0.069943 -lp: 0.0227943,0.0504691,0.0698211 -lp: 0.0225798,0.0506561,0.0698912 -lp: 0.0226082,0.0508424,0.0698816 -lp: 0.021743,-0.0308951,0.0930978 -lp: 0.021732,-0.0307368,0.0930965 -lp: 0.0217241,-0.0305786,0.0930941 -lp: 0.0217152,-0.0304207,0.093092 -lp: 0.0217098,-0.0302628,0.0930886 -lp: 0.0217442,-0.0301033,0.0930699 -lp: 0.0217778,-0.029944,0.0930515 -lp: 0.0217702,-0.029787,0.0930489 -lp: 0.0217634,-0.0296301,0.093046 -lp: 0.0217551,-0.0294735,0.0930438 -lp: 0.0217503,-0.029317,0.0930402 -lp: 0.0217461,-0.0291607,0.0930364 -lp: 0.0217431,-0.0290046,0.0930321 -lp: 0.0217347,-0.0288489,0.0930299 -lp: 0.0217299,-0.0286933,0.0930263 -lp: 0.0217718,-0.0285358,0.0930048 -lp: 0.0217696,-0.0283805,0.0930003 -lp: 0.0217631,-0.0282256,0.0929974 -lp: 0.0218048,-0.0280688,0.092976 -lp: 0.0217989,-0.0279143,0.0929729 -lp: 0.0217945,-0.0277599,0.0929692 -lp: 0.0217864,-0.027606,0.092967 -lp: 0.0217782,-0.0274522,0.0929647 -lp: 0.0217684,-0.0272987,0.0929632 -lp: 0.0217623,-0.0271453,0.0929602 -lp: 0.0217575,-0.026992,0.0929567 -lp: 0.0217535,-0.0268389,0.0929529 -lp: 0.0217922,-0.0266841,0.0929327 -lp: 0.0217873,-0.0265315,0.0929293 -lp: 0.021782,-0.026379,0.092926 -lp: 0.0218134,-0.0262252,0.0929087 -lp: 0.0218118,-0.026073,0.092904 -lp: 0.021803,-0.0259212,0.0929021 -lp: 0.0217926,-0.0257697,0.0929008 -lp: 0.021784,-0.0256184,0.0928988 -lp: 0.0217779,-0.0254671,0.0928959 -lp: 0.0217737,-0.0253159,0.0928923 -lp: 0.0217678,-0.025165,0.0928893 -lp: 0.0217629,-0.0250143,0.0928859 -lp: 0.0217565,-0.0248637,0.0928831 -lp: 0.0217526,-0.0247133,0.0928794 -lp: 0.0217954,-0.0245612,0.0928577 -lp: 0.0217947,-0.024411,0.0928528 -lp: 0.021789,-0.0242612,0.0928497 -lp: 0.0217856,-0.0241114,0.0928458 -lp: 0.021779,-0.023962,0.0928432 -lp: 0.0217712,-0.0238128,0.092841 -lp: 0.0218069,-0.0236621,0.0928221 -lp: 0.0218013,-0.0235131,0.092819 -lp: 0.021799,-0.0233642,0.0928148 -lp: 0.0217963,-0.0232155,0.0928106 -lp: 0.0217893,-0.0230671,0.0928081 -lp: 0.021787,-0.0229187,0.0928039 -lp: 0.0217828,-0.0227705,0.0928003 -lp: 0.0217812,-0.0226224,0.0927958 -lp: 0.0218153,-0.0224732,0.0927775 -lp: 0.0218133,-0.0223255,0.0927732 -lp: 0.0218089,-0.022178,0.0927697 -lp: 0.0218395,-0.0220294,0.0927529 -lp: 0.0218323,-0.0218823,0.0927505 -lp: 0.0218262,-0.0217354,0.0927477 -lp: 0.0218214,-0.0215885,0.0927445 -lp: 0.0218187,-0.0214418,0.0927404 -lp: 0.0218173,-0.0212951,0.0927359 -lp: 0.0218157,-0.0211486,0.0927314 -lp: 0.0218091,-0.0210025,0.0927288 -lp: 0.0218538,-0.0208547,0.0927066 -lp: 0.0218515,-0.0207087,0.0927024 -lp: 0.0218449,-0.020563,0.0926999 -lp: 0.0218363,-0.0204175,0.0926981 -lp: 0.0218287,-0.0202721,0.092696 -lp: 0.0218242,-0.0201267,0.0926926 -lp: 0.0218194,-0.0199815,0.0926894 -lp: 0.0218146,-0.0198365,0.0926862 -lp: 0.0218109,-0.0196915,0.0926826 -lp: 0.0218057,-0.0195467,0.0926796 -lp: 0.0218501,-0.0194006,0.0926575 -lp: 0.0218479,-0.019256,0.0926533 -lp: 0.0218475,-0.0191115,0.0926484 -lp: 0.0218437,-0.0189673,0.0926449 -lp: 0.0218403,-0.0188231,0.0926412 -lp: 0.0218348,-0.0186792,0.0926383 -lp: 0.0218288,-0.0185354,0.0926356 -lp: 0.0218251,-0.0183917,0.092632 -lp: 0.0218198,-0.0182481,0.092629 -lp: 0.0218522,-0.0181036,0.0926116 -lp: 0.0218483,-0.0179603,0.0926082 -lp: 0.0218434,-0.0178171,0.092605 -lp: 0.0218424,-0.0176739,0.0926004 -lp: 0.0218423,-0.0175309,0.0925955 -lp: 0.0218418,-0.017388,0.0925907 -lp: 0.0218391,-0.0172452,0.0925868 -lp: 0.021872,-0.0171016,0.0925693 -lp: 0.0218666,-0.0169592,0.0925664 -lp: 0.0218648,-0.0168168,0.0925621 -lp: 0.0218627,-0.0166746,0.092558 -lp: 0.0218606,-0.0165324,0.0925538 -lp: 0.0218563,-0.0163905,0.0925505 -lp: 0.0218512,-0.0162486,0.0925476 -lp: 0.0218457,-0.0161069,0.0925447 -lp: 0.0218395,-0.0159653,0.0925422 -lp: 0.0218343,-0.0158238,0.0925393 -lp: 0.0218813,-0.0156811,0.0925163 -lp: 0.0218848,-0.0155397,0.0925101 -lp: 0.0218873,-0.0153983,0.0925042 -lp: 0.0218832,-0.0152572,0.0925009 -lp: 0.0219249,-0.0151152,0.09248 -lp: 0.0219219,-0.0149743,0.0924762 -lp: 0.0219193,-0.0148335,0.0924724 -lp: 0.0219144,-0.0146929,0.0924693 -lp: 0.0219116,-0.0145523,0.0924655 -lp: 0.0219075,-0.0144119,0.0924622 -lp: 0.0219361,-0.0142708,0.0924464 -lp: 0.0219321,-0.0141306,0.092443 -lp: 0.0219279,-0.0139905,0.0924398 -lp: 0.0219252,-0.0138504,0.0924359 -lp: 0.0218904,-0.0137111,0.0924444 -lp: 0.0219192,-0.0135706,0.0924285 -lp: 0.021881,-0.0134316,0.0924383 -lp: 0.0219237,-0.0132909,0.0924171 -lp: 0.0219178,-0.0131514,0.0924145 -lp: 0.0219051,-0.0130121,0.0924145 -lp: 0.0219586,-0.0128716,0.0923892 -lp: 0.0219612,-0.0127322,0.0923833 -lp: 0.0219549,-0.0125931,0.0923809 -lp: 0.0219004,-0.012455,0.0923969 -lp: 0.0218975,-0.0123159,0.0923932 -lp: 0.0219347,-0.0121762,0.0923741 -lp: 0.0219329,-0.0120373,0.09237 -lp: 0.02193,-0.0118986,0.0923663 -lp: 0.0218807,-0.0117608,0.0923804 -lp: 0.0219198,-0.0116214,0.0923606 -lp: 0.021929,-0.0114826,0.0923522 -lp: 0.0219268,-0.0113442,0.0923483 -lp: 0.0219067,-0.0112062,0.0923511 -lp: 0.0218992,-0.011068,0.0923492 -lp: 0.0218603,-0.0109304,0.0923593 -lp: 0.0219019,-0.0107915,0.0923386 -lp: 0.0219089,-0.0106533,0.0923311 -lp: 0.02191,-0.0105153,0.0923259 -lp: 0.0219569,-0.0103766,0.0923031 -lp: 0.0220232,-0.0102376,0.0922729 -lp: 0.0220239,-0.0100999,0.0922679 -lp: 0.0220159,-0.00996232,0.0922662 -lp: 0.0220079,-0.00982484,0.0922645 -lp: 0.022001,-0.0096874,0.0922623 -lp: 0.0220009,-0.00954993,0.0922576 -lp: 0.0220022,-0.00941251,0.0922523 -lp: 0.022007,-0.00927511,0.0922457 -lp: 0.0220504,-0.00913722,0.0922243 -lp: 0.0220029,-0.00900071,0.0922377 -lp: 0.0219985,-0.00886365,0.0922347 -lp: 0.0219834,-0.0087268,0.0922357 -lp: 0.0219246,-0.0085906,0.0922534 -lp: 0.021967,-0.00845308,0.0922324 -lp: 0.0219706,-0.00831616,0.0922263 -lp: 0.0220218,-0.00817868,0.0922019 -lp: 0.0219687,-0.00804262,0.0922175 -lp: 0.0219683,-0.00790593,0.0922129 -lp: 0.0219649,-0.00776935,0.0922095 -lp: 0.0219965,-0.00763239,0.0921926 -lp: 0.0219937,-0.00749592,0.092189 -lp: 0.0219916,-0.00735949,0.092185 -lp: 0.0219902,-0.00722311,0.0921808 -lp: 0.021989,-0.00708679,0.0921765 -lp: 0.0219875,-0.00695052,0.0921724 -lp: 0.0219849,-0.00681432,0.0921687 -lp: 0.0219831,-0.00667816,0.0921646 -lp: 0.0219823,-0.00654205,0.0921602 -lp: 0.0219823,-0.00640597,0.0921554 -lp: 0.0219821,-0.00626995,0.0921508 -lp: 0.0219799,-0.006134,0.0921469 -lp: 0.0219811,-0.00599806,0.0921418 -lp: 0.0219818,-0.00586218,0.0921368 -lp: 0.0219795,-0.00572637,0.0921329 -lp: 0.0219759,-0.00559062,0.0921296 -lp: 0.0219731,-0.00545491,0.0921259 -lp: 0.0219711,-0.00531923,0.092122 -lp: 0.0219697,-0.0051836,0.0921178 -lp: 0.021968,-0.005048,0.0921138 -lp: 0.0219647,-0.00491246,0.0921103 -lp: 0.0219627,-0.00477696,0.0921064 -lp: 0.0220102,-0.00464111,0.0920835 -lp: 0.0219691,-0.00450598,0.0920945 -lp: 0.0219889,-0.00437044,0.0920822 -lp: 0.0219869,-0.00423509,0.0920783 -lp: 0.0220071,-0.00409963,0.0920658 -lp: 0.0220084,-0.00396434,0.0920607 -lp: 0.0220032,-0.00382912,0.092058 -lp: 0.0220028,-0.00369391,0.0920534 -lp: 0.021963,-0.00355897,0.0920639 -lp: 0.021995,-0.00342363,0.092047 -lp: 0.0219979,-0.0032885,0.0920412 -lp: 0.0220092,-0.00315336,0.0920321 -lp: 0.021996,-0.00301837,0.0920325 -lp: 0.0219901,-0.00288338,0.0920301 -lp: 0.0219839,-0.00274841,0.0920278 -lp: 0.0219937,-0.0026134,0.0920193 -lp: 0.0220416,-0.00247826,0.0919963 -lp: 0.0219919,-0.00234356,0.0920106 -lp: 0.0219785,-0.00220873,0.0920111 -lp: 0.0219724,-0.00207389,0.0920087 -lp: 0.0219813,-0.00193902,0.0920006 -lp: 0.0220423,-0.00180401,0.0919726 -lp: 0.0220909,-0.00166909,0.0919493 -lp: 0.0221079,-0.0015343,0.0919381 -lp: 0.0221074,-0.00139958,0.0919337 -lp: 0.0220986,-0.00126489,0.0919323 -lp: 0.0220389,-0.00113034,0.0919505 -lp: 0.0219802,-0.000995774,0.0919683 -lp: 0.0219782,-0.000861106,0.0919644 -lp: 0.0219912,-0.000726432,0.0919547 -lp: 0.0220777,-0.000591683,0.091917 -lp: 0.0220712,-0.000457088,0.0919148 -lp: 0.0220696,-0.000322501,0.0919107 -lp: 0.0220271,-0.000187955,0.0919223 -lp: 0.0220754,0.000484766,0.0918804 -lp: 0.022075,0.000619273,0.0918759 -lp: 0.0220324,0.000753804,0.0918875 -lp: 0.0220932,0.000888245,0.0918596 -lp: 0.022135,0.00102268,0.091839 -lp: 0.0220967,0.0011572,0.0918489 -lp: 0.0220931,0.00129167,0.0918457 -lp: 0.0220718,0.00142617,0.0918491 -lp: 0.0220172,0.00156075,0.0918653 -lp: 0.0220573,0.00169513,0.0918453 -lp: 0.0220175,0.00182969,0.0918559 -lp: 0.0220172,0.00196416,0.0918513 -lp: 0.0220217,0.00209862,0.0918449 -lp: 0.022024,0.00223309,0.0918394 -lp: 0.0220697,0.00236741,0.0918172 -lp: 0.0220256,0.00250202,0.0918294 -lp: 0.022028,0.00263649,0.0918238 -lp: 0.0220279,0.00277097,0.0918192 -lp: 0.022029,0.00290545,0.0918141 -lp: 0.0220289,0.00303994,0.0918094 -lp: 0.0220291,0.00317443,0.0918047 -lp: 0.0220743,0.00330872,0.0917827 -lp: 0.0220739,0.00344322,0.0917782 -lp: 0.0220734,0.00357773,0.0917737 -lp: 0.0220733,0.00371225,0.0917691 -lp: 0.0220741,0.00384677,0.0917642 -lp: 0.0220721,0.00398132,0.0917602 -lp: 0.0220276,0.00411613,0.0917726 -lp: 0.0220246,0.00425072,0.091769 -lp: 0.0220222,0.00438532,0.0917653 -lp: 0.022024,0.00451991,0.0917599 -lp: 0.0220283,0.00465449,0.0917536 -lp: 0.0220773,0.00478878,0.0917302 -lp: 0.0220786,0.00492341,0.091725 -lp: 0.0220781,0.00505806,0.0917205 -lp: 0.0220303,0.00519309,0.0917341 -lp: 0.022031,0.00532779,0.0917291 -lp: 0.022078,0.00546213,0.0917065 -lp: 0.0220802,0.00559684,0.091701 -lp: 0.0220811,0.00573159,0.091696 -lp: 0.0220841,0.00586633,0.0916901 -lp: 0.0220882,0.00600109,0.0916839 -lp: 0.0220899,0.00613589,0.0916785 -lp: 0.0220911,0.00627072,0.0916734 -lp: 0.0220917,0.00640558,0.0916685 -lp: 0.0220921,0.00654047,0.0916636 -lp: 0.0220927,0.00667538,0.0916587 -lp: 0.0220933,0.00681033,0.0916538 -lp: 0.0221039,0.00694519,0.0916451 -lp: 0.0221061,0.00708017,0.0916395 -lp: 0.0220524,0.00721577,0.0916554 -lp: 0.0220519,0.0115581,0.0915047 -lp: 0.0220416,0.0116948,0.0915039 -lp: 0.022043,0.0118313,0.0914986 -lp: 0.0220461,0.0119679,0.0914927 -lp: 0.022045,0.0121046,0.0914883 -lp: 0.0220472,0.0122413,0.0914827 -lp: 0.0220491,0.0123781,0.0914773 -lp: 0.0220535,0.0125149,0.0914708 -lp: 0.0221041,0.0126509,0.0914468 -lp: 0.0221078,0.0127878,0.0914406 -lp: 0.0221134,0.0129247,0.0914337 -lp: 0.0221173,0.0130618,0.0914275 -lp: 0.0221177,0.013199,0.0914225 -lp: 0.0220702,0.0133372,0.0914359 -lp: 0.022072,0.0134745,0.0914304 -lp: 0.0220802,0.0136117,0.0914225 -lp: 0.0220834,0.0137491,0.0914165 -lp: 0.0220843,0.0138867,0.0914114 -lp: 0.0220837,0.0140243,0.0914069 -lp: 0.0220836,0.014162,0.0914021 -lp: 0.0220848,0.0142997,0.0913969 -lp: 0.0220871,0.0144375,0.0913912 -lp: 0.0220914,0.0145754,0.0913848 -lp: 0.0220963,0.0147133,0.0913781 -lp: 0.0221004,0.0148513,0.0913718 -lp: 0.0221033,0.0149893,0.0913658 -lp: 0.0221045,0.0151275,0.0913606 -lp: 0.0221049,0.0152659,0.0913556 -lp: 0.0221086,0.0154042,0.0913494 -lp: 0.0220743,0.0155434,0.0913577 -lp: 0.0220783,0.0156819,0.0913513 -lp: 0.0221217,0.0158196,0.0913299 -lp: 0.0221238,0.0159582,0.0913243 -lp: 0.0221257,0.016097,0.0913188 -lp: 0.0221299,0.0162358,0.0913123 -lp: 0.0220969,0.0163756,0.0913201 -lp: 0.0221458,0.0165135,0.0912966 -lp: 0.0220976,0.0166539,0.0913102 -lp: 0.0221026,0.016793,0.0913034 -lp: 0.0221132,0.0169321,0.0912945 -lp: 0.0222249,0.0170688,0.0912471 -lp: 0.0221807,0.0172094,0.0912591 -lp: 0.0220724,0.021305,0.0911582 -lp: 0.0220721,0.0214479,0.0911534 -lp: 0.0220775,0.0215907,0.0911463 -lp: 0.0220788,0.0217338,0.0911409 -lp: 0.0220846,0.0218769,0.0911337 -lp: 0.0220952,0.0220199,0.0911246 -lp: 0.0220996,0.0221632,0.091118 -lp: 0.0220657,0.022308,0.0911259 -lp: 0.0220675,0.0224517,0.0911202 -lp: 0.0221104,0.0225942,0.0910989 -lp: 0.0221149,0.0227381,0.0910922 -lp: 0.0220789,0.0228835,0.0911009 -lp: 0.0220826,0.0230276,0.0910944 -lp: 0.0220843,0.023172,0.0910888 -lp: 0.0220908,0.0233164,0.0910813 -lp: 0.0220996,0.0234608,0.0910729 -lp: 0.022106,0.0236055,0.0910654 -lp: 0.0221069,0.0237505,0.09106 -lp: 0.0221076,0.0238956,0.0910548 -lp: 0.0221107,0.0240408,0.0910485 -lp: 0.0221126,0.0241862,0.0910427 -lp: 0.0220743,0.0243331,0.0910523 -lp: 0.0221212,0.0244772,0.0910293 -lp: 0.0221275,0.0246229,0.0910219 -lp: 0.0221334,0.0247687,0.0910145 -lp: 0.0220948,0.0249163,0.0910242 -lp: 0.0220979,0.0250626,0.0910179 -lp: 0.0221044,0.0252088,0.0910103 -lp: 0.0221112,0.0253552,0.0910027 -lp: 0.0220676,0.0255037,0.0910142 -lp: 0.0220703,0.0256506,0.091008 -lp: 0.0220751,0.0257976,0.0910011 -lp: 0.0220804,0.0259447,0.0909939 -lp: 0.0220863,0.0260919,0.0909866 -lp: 0.0220934,0.0262393,0.0909788 -lp: 0.022102,0.0263868,0.0909703 -lp: 0.0221067,0.0265345,0.0909634 -lp: 0.0221096,0.0266826,0.0909572 -lp: 0.0220605,0.0268328,0.0909707 -lp: 0.0220635,0.0269812,0.0909644 -lp: 0.0220674,0.0271297,0.0909578 -lp: 0.0220749,0.0272782,0.0909497 -lp: 0.0220425,0.0274285,0.0909569 -lp: 0.0220487,0.0275774,0.0909493 -lp: 0.0220561,0.0277265,0.0909413 -lp: 0.0220585,0.0278759,0.0909352 -lp: 0.022061,0.0280255,0.0909291 -lp: 0.0220662,0.0281752,0.0909219 -lp: 0.0220739,0.0283249,0.0909138 -lp: 0.0220859,0.0284747,0.090904 -lp: 0.0220929,0.0286248,0.0908961 -lp: 0.0220961,0.0287753,0.0908896 -lp: 0.0220984,0.028926,0.0908835 -lp: 0.0221044,0.0290768,0.0908759 -lp: 0.0221089,0.0292278,0.090869 -lp: 0.0221134,0.0293789,0.090862 -lp: 0.0221215,0.0295302,0.0908537 -lp: 0.0220869,0.0296834,0.0908616 -lp: 0.0220932,0.0298351,0.0908539 -lp: 0.0220942,0.0299872,0.0908482 -lp: 0.0220997,0.0301393,0.0908408 -lp: 0.0220604,0.0302937,0.0908505 -lp: 0.0220671,0.0304461,0.0908426 -lp: 0.0220745,0.0305988,0.0908345 -lp: 0.0220788,0.0307518,0.0908275 -lp: 0.0220849,0.0309049,0.0908199 -lp: 0.022088,0.0310583,0.0908134 -lp: 0.0220925,0.0312119,0.0908063 -lp: 0.0220477,0.031368,0.090818 -lp: 0.0220545,0.0315219,0.0908101 -lp: 0.0220634,0.0316759,0.0908013 -lp: 0.0220727,0.0318301,0.0907924 -lp: 0.0220799,0.0319847,0.0907843 -lp: 0.0220892,0.0321393,0.0907754 -lp: 0.0220529,0.0322963,0.0907838 -lp: 0.022058,0.0324516,0.0907764 -lp: 0.0220631,0.0326072,0.0907691 -lp: 0.0220699,0.0327628,0.0907611 -lp: 0.0220768,0.0329187,0.090753 -lp: 0.022082,0.0330749,0.0907456 -lp: 0.0220885,0.0332312,0.0907377 -lp: 0.022095,0.0333878,0.0907298 -lp: 0.0221001,0.0335446,0.0907224 -lp: 0.022107,0.0337017,0.0907143 -lp: 0.0221141,0.0338589,0.0907061 -lp: 0.0221221,0.0340163,0.0906976 -lp: 0.0221325,0.0341739,0.0906881 -lp: 0.0221447,0.0343316,0.090678 -lp: 0.0221087,0.0344919,0.0906862 -lp: 0.0220638,0.034653,0.0906977 -lp: 0.0220681,0.0348119,0.0906906 -lp: 0.0220782,0.0349707,0.0906812 -lp: 0.0220867,0.0351298,0.0906724 -lp: 0.0220953,0.0352891,0.0906636 -lp: 0.0221019,0.0354488,0.0906555 -lp: 0.0221091,0.0356088,0.0906472 -lp: 0.0221155,0.035769,0.0906392 -lp: 0.0221219,0.0359295,0.0906312 -lp: 0.0220313,0.0360954,0.0906601 -lp: 0.0220819,0.036254,0.0906352 -lp: 0.0220466,0.0364175,0.090643 -lp: 0.0220539,0.036579,0.0906346 -lp: 0.0220632,0.0367407,0.0906254 -lp: 0.0220758,0.0369024,0.090615 -lp: 0.022087,0.0370645,0.0906051 -lp: 0.0220938,0.0372271,0.0905968 -lp: 0.0220981,0.0373901,0.0905895 -lp: 0.0221039,0.0375533,0.0905817 -lp: 0.022113,0.0377166,0.0905725 -lp: 0.0221236,0.0378801,0.0905628 -lp: 0.0221342,0.0380439,0.090553 -lp: 0.0221385,0.0382083,0.0905456 -lp: 0.0220973,0.0383755,0.0905556 -lp: 0.0221131,0.0385399,0.0905438 -lp: 0.0221232,0.0387048,0.0905342 -lp: 0.0220824,0.0388729,0.090544 -lp: 0.0220885,0.0390387,0.0905359 -lp: 0.0220959,0.0392047,0.0905273 -lp: 0.0221004,0.0393711,0.0905198 -lp: 0.0221089,0.0395376,0.0905108 -lp: 0.022118,0.0397044,0.0905015 -lp: 0.0221294,0.0398714,0.0904914 -lp: 0.0220877,0.0400417,0.0905014 -lp: 0.0220972,0.0402094,0.0904919 -lp: 0.0221077,0.0403774,0.0904821 -lp: 0.0220744,0.0405482,0.0904889 -lp: 0.0220821,0.0407169,0.0904801 -lp: 0.0220905,0.0408859,0.090471 -lp: 0.0221016,0.0410551,0.0904608 -lp: 0.0221115,0.0412247,0.0904512 -lp: 0.0221199,0.0413946,0.0904421 -lp: 0.022126,0.0415651,0.0904338 -lp: 0.0221379,0.0417355,0.0904233 -lp: 0.0221523,0.0419061,0.0904119 -lp: 0.0221649,0.0420771,0.0904011 -lp: 0.0221696,0.0422489,0.0903934 -lp: 0.0221753,0.042421,0.0903852 -lp: 0.0221402,0.042596,0.0903926 -lp: 0.0221011,0.0427716,0.0904014 -lp: 0.0221088,0.0429447,0.0903925 -lp: 0.0221139,0.0431182,0.0903845 -lp: 0.022125,0.0432917,0.0903742 -lp: 0.0221303,0.043466,0.0903661 -lp: 0.022085,0.0436438,0.0903773 -lp: 0.0220955,0.0438184,0.0903672 -lp: 0.0220604,0.0439963,0.0903744 -lp: 0.0220727,0.0441715,0.0903636 -lp: 0.0220772,0.0443477,0.0903558 -lp: 0.022087,0.0445238,0.0903459 -lp: 0.022099,0.0447001,0.0903352 -lp: 0.022113,0.0448767,0.0903237 -lp: 0.0221242,0.0450539,0.0903133 -lp: 0.0221361,0.0452314,0.0903025 -lp: 0.0221447,0.0454095,0.0902931 -lp: 0.0221578,0.0455876,0.0902819 -lp: 0.0221229,0.0457694,0.0902889 -lp: 0.0221317,0.0459486,0.0902793 -lp: 0.0220946,0.0461313,0.0902872 -lp: 0.0221035,0.0463113,0.0902775 -lp: 0.0221093,0.0464919,0.090269 -lp: 0.0221205,0.0466726,0.0902585 -lp: 0.0221348,0.0468534,0.0902467 -lp: 0.0221511,0.0470346,0.0902342 -lp: 0.022165,0.0472162,0.0902226 -lp: 0.022172,0.0473988,0.0902135 -lp: 0.0221371,0.0475847,0.0902204 -lp: 0.0220917,0.0477717,0.0902313 -lp: 0.0220994,0.0479555,0.090222 -lp: 0.0221118,0.0481394,0.0902108 -lp: 0.0221253,0.0483236,0.0901993 -lp: 0.0221341,0.0485086,0.0901895 -lp: 0.0221369,0.0486945,0.0901819 -lp: 0.0221475,0.0488802,0.0901714 -lp: 0.0221147,0.0490695,0.0901774 -lp: 0.0220777,0.0492595,0.0901849 -lp: 0.0220904,0.0494464,0.0901736 -lp: 0.0221005,0.049634,0.0901632 -lp: 0.0221108,0.049822,0.0901527 -lp: 0.0221255,0.0500101,0.0901406 -lp: 0.0221408,0.0501987,0.0901282 -lp: 0.0221529,0.0503879,0.090117 -lp: 0.022058,0.0505855,0.0901464 -lp: 0.0220745,0.0507753,0.0901335 -lp: 0.0220921,0.0509656,0.0901202 -lp: 0.0221089,0.0511564,0.0901071 -lp: 0.0221134,0.0513486,0.0900987 -lp: 0.0221226,0.0515409,0.0900885 -lp: 0.0221414,0.051733,0.0900747 -lp: 0.022154,0.051926,0.0900631 -lp: 0.022164,0.0521197,0.0900526 -lp: 0.0221762,0.0523138,0.0900411 -lp: 0.0221426,0.0525118,0.0900471 -lp: 0.0221554,0.0527068,0.0900354 -lp: 0.0221083,0.0529069,0.0900465 -lp: 0.0221161,0.0531033,0.0900367 -lp: 0.0221309,0.0532998,0.0900242 -lp: 0.0221482,0.0534965,0.0900108 -lp: 0.0221641,0.0536939,0.0899979 -lp: 0.0221787,0.0538919,0.0899854 -lp: 0.0221921,0.0540905,0.0899734 -lp: 0.0221538,0.0542937,0.0899809 -lp: 0.022123,0.0544968,0.0899856 -lp: 0.0221372,0.054697,0.0899733 -lp: 0.0221538,0.0548976,0.08996 -lp: 0.0221652,0.0550991,0.0899486 -lp: 0.0221746,0.0553013,0.089938 -lp: 0.0221325,0.0555082,0.0899469 -lp: 0.0221447,0.0557113,0.0899352 -lp: 0.0221592,0.0559149,0.0899225 -lp: 0.0221752,0.0561189,0.0899094 -lp: 0.022135,0.0563279,0.0899175 -lp: 0.0221482,0.0565333,0.0899053 -lp: 0.0221575,0.0567396,0.0898945 -lp: 0.0221765,0.0569457,0.0898801 -lp: 0.0221935,0.0571525,0.0898664 -lp: 0.0222103,0.05736,0.0898528 -lp: 0.0222295,0.0575678,0.0898382 -lp: 0.0221371,0.0577855,0.089866 -lp: 0.0221469,0.0579954,0.089855 -lp: 0.0221568,0.0582059,0.0898439 -lp: 0.0221713,0.0584166,0.089831 -lp: 0.0221881,0.0586277,0.0898172 -lp: 0.0222068,0.0588394,0.0898027 -lp: 0.0221715,0.0590562,0.0898087 -lp: 0.022181,0.0592699,0.0897976 -lp: 0.0221449,0.0594882,0.0898039 -lp: 0.0221602,0.0597027,0.0897906 -lp: 0.0221731,0.0599181,0.0897781 -lp: 0.0221353,0.0601385,0.0897849 -lp: 0.0220874,0.0603605,0.0897956 -lp: 0.0221049,0.0605775,0.0897813 -lp: 0.022119,0.0607955,0.0897684 -lp: 0.0221336,0.0610142,0.0897552 -lp: 0.022158,0.0612327,0.0897382 -lp: 0.0221804,0.061452,0.0897221 -lp: 0.0222013,0.0616722,0.0897064 -lp: 0.0222196,0.0618934,0.0896917 -lp: 0.0222467,0.0621144,0.0896737 -lp: 0.0222672,0.0623368,0.0896581 -lp: 0.0222927,0.0625594,0.0896406 -lp: 0.0223817,0.0627773,0.089599 -lp: 0.0221992,0.0630198,0.0896604 -lp: 0.0222103,0.0632459,0.0896483 -lp: 0.0221726,0.0634773,0.0896547 -lp: 0.0221687,0.0637063,0.0896482 -lp: 0.0221273,0.0639395,0.089656 -lp: 0.0221526,0.0641675,0.0896383 -lp: 0.0221689,0.064397,0.0896241 -lp: 0.0217105,-0.0323939,0.0978547 -lp: 0.0216991,-0.0322273,0.0978512 -lp: 0.0216914,-0.0320608,0.0978464 -lp: 0.0216846,-0.0318945,0.0978411 -lp: 0.0216795,-0.0317283,0.0978352 -lp: 0.0216728,-0.0315625,0.09783 -lp: 0.021669,-0.0313968,0.0978236 -lp: 0.0216635,-0.0312314,0.0978179 -lp: 0.0217071,-0.0310636,0.097793 -lp: 0.0217,-0.0308988,0.097788 -lp: 0.0216884,-0.0307345,0.0977847 -lp: 0.0216789,-0.0305703,0.0977806 -lp: 0.0216745,-0.030406,0.0977746 -lp: 0.0217207,-0.0302394,0.0977487 -lp: 0.0217207,-0.0300755,0.097741 -lp: 0.0217132,-0.0299121,0.0977361 -lp: 0.0217038,-0.0297491,0.0977321 -lp: 0.0216935,-0.0295864,0.0977284 -lp: 0.0216846,-0.0294238,0.0977241 -lp: 0.0216825,-0.0292611,0.0977173 -lp: 0.0217222,-0.0290965,0.097694 -lp: 0.021717,-0.0289345,0.0976884 -lp: 0.0217145,-0.0287725,0.0976817 -lp: 0.0217102,-0.0286108,0.0976757 -lp: 0.021706,-0.0284493,0.0976697 -lp: 0.021739,-0.0282863,0.0976491 -lp: 0.0217321,-0.0281254,0.0976442 -lp: 0.0217238,-0.0279648,0.0976398 -lp: 0.0217166,-0.0278044,0.097635 -lp: 0.0217074,-0.0276442,0.097631 -lp: 0.0217016,-0.0274842,0.0976257 -lp: 0.0216955,-0.0273243,0.0976205 -lp: 0.02169,-0.0271646,0.0976151 -lp: 0.0217327,-0.0270029,0.0975908 -lp: 0.0217289,-0.0268436,0.0975848 -lp: 0.0217201,-0.0266847,0.0975807 -lp: 0.0217127,-0.0265259,0.097576 -lp: 0.021706,-0.0263673,0.0975711 -lp: 0.0217075,-0.0262086,0.097563 -lp: 0.0217512,-0.0260481,0.0975384 -lp: 0.0217492,-0.0258899,0.0975317 -lp: 0.0217424,-0.0257321,0.0975269 -lp: 0.0217363,-0.0255745,0.0975218 -lp: 0.0217296,-0.0254171,0.097517 -lp: 0.0217249,-0.0252598,0.0975113 -lp: 0.0217197,-0.0251027,0.0975059 -lp: 0.0217165,-0.0249457,0.0974997 -lp: 0.0217095,-0.0247891,0.097495 -lp: 0.0217449,-0.0246309,0.0974738 -lp: 0.0217368,-0.0244746,0.0974695 -lp: 0.0217304,-0.0243185,0.0974647 -lp: 0.0217258,-0.0241626,0.097459 -lp: 0.0217226,-0.0240067,0.0974529 -lp: 0.0217577,-0.0238494,0.0974318 -lp: 0.0217526,-0.023694,0.0974264 -lp: 0.021749,-0.0235387,0.0974205 -lp: 0.0217443,-0.0233836,0.097415 -lp: 0.0217375,-0.0232288,0.0974103 -lp: 0.021731,-0.0230741,0.0974055 -lp: 0.0217231,-0.0229197,0.0974013 -lp: 0.0217178,-0.0227653,0.097396 -lp: 0.0217124,-0.0226111,0.0973908 -lp: 0.0217596,-0.022455,0.0973651 -lp: 0.0217556,-0.0223011,0.0973593 -lp: 0.0217534,-0.0221473,0.0973529 -lp: 0.0217485,-0.0219938,0.0973476 -lp: 0.0217947,-0.0218385,0.0973222 -lp: 0.0217913,-0.0216852,0.0973163 -lp: 0.0217874,-0.0215321,0.0973106 -lp: 0.0217798,-0.0213793,0.0973063 -lp: 0.0217735,-0.0212267,0.0973015 -lp: 0.0217683,-0.0210741,0.0972963 -lp: 0.0217638,-0.0209217,0.0972908 -lp: 0.0217573,-0.0207695,0.0972861 -lp: 0.0217538,-0.0206173,0.0972803 -lp: 0.0217503,-0.0204653,0.0972745 -lp: 0.0217459,-0.0203135,0.097269 -lp: 0.0217397,-0.0201618,0.0972643 -lp: 0.0217345,-0.0200103,0.0972591 -lp: 0.0217743,-0.0198575,0.0972364 -lp: 0.0217744,-0.0197061,0.0972292 -lp: 0.0217737,-0.0195549,0.0972223 -lp: 0.0218081,-0.0194027,0.0972017 -lp: 0.021803,-0.0192519,0.0971965 -lp: 0.0217977,-0.0191013,0.0971915 -lp: 0.0217966,-0.0189507,0.0971848 -lp: 0.0217898,-0.0188004,0.0971803 -lp: 0.0217854,-0.0186502,0.0971749 -lp: 0.0217811,-0.0185001,0.0971695 -lp: 0.0218287,-0.0183485,0.0971438 -lp: 0.0218241,-0.0181987,0.0971385 -lp: 0.0218195,-0.0180491,0.0971332 -lp: 0.0218168,-0.0178995,0.0971272 -lp: 0.0218154,-0.01775,0.0971206 -lp: 0.0218106,-0.0176007,0.0971154 -lp: 0.0218018,-0.0174517,0.0971118 -lp: 0.0217969,-0.0173027,0.0971066 -lp: 0.0217979,-0.0171536,0.0970992 -lp: 0.0218479,-0.0170033,0.0970727 -lp: 0.0218427,-0.0168547,0.0970676 -lp: 0.0218371,-0.0167062,0.0970628 -lp: 0.0218322,-0.0165579,0.0970577 -lp: 0.0218286,-0.0164096,0.097052 -lp: 0.021828,-0.0162613,0.0970453 -lp: 0.0218272,-0.0161132,0.0970386 -lp: 0.0218224,-0.0159653,0.0970334 -lp: 0.0218175,-0.0158176,0.0970283 -lp: 0.0218124,-0.0156699,0.0970233 -lp: 0.0218099,-0.0155223,0.0970173 -lp: 0.0218457,-0.0153738,0.0969963 -lp: 0.0218433,-0.0152265,0.0969903 -lp: 0.021838,-0.0150793,0.0969854 -lp: 0.0218342,-0.0149322,0.0969799 -lp: 0.0218327,-0.0147851,0.0969735 -lp: 0.0218309,-0.0146382,0.0969673 -lp: 0.0218289,-0.0144914,0.0969611 -lp: 0.0218319,-0.0143445,0.096953 -lp: 0.0218349,-0.0141978,0.0969449 -lp: 0.0218652,-0.0140505,0.0969261 -lp: 0.021857,-0.0139043,0.0969224 -lp: 0.021853,-0.0137581,0.096917 -lp: 0.0218508,-0.0136119,0.096911 -lp: 0.0218508,-0.0134658,0.096904 -lp: 0.0218479,-0.0133198,0.0968983 -lp: 0.0218931,-0.0131729,0.0968737 -lp: 0.021889,-0.0130272,0.0968684 -lp: 0.0218853,-0.0128815,0.096863 -lp: 0.0218826,-0.012736,0.0968571 -lp: 0.0218819,-0.0125905,0.0968505 -lp: 0.0218809,-0.0124451,0.096844 -lp: 0.0218805,-0.0122998,0.0968373 -lp: 0.0218758,-0.0121546,0.0968322 -lp: 0.0218735,-0.0120095,0.0968263 -lp: 0.0218707,-0.0118645,0.0968205 -lp: 0.0219113,-0.0117188,0.0967978 -lp: 0.0219057,-0.011574,0.0967931 -lp: 0.0219103,-0.0114292,0.0967845 -lp: 0.0219129,-0.0112844,0.0967766 -lp: 0.0219097,-0.0111399,0.096771 -lp: 0.0219188,-0.0109952,0.0967606 -lp: 0.0219087,-0.010851,0.0967577 -lp: 0.0219613,-0.0107057,0.0967304 -lp: 0.0219548,-0.0105616,0.0967261 -lp: 0.0219484,-0.0104175,0.0967218 -lp: 0.0218984,-0.0102743,0.0967344 -lp: 0.0219411,-0.0101296,0.096711 -lp: 0.0219414,-0.00998565,0.0967041 -lp: 0.021937,-0.00984188,0.0966989 -lp: 0.0219367,-0.00969812,0.0966922 -lp: 0.0219326,-0.0095545,0.096687 -lp: 0.0219266,-0.00941099,0.0966826 -lp: 0.0219202,-0.00926755,0.0966783 -lp: 0.0219161,-0.00912415,0.0966731 -lp: 0.0218793,-0.00755113,0.0966129 -lp: 0.0219347,-0.00740778,0.0965846 -lp: 0.0219527,-0.00726497,0.0965709 -lp: 0.0219865,-0.00712205,0.096551 -lp: 0.0219857,-0.00697962,0.0965445 -lp: 0.0219318,-0.00683786,0.0965588 -lp: 0.021928,-0.00669557,0.0965535 -lp: 0.0219809,-0.00655269,0.0965261 -lp: 0.0219775,-0.00641052,0.0965208 -lp: 0.0219705,-0.00626844,0.0965168 -lp: 0.0219659,-0.00612638,0.0965118 -lp: 0.0219642,-0.00598435,0.0965058 -lp: 0.0219643,-0.00584236,0.096499 -lp: 0.0219672,-0.00570039,0.0964911 -lp: 0.0219656,-0.00555851,0.096485 -lp: 0.0219629,-0.0054167,0.0964794 -lp: 0.0219593,-0.00527494,0.0964741 -lp: 0.0219563,-0.00513323,0.0964685 -lp: 0.0219542,-0.00499155,0.0964627 -lp: 0.0219504,-0.00484994,0.0964574 -lp: 0.0219457,-0.00470838,0.0964526 -lp: 0.021943,-0.00456684,0.0964469 -lp: 0.0219388,-0.00442536,0.0964419 -lp: 0.0219366,-0.00428391,0.096436 -lp: 0.0219354,-0.0041425,0.0964298 -lp: 0.0219407,-0.00400108,0.096421 -lp: 0.0219692,-0.00385954,0.0964032 -lp: 0.0219733,-0.00371822,0.0963949 -lp: 0.0219383,-0.00357719,0.0964019 -lp: 0.0219378,-0.00343597,0.0963954 -lp: 0.0219371,-0.00329479,0.096389 -lp: 0.0219848,-0.00315338,0.0963637 -lp: 0.0219856,-0.00301228,0.0963567 -lp: 0.0219836,-0.00287123,0.0963508 -lp: 0.0219809,-0.00273021,0.0963452 -lp: 0.0219767,-0.00258923,0.0963402 -lp: 0.0219739,-0.00244828,0.0963346 -lp: 0.0219713,-0.00230736,0.0963289 -lp: 0.0219693,-0.00216647,0.096323 -lp: 0.0219699,-0.0020256,0.0963161 -lp: 0.0219706,-0.00188475,0.0963092 -lp: 0.0219702,-0.00174394,0.0963027 -lp: 0.0219732,-0.00160315,0.0962949 -lp: 0.0220188,-0.00146226,0.0962704 -lp: 0.0220187,-0.00132154,0.0962638 -lp: 0.0219647,-0.00118098,0.0962782 -lp: 0.0220202,-0.00104018,0.0962499 -lp: 0.0220201,-0.000899532,0.0962433 -lp: 0.0220199,-0.00075891,0.0962367 -lp: 0.0220183,-0.000618311,0.0962307 -lp: 0.0220199,-0.000477729,0.0962234 -lp: 0.0220137,-0.000337176,0.0962192 -lp: 0.0220103,-0.000196637,0.0962138 -lp: 0.0220089,-5.61143e-05,0.0962077 -lp: 0.0219683,8.43817e-05,0.0962168 -lp: 0.0219596,0.00022488,0.0962136 -lp: 0.0220105,0.000365352,0.0961871 -lp: 0.0220093,0.000505809,0.096181 -lp: 0.0220081,0.000646252,0.0961748 -lp: 0.0220084,0.000786681,0.096168 -lp: 0.0220103,0.000927095,0.0961606 -lp: 0.0220096,0.0010675,0.0961542 -lp: 0.0220037,0.0012079,0.0961499 -lp: 0.0220046,0.00134828,0.0961429 -lp: 0.0220091,0.00148865,0.0961345 -lp: 0.0220537,0.00162891,0.0961105 -lp: 0.0220534,0.00176926,0.096104 -lp: 0.0220526,0.0019096,0.0960976 -lp: 0.0220056,0.00205007,0.0961093 -lp: 0.0220046,0.00219041,0.096103 -lp: 0.0220044,0.00233075,0.0960965 -lp: 0.0220031,0.00247108,0.0960903 -lp: 0.0220026,0.00261141,0.0960839 -lp: 0.022002,0.00275174,0.0960775 -lp: 0.0219999,0.00289208,0.0960717 -lp: 0.0220026,0.00303239,0.096064 -lp: 0.0220613,0.00317243,0.0960345 -lp: 0.0220505,0.0033128,0.0960321 -lp: 0.0220454,0.00345314,0.0960274 -lp: 0.0219966,0.00359373,0.0960397 -lp: 0.022046,0.00373379,0.0960139 -lp: 0.0220074,0.00387435,0.0960222 -lp: 0.0220432,0.00401447,0.0960017 -lp: 0.0220411,0.00415483,0.0959959 -lp: 0.0220406,0.00429518,0.0959894 -lp: 0.0220404,0.00443554,0.0959828 -lp: 0.0220406,0.00457591,0.0959761 -lp: 0.0220052,0.00471654,0.0959832 -lp: 0.0220061,0.00485693,0.0959762 -lp: 0.0220065,0.00499733,0.0959694 -lp: 0.0220432,0.00513746,0.0959485 -lp: 0.0220454,0.00527786,0.095941 -lp: 0.0220493,0.00541827,0.0959329 -lp: 0.0220496,0.00555872,0.0959261 -lp: 0.0220484,0.00569919,0.0959199 -lp: 0.0220473,0.00583968,0.0959137 -lp: 0.0220469,0.00598019,0.0959072 -lp: 0.0220467,0.00612071,0.0959006 -lp: 0.0220474,0.00626124,0.0958937 -lp: 0.0220495,0.00640177,0.0958862 -lp: 0.0220525,0.00654232,0.0958784 -lp: 0.0220535,0.00668291,0.0958714 -lp: 0.0220534,0.00682353,0.0958647 -lp: 0.0220533,0.00696417,0.0958581 -lp: 0.0220545,0.00710483,0.095851 -lp: 0.0220576,0.00724548,0.0958431 -lp: 0.0220608,0.00738616,0.0958352 -lp: 0.0220617,0.00752689,0.0958282 -lp: 0.0220603,0.00766768,0.0958221 -lp: 0.0220593,0.00780849,0.0958158 -lp: 0.0220614,0.00794929,0.0958083 -lp: 0.0220612,0.00809015,0.0958017 -lp: 0.0220247,0.00823151,0.0958092 -lp: 0.0220115,0.00837262,0.0958077 -lp: 0.0220724,0.00851276,0.0957774 -lp: 0.0220918,0.00865348,0.0957632 -lp: 0.0220881,0.00879454,0.0957579 -lp: 0.0220926,0.00893552,0.0957495 -lp: 0.0220884,0.00907667,0.0957445 -lp: 0.0220873,0.00921781,0.0957382 -lp: 0.022072,0.00935919,0.0957374 -lp: 0.0220208,0.00950116,0.0957506 -lp: 0.0220731,0.0130455,0.0955625 -lp: 0.0220213,0.0131891,0.0955758 -lp: 0.0220717,0.0133306,0.0955495 -lp: 0.0220748,0.0134732,0.0955416 -lp: 0.0220332,0.0136168,0.095551 -lp: 0.0220782,0.0137586,0.0955268 -lp: 0.0220805,0.0139014,0.0955191 -lp: 0.0220833,0.0140442,0.0955113 -lp: 0.0220864,0.0141871,0.0955033 -lp: 0.022089,0.0143301,0.0954955 -lp: 0.0220908,0.0144731,0.095488 -lp: 0.0220933,0.0146162,0.0954803 -lp: 0.0220962,0.0147594,0.0954724 -lp: 0.0220996,0.0149027,0.0954643 -lp: 0.0221032,0.015046,0.0954561 -lp: 0.022106,0.0151894,0.0954482 -lp: 0.0221087,0.0153328,0.0954404 -lp: 0.0220683,0.0154774,0.0954492 -lp: 0.02207,0.0156211,0.0954418 -lp: 0.0220706,0.0157649,0.0954348 -lp: 0.022072,0.0159087,0.0954274 -lp: 0.0220724,0.0160526,0.0954204 -lp: 0.0220726,0.0161966,0.0954135 -lp: 0.0220734,0.0163407,0.0954064 -lp: 0.0220793,0.0164847,0.0953973 -lp: 0.022083,0.0166289,0.095389 -lp: 0.0220872,0.0167732,0.0953805 -lp: 0.0220902,0.0169175,0.0953726 -lp: 0.0221324,0.0170609,0.0953493 -lp: 0.0220958,0.0172065,0.0953567 -lp: 0.0221002,0.0173511,0.0953481 -lp: 0.0221046,0.0174957,0.0953396 -lp: 0.0221086,0.0176405,0.0953312 -lp: 0.0221128,0.0177854,0.0953227 -lp: 0.0221166,0.0179303,0.0953143 -lp: 0.0221186,0.0180754,0.0953067 -lp: 0.0221267,0.0182204,0.0952967 -lp: 0.0221324,0.0183656,0.0952876 -lp: 0.0221326,0.018511,0.0952806 -lp: 0.0221403,0.0186563,0.0952708 -lp: 0.0221516,0.0188016,0.0952595 -lp: 0.0221574,0.0189472,0.0952503 -lp: 0.0221631,0.0190929,0.0952412 -lp: 0.0221612,0.0192389,0.0952351 -lp: 0.02216,0.0193849,0.0952286 -lp: 0.0221381,0.0227754,0.0950766 -lp: 0.0221421,0.0229241,0.095068 -lp: 0.0220771,0.0230755,0.0950861 -lp: 0.0220842,0.0232243,0.0950763 -lp: 0.0220925,0.0233733,0.095066 -lp: 0.0220964,0.0235225,0.0950575 -lp: 0.0221015,0.0236718,0.0950484 -lp: 0.0221055,0.0238213,0.0950398 -lp: 0.0221102,0.0239709,0.0950309 -lp: 0.0221148,0.0241206,0.095022 -lp: 0.0221198,0.0242705,0.095013 -lp: 0.0221253,0.0244205,0.0950037 -lp: 0.0221284,0.0245707,0.0949954 -lp: 0.0221288,0.0247212,0.0949881 -lp: 0.0221314,0.0248717,0.09498 -lp: 0.0221378,0.0250222,0.0949704 -lp: 0.0221431,0.0251729,0.0949612 -lp: 0.0221064,0.0253254,0.0949682 -lp: 0.0221096,0.0254765,0.0949598 -lp: 0.0220643,0.0256297,0.0949702 -lp: 0.0220644,0.0257812,0.094963 -lp: 0.0220673,0.0259328,0.0949547 -lp: 0.0220715,0.0260845,0.0949459 -lp: 0.022077,0.0262362,0.0949365 -lp: 0.0220831,0.0263881,0.094927 -lp: 0.0220885,0.0265402,0.0949177 -lp: 0.0220951,0.0266923,0.0949079 -lp: 0.0221003,0.0268447,0.0948987 -lp: 0.0221017,0.0269975,0.0948909 -lp: 0.0221041,0.0271503,0.0948827 -lp: 0.0221069,0.0273033,0.0948744 -lp: 0.0221122,0.0274563,0.0948651 -lp: 0.0220694,0.0276116,0.0948744 -lp: 0.0220751,0.027765,0.0948649 -lp: 0.0220383,0.0279204,0.0948719 -lp: 0.0220829,0.0280723,0.0948473 -lp: 0.0220863,0.0282263,0.0948387 -lp: 0.0220932,0.0283803,0.0948287 -lp: 0.0221023,0.0285343,0.0948179 -lp: 0.0220691,0.0286905,0.0948234 -lp: 0.0220781,0.0288449,0.0948126 -lp: 0.0220819,0.0289997,0.0948038 -lp: 0.0220833,0.0291548,0.0947959 -lp: 0.0220856,0.0293101,0.0947877 -lp: 0.0220887,0.0294655,0.0947791 -lp: 0.0220922,0.029621,0.0947704 -lp: 0.0220968,0.0297767,0.0947612 -lp: 0.0221021,0.0299326,0.0947518 -lp: 0.0221082,0.0300886,0.094742 -lp: 0.0221165,0.0302447,0.0947314 -lp: 0.0221215,0.0304011,0.0947221 -lp: 0.0221217,0.0305579,0.0947146 -lp: 0.0220807,0.0307169,0.094723 -lp: 0.0220388,0.0308762,0.0947317 -lp: 0.0220463,0.0310333,0.0947214 -lp: 0.0220531,0.0311907,0.0947113 -lp: 0.0220602,0.0313482,0.0947011 -lp: 0.0220651,0.031506,0.0946917 -lp: 0.0220717,0.0316639,0.0946816 -lp: 0.0220776,0.0318221,0.0946719 -lp: 0.0220854,0.0319803,0.0946613 -lp: 0.0220942,0.0321387,0.0946504 -lp: 0.0220975,0.0322977,0.0946416 -lp: 0.0221018,0.0324567,0.0946324 -lp: 0.0221077,0.0326159,0.0946226 -lp: 0.0221145,0.0327753,0.0946124 -lp: 0.0221212,0.0329348,0.0946022 -lp: 0.0220745,0.0330974,0.0946127 -lp: 0.0220775,0.0332576,0.0946039 -lp: 0.0220833,0.0334179,0.0945941 -lp: 0.0220899,0.0335784,0.0945839 -lp: 0.022052,0.0337414,0.094591 -lp: 0.0220589,0.0339023,0.0945807 -lp: 0.022068,0.0340633,0.0945695 -lp: 0.0220744,0.0342246,0.0945594 -lp: 0.0220776,0.0343864,0.0945505 -lp: 0.0220856,0.0345481,0.0945397 -lp: 0.0220965,0.03471,0.0945278 -lp: 0.0221074,0.034872,0.0945159 -lp: 0.022113,0.0350346,0.094506 -lp: 0.0221192,0.0351973,0.0944959 -lp: 0.0221267,0.0353602,0.0944853 -lp: 0.0221339,0.0355234,0.0944747 -lp: 0.0221439,0.0356867,0.0944631 -lp: 0.0221519,0.0358503,0.0944523 -lp: 0.0221586,0.0360142,0.0944419 -lp: 0.0221656,0.0361784,0.0944314 -lp: 0.0221189,0.0363458,0.0944416 -lp: 0.0220735,0.0365135,0.0944514 -lp: 0.02208,0.0366785,0.094441 -lp: 0.0220858,0.0368437,0.094431 -lp: 0.0220951,0.037009,0.0944195 -lp: 0.0221053,0.0371745,0.0944077 -lp: 0.0221133,0.0373404,0.0943967 -lp: 0.022118,0.0375068,0.0943871 -lp: 0.0221251,0.0376732,0.0943764 -lp: 0.0221333,0.0378399,0.0943653 -lp: 0.0221452,0.0380066,0.0943528 -lp: 0.0221559,0.0381737,0.0943407 -lp: 0.0221644,0.0383411,0.0943295 -lp: 0.0221232,0.0385118,0.0943375 -lp: 0.0220748,0.0386832,0.0943481 -lp: 0.0220782,0.0388518,0.0943388 -lp: 0.022089,0.0390202,0.0943267 -lp: 0.0220964,0.0391892,0.0943158 -lp: 0.0221037,0.0393583,0.094305 -lp: 0.0221118,0.0395278,0.0942938 -lp: 0.022122,0.0396974,0.0942818 -lp: 0.0221301,0.0398673,0.0942706 -lp: 0.022137,0.0400377,0.0942598 -lp: 0.0221485,0.0402081,0.0942473 -lp: 0.0221581,0.0403788,0.0942355 -lp: 0.022165,0.0405501,0.0942247 -lp: 0.0220718,0.040728,0.0942525 -lp: 0.0220782,0.0408999,0.0942419 -lp: 0.0220889,0.0410718,0.0942296 -lp: 0.0220971,0.0412442,0.0942182 -lp: 0.0221072,0.0414167,0.0942062 -lp: 0.022117,0.0415896,0.0941941 -lp: 0.0221278,0.0417627,0.0941818 -lp: 0.0221361,0.0419363,0.0941703 -lp: 0.0221421,0.0421104,0.0941597 -lp: 0.0221503,0.0422846,0.0941483 -lp: 0.022158,0.0424592,0.094137 -lp: 0.0221224,0.042637,0.0941425 -lp: 0.0220802,0.0428156,0.0941504 -lp: 0.0220856,0.0429913,0.09414 -lp: 0.0220953,0.0431671,0.0941279 -lp: 0.0221071,0.0433431,0.094115 -lp: 0.0221201,0.0435193,0.0941016 -lp: 0.0221292,0.0436961,0.0940897 -lp: 0.0221362,0.0438734,0.0940786 -lp: 0.0221415,0.0440511,0.0940681 -lp: 0.0221515,0.0442289,0.0940558 -lp: 0.0221632,0.0444069,0.0940428 -lp: 0.022176,0.0445852,0.0940294 -lp: 0.0221814,0.0447643,0.0940188 -lp: 0.0220836,0.044951,0.094048 -lp: 0.022091,0.0451307,0.0940366 -lp: 0.0221046,0.0453103,0.0940228 -lp: 0.0221193,0.0454902,0.0940086 -lp: 0.0221337,0.0456705,0.0939944 -lp: 0.0221466,0.0458513,0.0939809 -lp: 0.0221466,0.0460333,0.0939723 -lp: 0.0221014,0.046219,0.0939811 -lp: 0.0221045,0.0464016,0.0939712 -lp: 0.0220672,0.0465875,0.0939769 -lp: 0.0220804,0.0467701,0.0939631 -lp: 0.0220916,0.0469533,0.0939501 -lp: 0.0221024,0.0471368,0.0939372 -lp: 0.022111,0.0473209,0.0939252 -lp: 0.0221209,0.0475053,0.0939126 -lp: 0.0221303,0.0476902,0.0939002 -lp: 0.0221442,0.0478751,0.093886 -lp: 0.0221575,0.0480604,0.093872 -lp: 0.0221696,0.0482462,0.0938586 -lp: 0.0221761,0.0484328,0.0938472 -lp: 0.0221875,0.0486195,0.0938339 -lp: 0.0221487,0.0488104,0.09384 -lp: 0.0221606,0.0489978,0.0938265 -lp: 0.0221115,0.0491904,0.0938365 -lp: 0.022121,0.0493789,0.0938238 -lp: 0.0221322,0.0495676,0.0938105 -lp: 0.0221442,0.0497568,0.0937969 -lp: 0.0221551,0.0499464,0.0937837 -lp: 0.0221658,0.0501365,0.0937705 -lp: 0.0221781,0.050327,0.0937568 -lp: 0.0221932,0.0505176,0.0937419 -lp: 0.0221523,0.050713,0.0937485 -lp: 0.0222254,0.0509,0.0937112 -lp: 0.022129,0.0511007,0.0937392 -lp: 0.0221374,0.0512936,0.0937268 -lp: 0.0221472,0.0514869,0.0937138 -lp: 0.0221603,0.0516804,0.0936996 -lp: 0.0221665,0.0518749,0.093688 -lp: 0.0221754,0.0520696,0.0936753 -lp: 0.0221852,0.0522648,0.0936622 -lp: 0.0222036,0.0524597,0.0936459 -lp: 0.02216,0.0526601,0.0936533 -lp: 0.0221176,0.0528609,0.0936603 -lp: 0.0221273,0.0530579,0.0936472 -lp: 0.0221394,0.0532553,0.0936332 -lp: 0.0221505,0.0534532,0.0936195 -lp: 0.0221651,0.0536513,0.0936044 -lp: 0.02218,0.0538499,0.0935892 -lp: 0.0221942,0.054049,0.0935743 -lp: 0.022148,0.0542537,0.0935826 -lp: 0.0221619,0.0544539,0.0935677 -lp: 0.0221794,0.0546542,0.0935514 -lp: 0.0221484,0.0548592,0.0935537 -lp: 0.02216,0.0550611,0.0935397 -lp: 0.0221642,0.0552642,0.0935284 -lp: 0.0221705,0.0554676,0.0935163 -lp: 0.0221846,0.0556709,0.0935013 -lp: 0.0222022,0.0558744,0.0934848 -lp: 0.0221625,0.0560833,0.0934903 -lp: 0.0221741,0.0562885,0.0934761 -lp: 0.0221307,0.0564989,0.093483 -lp: 0.0221441,0.0567049,0.093468 -lp: 0.0221619,0.0569111,0.0934513 -lp: 0.0221761,0.0571182,0.093436 -lp: 0.0221827,0.0573266,0.0934236 -lp: 0.0221994,0.0575346,0.0934072 -lp: 0.0222181,0.057743,0.0933901 -lp: 0.0222361,0.057952,0.0933732 -lp: 0.0221926,0.058167,0.0933799 -lp: 0.0221437,0.0583832,0.0933887 -lp: 0.0221538,0.0585947,0.0933748 -lp: 0.022172,0.0588061,0.0933577 -lp: 0.022192,0.0590179,0.0933399 -lp: 0.0222109,0.0592304,0.0933225 -lp: 0.022224,0.059444,0.0933073 -lp: 0.0221746,0.0596639,0.0933161 -lp: 0.0221833,0.0598792,0.0933025 -lp: 0.022145,0.0600993,0.093307 -lp: 0.0221564,0.0603156,0.0932923 -lp: 0.0221685,0.0605325,0.0932773 -lp: 0.0221872,0.0607493,0.0932598 -lp: 0.0222063,0.0609668,0.0932421 -lp: 0.0221035,0.0611963,0.0932712 -lp: 0.022121,0.0614152,0.093254 -lp: 0.0221362,0.061635,0.0932377 -lp: 0.0221578,0.0618549,0.0932189 -lp: 0.0221763,0.0620757,0.0932013 -lp: 0.0221964,0.062297,0.093183 -lp: 0.0222102,0.0625196,0.0931671 -lp: 0.0222198,0.0627433,0.0931527 -lp: 0.0222298,0.0629676,0.0931382 -lp: 0.0222499,0.0631917,0.0931198 -lp: 0.0222133,0.0634219,0.0931231 -lp: 0.022227,0.063648,0.0931071 -lp: 0.0221812,0.0638805,0.0931139 -lp: 0.0221998,0.0641076,0.0930959 -lp: 0.0222224,0.0643349,0.0930764 -lp: 0.0222496,0.0645626,0.093055 -lp: 0.0222719,0.0647915,0.0930355 -lp: 0.0222942,0.0650211,0.093016 -lp: 0.0223051,0.0652525,0.0930008 -lp: 0.0223242,0.0654839,0.0929824 -lp: 0.0223426,0.0657162,0.0929642 -lp: 0.022361,0.0659492,0.092946 -lp: 0.0223115,0.0661896,0.0929539 -lp: 0.0221923,0.0664379,0.0929885 -lp: 0.0222874,0.0666656,0.0929407 -lp: 0.0223182,0.0669005,0.0929176 -lp: 0.0210694,-0.0411724,0.125606 -lp: 0.0210573,-0.0409587,0.125594 -lp: 0.0211069,-0.0407401,0.125556 -lp: 0.0211037,-0.0405263,0.12554 -lp: 0.0211642,-0.0403076,0.125497 -lp: 0.0211578,-0.0400948,0.125483 -lp: 0.0211554,-0.039882,0.125467 -lp: 0.0211494,-0.0396698,0.125452 -lp: 0.0211433,-0.039458,0.125438 -lp: 0.0211962,-0.0392418,0.125398 -lp: 0.0211925,-0.0390305,0.125383 -lp: 0.0211886,-0.0388196,0.125368 -lp: 0.0211828,-0.0386091,0.125353 -lp: 0.0211726,-0.0383993,0.125341 -lp: 0.0211611,-0.0381899,0.125329 -lp: 0.0211491,-0.0379809,0.125318 -lp: 0.0211931,-0.0377678,0.125282 -lp: 0.0211356,-0.037563,0.12529 -lp: 0.0211893,-0.0373499,0.12525 -lp: 0.0211877,-0.0371414,0.125234 -lp: 0.0211804,-0.0369336,0.125221 -lp: 0.0211718,-0.0367262,0.125208 -lp: 0.0211701,-0.0365186,0.125192 -lp: 0.021171,-0.0363111,0.125175 -lp: 0.0212151,-0.0361008,0.12514 -lp: 0.0212051,-0.0358947,0.125127 -lp: 0.0211955,-0.035689,0.125115 -lp: 0.0211891,-0.0354833,0.125101 -lp: 0.0211867,-0.0352776,0.125086 -lp: 0.0211832,-0.0350722,0.125071 -lp: 0.0212341,-0.0348633,0.125033 -lp: 0.0212271,-0.0346588,0.12502 -lp: 0.021221,-0.0344546,0.125006 -lp: 0.0212172,-0.0342505,0.124991 -lp: 0.0212116,-0.0340467,0.124977 -lp: 0.0212025,-0.0338436,0.124965 -lp: 0.0211956,-0.0336405,0.124952 -lp: 0.0211925,-0.0334374,0.124937 -lp: 0.0212459,-0.0332308,0.124898 -lp: 0.0212368,-0.0330287,0.124885 -lp: 0.0212264,-0.032827,0.124874 -lp: 0.0212171,-0.0326255,0.124861 -lp: 0.0212084,-0.0324242,0.124849 -lp: 0.0212066,-0.0322227,0.124834 -lp: 0.0212598,-0.0320179,0.124795 -lp: 0.0211996,-0.0318208,0.124805 -lp: 0.0211954,-0.0316203,0.12479 -lp: 0.0212456,-0.0314165,0.124753 -lp: 0.0212445,-0.0312163,0.124737 -lp: 0.0212426,-0.0310164,0.124722 -lp: 0.0212385,-0.0308169,0.124708 -lp: 0.0212314,-0.0306179,0.124695 -lp: 0.0212231,-0.0304192,0.124683 -lp: 0.0212161,-0.0302206,0.12467 -lp: 0.0212109,-0.0300222,0.124656 -lp: 0.0212546,-0.0298211,0.124622 -lp: 0.0212468,-0.0296233,0.124609 -lp: 0.0212391,-0.0294258,0.124597 -lp: 0.0211831,-0.0292314,0.124605 -lp: 0.0212313,-0.029031,0.124569 -lp: 0.021223,-0.0288342,0.124556 -lp: 0.0212151,-0.0286377,0.124544 -lp: 0.0212706,-0.0284376,0.124505 -lp: 0.0212702,-0.0282411,0.124489 -lp: 0.0212704,-0.0280448,0.124473 -lp: 0.0212654,-0.027849,0.12446 -lp: 0.0212606,-0.0276535,0.124446 -lp: 0.0212539,-0.0274582,0.124434 -lp: 0.0212443,-0.0272634,0.124422 -lp: 0.0212311,-0.027069,0.124412 -lp: 0.0212242,-0.0268744,0.1244 -lp: 0.0212208,-0.0266798,0.124385 -lp: 0.0212229,-0.0264852,0.124369 -lp: 0.0212804,-0.0262878,0.124329 -lp: 0.0212766,-0.026094,0.124315 -lp: 0.0212683,-0.0259006,0.124303 -lp: 0.0212597,-0.0257074,0.124291 -lp: 0.0212535,-0.0255143,0.124279 -lp: 0.0212455,-0.0253216,0.124267 -lp: 0.0212399,-0.0251289,0.124254 -lp: 0.021291,-0.0249335,0.124216 -lp: 0.0212923,-0.0247408,0.124201 -lp: 0.0212902,-0.0245486,0.124186 -lp: 0.0212845,-0.0243567,0.124173 -lp: 0.0212784,-0.024165,0.12416 -lp: 0.0212708,-0.0239737,0.124148 -lp: 0.0212658,-0.0237824,0.124135 -lp: 0.021265,-0.023591,0.12412 -lp: 0.0212619,-0.0234,0.124106 -lp: 0.0212566,-0.0232093,0.124093 -lp: 0.0212549,-0.0230186,0.124079 -lp: 0.0213015,-0.0228258,0.124044 -lp: 0.0212974,-0.0226356,0.12403 -lp: 0.021243,-0.0224479,0.124038 -lp: 0.0212939,-0.0222556,0.124002 -lp: 0.0213523,-0.0220631,0.123961 -lp: 0.0213459,-0.0218738,0.123949 -lp: 0.0213398,-0.0216846,0.123937 -lp: 0.0213341,-0.0214956,0.123924 -lp: 0.0213318,-0.0213066,0.12391 -lp: 0.0213273,-0.0211179,0.123897 -lp: 0.0213218,-0.0209294,0.123884 -lp: 0.0213176,-0.020741,0.123871 -lp: 0.021315,-0.0205527,0.123857 -lp: 0.0213136,-0.0203646,0.123842 -lp: 0.0213103,-0.0201767,0.123829 -lp: 0.0213064,-0.019989,0.123815 -lp: 0.0213052,-0.0198013,0.123801 -lp: 0.0213644,-0.0196114,0.123761 -lp: 0.0213594,-0.0194243,0.123748 -lp: 0.0213544,-0.0192373,0.123735 -lp: 0.0213418,-0.0190507,0.123726 -lp: 0.0213366,-0.0188641,0.123713 -lp: 0.0213321,-0.0186775,0.1237 -lp: 0.0213834,-0.018489,0.123663 -lp: 0.0213811,-0.0183027,0.123649 -lp: 0.0213804,-0.0181166,0.123635 -lp: 0.021381,-0.0179305,0.12362 -lp: 0.0213765,-0.0177447,0.123607 -lp: 0.0213737,-0.0175591,0.123593 -lp: 0.0213686,-0.0173736,0.12358 -lp: 0.0213657,-0.0171883,0.123567 -lp: 0.021364,-0.017003,0.123553 -lp: 0.02136,-0.016818,0.12354 -lp: 0.0213595,-0.016633,0.123525 -lp: 0.0213586,-0.0164481,0.123511 -lp: 0.0213582,-0.0162634,0.123496 -lp: 0.0213557,-0.0160789,0.123483 -lp: 0.021352,-0.0158946,0.123469 -lp: 0.0213466,-0.0157104,0.123457 -lp: 0.0213935,-0.0155248,0.123422 -lp: 0.0213913,-0.0153408,0.123409 -lp: 0.0213891,-0.015157,0.123395 -lp: 0.021444,-0.0149716,0.123357 -lp: 0.0214424,-0.014788,0.123343 -lp: 0.0214385,-0.0146046,0.12333 -lp: 0.0214362,-0.0144214,0.123316 -lp: 0.0214345,-0.0142382,0.123302 -lp: 0.0214317,-0.0140552,0.123289 -lp: 0.0214279,-0.0138723,0.123276 -lp: 0.0214224,-0.0136897,0.123264 -lp: 0.0214158,-0.0135071,0.123252 -lp: 0.0214141,-0.0133246,0.123238 -lp: 0.0214149,-0.0131421,0.123223 -lp: 0.021417,-0.0129597,0.123208 -lp: 0.0214135,-0.0127775,0.123195 -lp: 0.0214103,-0.0125955,0.123181 -lp: 0.0214061,-0.0124136,0.123169 -lp: 0.0214013,-0.0122319,0.123156 -lp: 0.0213975,-0.0120502,0.123143 -lp: 0.0214522,-0.0118672,0.123106 -lp: 0.0214372,-0.011686,0.123098 -lp: 0.0214524,-0.0115043,0.123077 -lp: 0.0214534,-0.0113229,0.123062 -lp: 0.0214357,-0.0111421,0.123055 -lp: 0.0215056,-0.0109595,0.123011 -lp: 0.0215097,-0.0107784,0.122994 -lp: 0.0215049,-0.0105977,0.122982 -lp: 0.0215054,-0.0104169,0.122967 -lp: 0.021424,-0.010238,0.122988 -lp: 0.0215513,-0.00789594,0.122747 -lp: 0.0215389,-0.00771682,0.122738 -lp: 0.0215178,-0.00753791,0.122732 -lp: 0.0215123,-0.00735884,0.12272 -lp: 0.021513,-0.00717975,0.122706 -lp: 0.0215084,-0.00700083,0.122694 -lp: 0.0215284,-0.00682164,0.122671 -lp: 0.0215131,-0.00664302,0.122663 -lp: 0.021505,-0.00646437,0.122652 -lp: 0.0215024,-0.00628573,0.122639 -lp: 0.0215015,-0.00610714,0.122625 -lp: 0.0215575,-0.00592794,0.122587 -lp: 0.0215543,-0.00574954,0.122574 -lp: 0.0215516,-0.00557121,0.122561 -lp: 0.0215493,-0.00539295,0.122548 -lp: 0.0215502,-0.00521473,0.122533 -lp: 0.0215528,-0.00503655,0.122518 -lp: 0.0215501,-0.0048585,0.122505 -lp: 0.0215452,-0.00468054,0.122493 -lp: 0.0215403,-0.00450264,0.122481 -lp: 0.0214911,-0.0043252,0.122487 -lp: 0.0214875,-0.00414739,0.122475 -lp: 0.021485,-0.00396964,0.122462 -lp: 0.0215312,-0.00379157,0.122428 -lp: 0.0215326,-0.00361393,0.122413 -lp: 0.0215309,-0.00343637,0.1224 -lp: 0.0215333,-0.00325884,0.122384 -lp: 0.0215341,-0.00308138,0.12237 -lp: 0.0215347,-0.00290398,0.122356 -lp: 0.0215922,-0.0027263,0.122317 -lp: 0.0215899,-0.00254905,0.122304 -lp: 0.0215919,-0.00237183,0.122289 -lp: 0.021591,-0.00219467,0.122275 -lp: 0.0215904,-0.00201757,0.122261 -lp: 0.0215815,-0.00184054,0.122251 -lp: 0.0215716,-0.00166357,0.122241 -lp: 0.0216504,-0.00148634,0.122193 -lp: 0.0215842,-0.00130964,0.122207 -lp: 0.0216225,0.00274859,0.121867 -lp: 0.0216153,0.00292472,0.121856 -lp: 0.0216177,0.00310077,0.121841 -lp: 0.0216119,0.00327685,0.12183 -lp: 0.021615,0.00345286,0.121814 -lp: 0.0216134,0.00362888,0.121801 -lp: 0.0216097,0.0038049,0.121788 -lp: 0.0216065,0.00398091,0.121776 -lp: 0.0216058,0.00415688,0.121762 -lp: 0.0216066,0.00433282,0.121748 -lp: 0.0216077,0.00450875,0.121733 -lp: 0.0216074,0.00468468,0.121719 -lp: 0.0216046,0.00486063,0.121706 -lp: 0.0216011,0.00503657,0.121694 -lp: 0.021599,0.00521249,0.121681 -lp: 0.0215975,0.0053884,0.121667 -lp: 0.0215977,0.00556429,0.121653 -lp: 0.0215984,0.00574017,0.121639 -lp: 0.0215993,0.00591604,0.121624 -lp: 0.0216033,0.00609187,0.121609 -lp: 0.0216059,0.00626771,0.121593 -lp: 0.0216062,0.00644358,0.121579 -lp: 0.0216055,0.00661946,0.121566 -lp: 0.0216028,0.00679537,0.121553 -lp: 0.0216015,0.00697126,0.121539 -lp: 0.0216005,0.00714716,0.121526 -lp: 0.0216032,0.007323,0.12151 -lp: 0.0216038,0.00749888,0.121496 -lp: 0.0216099,0.00767469,0.12148 -lp: 0.0216092,0.0078506,0.121466 -lp: 0.0216609,0.0080257,0.12143 -lp: 0.0216672,0.0082015,0.121413 -lp: 0.0216651,0.00837744,0.1214 -lp: 0.0216773,0.00855316,0.121381 -lp: 0.0216757,0.012958,0.12103 -lp: 0.0216765,0.0131346,0.121016 -lp: 0.0216708,0.0133113,0.121004 -lp: 0.0216714,0.013488,0.12099 -lp: 0.0216725,0.0136647,0.120975 -lp: 0.0216789,0.0138413,0.120958 -lp: 0.0217421,0.0140164,0.120918 -lp: 0.0216848,0.0141948,0.120928 -lp: 0.0216842,0.0143717,0.120914 -lp: 0.0216802,0.0145487,0.120901 -lp: 0.0216278,0.0147272,0.120909 -lp: 0.0216272,0.0149043,0.120895 -lp: 0.0216309,0.0150813,0.12088 -lp: 0.0216333,0.0152584,0.120864 -lp: 0.0216891,0.0154339,0.120827 -lp: 0.0216931,0.0156111,0.120811 -lp: 0.0217533,0.0157865,0.120772 -lp: 0.021753,0.0159639,0.120758 -lp: 0.0216416,0.0161448,0.12079 -lp: 0.021639,0.0163224,0.120777 -lp: 0.0216419,0.0164998,0.120762 -lp: 0.0216442,0.0166774,0.120747 -lp: 0.0216995,0.0168532,0.120709 -lp: 0.0216467,0.0170327,0.120717 -lp: 0.0217054,0.0172086,0.120678 -lp: 0.0217112,0.0173862,0.120662 -lp: 0.0217128,0.0175641,0.120647 -lp: 0.0217072,0.0177423,0.120635 -lp: 0.021701,0.0179205,0.120623 -lp: 0.0217075,0.0180984,0.120606 -lp: 0.0217035,0.0182768,0.120594 -lp: 0.0217051,0.018455,0.120579 -lp: 0.0217126,0.0186331,0.120562 -lp: 0.0217006,0.0227585,0.120238 -lp: 0.0216981,0.022939,0.120224 -lp: 0.0217015,0.0231195,0.120208 -lp: 0.0217044,0.0233,0.120193 -lp: 0.0217098,0.0234805,0.120176 -lp: 0.0217118,0.0236613,0.120161 -lp: 0.0217149,0.0238422,0.120145 -lp: 0.0217173,0.0240232,0.12013 -lp: 0.0217219,0.0242041,0.120113 -lp: 0.0217265,0.0243852,0.120097 -lp: 0.0217347,0.0245663,0.120079 -lp: 0.0217356,0.0247478,0.120064 -lp: 0.0217315,0.0249296,0.120051 -lp: 0.0217329,0.0251113,0.120036 -lp: 0.0217371,0.025293,0.12002 -lp: 0.0217396,0.0254749,0.120004 -lp: 0.021742,0.0256569,0.119989 -lp: 0.021746,0.025839,0.119973 -lp: 0.0217528,0.026021,0.119955 -lp: 0.021755,0.0262034,0.11994 -lp: 0.0217553,0.026386,0.119925 -lp: 0.0217572,0.0265686,0.11991 -lp: 0.0217614,0.0267513,0.119893 -lp: 0.0217696,0.0269339,0.119875 -lp: 0.0217752,0.0271167,0.119858 -lp: 0.0217789,0.0272998,0.119842 -lp: 0.0217751,0.0274834,0.119829 -lp: 0.021775,0.0276669,0.119814 -lp: 0.0217776,0.0278504,0.119799 -lp: 0.0217795,0.0280341,0.119783 -lp: 0.0217813,0.028218,0.119768 -lp: 0.0217308,0.0284049,0.119774 -lp: 0.0217915,0.0285857,0.119734 -lp: 0.0217994,0.0287697,0.119716 -lp: 0.0218056,0.0289538,0.119699 -lp: 0.0217557,0.0291413,0.119705 -lp: 0.0218163,0.0293227,0.119665 -lp: 0.0218168,0.0295076,0.11965 -lp: 0.0217665,0.0296956,0.119656 -lp: 0.0218218,0.0298776,0.119618 -lp: 0.0217625,0.0300665,0.119628 -lp: 0.0217638,0.030252,0.119613 -lp: 0.0217114,0.0304408,0.11962 -lp: 0.0217177,0.0306263,0.119602 -lp: 0.0217235,0.030812,0.119585 -lp: 0.021727,0.030998,0.119569 -lp: 0.021727,0.0311844,0.119554 -lp: 0.0217283,0.0313708,0.119539 -lp: 0.0217335,0.0315572,0.119522 -lp: 0.0217388,0.0317438,0.119504 -lp: 0.0217465,0.0319303,0.119486 -lp: 0.0217553,0.032117,0.119468 -lp: 0.0217638,0.0323038,0.119449 -lp: 0.0217645,0.0324913,0.119434 -lp: 0.0217597,0.0326793,0.119421 -lp: 0.0217593,0.0328672,0.119406 -lp: 0.0217654,0.0330549,0.119389 -lp: 0.0217717,0.0332427,0.119371 -lp: 0.0217769,0.0334308,0.119354 -lp: 0.0217795,0.0336192,0.119338 -lp: 0.0217752,0.0338082,0.119324 -lp: 0.0217811,0.0339968,0.119307 -lp: 0.0217939,0.0341851,0.119286 -lp: 0.0218039,0.0343737,0.119267 -lp: 0.0218088,0.0345629,0.11925 -lp: 0.0218096,0.0347525,0.119234 -lp: 0.0217555,0.0349461,0.119242 -lp: 0.0217553,0.0351362,0.119227 -lp: 0.021758,0.0353263,0.11921 -lp: 0.0217021,0.0355206,0.119218 -lp: 0.0217655,0.0357069,0.119177 -lp: 0.0217729,0.0358973,0.119159 -lp: 0.0217221,0.0360919,0.119164 -lp: 0.0217248,0.036283,0.119148 -lp: 0.0217291,0.0364742,0.119131 -lp: 0.0217323,0.0366657,0.119114 -lp: 0.0217299,0.0368578,0.1191 -lp: 0.0217366,0.0370494,0.119082 -lp: 0.0217496,0.0372408,0.119061 -lp: 0.0217566,0.0374328,0.119043 -lp: 0.0217619,0.0376252,0.119025 -lp: 0.0217658,0.0378179,0.119008 -lp: 0.0217718,0.0380106,0.11899 -lp: 0.0217724,0.038204,0.118975 -lp: 0.0217693,0.0383978,0.11896 -lp: 0.021773,0.0385914,0.118943 -lp: 0.021785,0.0387846,0.118923 -lp: 0.0217939,0.0389782,0.118904 -lp: 0.0218054,0.0391718,0.118883 -lp: 0.0218128,0.039366,0.118865 -lp: 0.0218187,0.0395605,0.118847 -lp: 0.0218254,0.0397552,0.118828 -lp: 0.0218297,0.0399503,0.118811 -lp: 0.021832,0.0401458,0.118795 -lp: 0.0218343,0.0403415,0.118778 -lp: 0.0218365,0.0405375,0.118761 -lp: 0.0217873,0.0407377,0.118766 -lp: 0.0218509,0.0409293,0.118724 -lp: 0.0217912,0.0411309,0.118733 -lp: 0.0218023,0.0413272,0.118713 -lp: 0.0218159,0.0415235,0.118691 -lp: 0.0218248,0.0417204,0.118672 -lp: 0.0218856,0.0419134,0.118631 -lp: 0.0217604,0.0421216,0.118667 -lp: 0.0217593,0.0423201,0.118652 -lp: 0.0217671,0.0425181,0.118633 -lp: 0.0217783,0.0427161,0.118612 -lp: 0.0217871,0.0429146,0.118593 -lp: 0.0217935,0.0431135,0.118574 -lp: 0.0217964,0.043313,0.118557 -lp: 0.0218026,0.0435125,0.118538 -lp: 0.0218079,0.0437123,0.11852 -lp: 0.0218136,0.0439123,0.118502 -lp: 0.0218231,0.0441123,0.118482 -lp: 0.0218343,0.0443124,0.118461 -lp: 0.0218423,0.0445131,0.118442 -lp: 0.021846,0.0447144,0.118424 -lp: 0.0217899,0.0449211,0.118431 -lp: 0.0217957,0.0451229,0.118413 -lp: 0.0218073,0.0453243,0.118392 -lp: 0.0218198,0.045526,0.11837 -lp: 0.0218289,0.0457283,0.11835 -lp: 0.0218349,0.0459311,0.118332 -lp: 0.0217659,0.0461409,0.118344 -lp: 0.0217674,0.0463447,0.118327 -lp: 0.0217773,0.0465481,0.118307 -lp: 0.0217892,0.0467516,0.118285 -lp: 0.0218002,0.0469555,0.118265 -lp: 0.0218097,0.0471598,0.118244 -lp: 0.0218145,0.0473649,0.118226 -lp: 0.0218199,0.0475702,0.118207 -lp: 0.021829,0.0477755,0.118187 -lp: 0.0218377,0.0479811,0.118167 -lp: 0.0218464,0.048187,0.118147 -lp: 0.0218463,0.0483941,0.11813 -lp: 0.0218563,0.0486005,0.11811 -lp: 0.0218708,0.0488068,0.118087 -lp: 0.0218808,0.0490139,0.118066 -lp: 0.0218858,0.0492218,0.118047 -lp: 0.0218878,0.0494303,0.11803 -lp: 0.0218902,0.049639,0.118012 -lp: 0.0219016,0.0498473,0.117991 -lp: 0.0219158,0.0500556,0.117968 -lp: 0.0219209,0.0502651,0.117949 -lp: 0.0219249,0.0504751,0.117931 -lp: 0.0219348,0.0506848,0.11791 -lp: 0.0218849,0.0509007,0.117914 -lp: 0.0218951,0.0511111,0.117893 -lp: 0.0218342,0.0513289,0.117901 -lp: 0.0218301,0.0515414,0.117886 -lp: 0.0218314,0.0517538,0.117868 -lp: 0.0218401,0.0519658,0.117848 -lp: 0.0218511,0.0521779,0.117826 -lp: 0.0218709,0.0523895,0.117801 -lp: 0.0218826,0.0526023,0.117779 -lp: 0.0218911,0.0528158,0.117758 -lp: 0.0218988,0.0530297,0.117738 -lp: 0.0219059,0.053244,0.117718 -lp: 0.0219166,0.0534584,0.117696 -lp: 0.0219259,0.0536733,0.117675 -lp: 0.021936,0.0538884,0.117654 -lp: 0.0219465,0.0541039,0.117632 -lp: 0.0219581,0.0543197,0.11761 -lp: 0.0218998,0.0545431,0.117617 -lp: 0.0218287,0.0547683,0.117629 -lp: 0.0218326,0.0549861,0.11761 -lp: 0.0218419,0.0552038,0.117589 -lp: 0.0218503,0.0554219,0.117568 -lp: 0.0218712,0.0556391,0.117542 -lp: 0.0218833,0.0558577,0.117519 -lp: 0.0218931,0.0560769,0.117497 -lp: 0.021901,0.0562967,0.117477 -lp: 0.0219113,0.0565166,0.117455 -lp: 0.0219226,0.0567369,0.117432 -lp: 0.021937,0.0569572,0.117409 -lp: 0.0219495,0.0571782,0.117386 -lp: 0.0219601,0.0573998,0.117364 -lp: 0.0219669,0.0576223,0.117343 -lp: 0.0219759,0.0578449,0.117321 -lp: 0.0219829,0.0580682,0.117301 -lp: 0.0218527,0.0583071,0.117337 -lp: 0.0218576,0.0585316,0.117317 -lp: 0.0219296,0.058749,0.117269 -lp: 0.0219432,0.0589734,0.117245 -lp: 0.0218201,0.0592135,0.117278 -lp: 0.0218951,0.0594319,0.117229 -lp: 0.0219149,0.059657,0.117202 -lp: 0.0219283,0.0598832,0.117179 -lp: 0.0219347,0.0601107,0.117158 -lp: 0.0219482,0.0603378,0.117134 -lp: 0.0219668,0.0605648,0.117108 -lp: 0.0219792,0.0607931,0.117085 -lp: 0.0219827,0.0610228,0.117065 -lp: 0.0218426,0.0612696,0.117104 -lp: 0.0218408,0.0615009,0.117087 -lp: 0.0218509,0.0617314,0.117064 -lp: 0.021873,0.061961,0.117036 -lp: 0.0218872,0.0621919,0.117012 -lp: 0.0218955,0.0624241,0.11699 -lp: 0.0219098,0.062656,0.116965 -lp: 0.0219212,0.0628888,0.116942 -lp: 0.0219356,0.0631218,0.116917 -lp: 0.0219486,0.0633554,0.116893 -lp: 0.0219622,0.0635895,0.116869 -lp: 0.0219645,0.0638254,0.116849 -lp: 0.0218996,0.06407,0.116857 -lp: 0.0219138,0.0643056,0.116832 -lp: 0.0219298,0.0645415,0.116806 -lp: 0.0220227,0.0647686,0.116749 -lp: 0.0220406,0.0650053,0.116723 -lp: 0.0219759,0.0652527,0.11673 -lp: 0.0219159,0.0655002,0.116736 -lp: 0.0219182,0.0657405,0.116716 -lp: 0.0219275,0.0659805,0.116693 -lp: 0.0219442,0.0662202,0.116666 -lp: 0.0219587,0.0664607,0.116641 -lp: 0.0219,0.066711,0.116646 -lp: 0.0218334,0.0669629,0.116654 -lp: 0.0218549,0.0672043,0.116626 -lp: 0.0219355,0.0674388,0.116573 -lp: 0.0219507,0.0676821,0.116547 -lp: 0.0218969,0.0679349,0.11655 -lp: 0.0219027,0.0681806,0.116527 -lp: 0.0219063,0.0684272,0.116506 -lp: 0.0219226,0.0686729,0.11648 -lp: 0.0219422,0.0689186,0.116452 -lp: 0.0219647,0.0691647,0.116423 -lp: 0.0219746,0.0694129,0.116399 -lp: 0.0219107,0.0696715,0.116405 -lp: 0.0219207,0.069921,0.116381 -lp: 0.0219283,0.0701715,0.116358 -lp: 0.0219358,0.0704226,0.116335 -lp: 0.021962,0.0706719,0.116304 -lp: 0.0219839,0.0709225,0.116274 -lp: 0.022014,0.0711725,0.116242 -lp: 0.0220194,0.0714265,0.116219 -lp: 0.0220214,0.0716817,0.116198 -lp: 0.0219609,0.0719459,0.116202 -lp: 0.0219785,0.0722003,0.116175 -lp: 0.0220614,0.0724466,0.11612 -lp: 0.022078,0.0727025,0.116093 -lp: 0.0220222,0.0729689,0.116095 -lp: 0.0219627,0.0732366,0.116099 -lp: 0.0219679,0.0734962,0.116076 -lp: 0.0219088,0.0737653,0.116079 -lp: 0.0219282,0.0740244,0.11605 -lp: 0.0219436,0.0742847,0.116023 -lp: 0.0219526,0.0745467,0.115998 -lp: 0.0219672,0.0748086,0.115971 -lp: 0.0219794,0.0750715,0.115945 -lp: 0.0220004,0.075334,0.115915 -lp: 0.0220169,0.0755978,0.115887 -lp: 0.0220182,0.0758645,0.115865 -lp: 0.022037,0.0761295,0.115836 -lp: 0.0220553,0.0763954,0.115807 -lp: 0.022078,0.0766613,0.115777 -lp: 0.022086,0.0769302,0.115752 -lp: 0.0220357,0.0772082,0.115751 -lp: 0.0220426,0.0774788,0.115726 -lp: 0.0219859,0.0777594,0.115728 -lp: 0.0219918,0.0780318,0.115704 -lp: 0.0220047,0.0783039,0.115677 -lp: 0.0219374,0.0785887,0.115682 -lp: 0.0219489,0.0788627,0.115656 -lp: 0.0219094,0.0791451,0.11565 -lp: 0.0219331,0.0794191,0.115618 -lp: 0.021945,0.0796956,0.115591 -lp: 0.0220438,0.07996,0.115528 -lp: 0.0221344,0.0802264,0.115468 -lp: 0.0220979,0.0805126,0.115461 -lp: 0.0221191,0.0807911,0.11543 -lp: 0.0221334,0.0810715,0.115401 -lp: 0.0221512,0.0813523,0.115371 -lp: 0.0221747,0.081633,0.115339 -lp: 0.0223662,0.0818894,0.115238 -lp: 0.022287,0.0821874,0.115247 -lp: 0.0205433,-0.0502107,0.153932 -lp: 0.0205302,-0.0499468,0.153907 -lp: 0.0205204,-0.049683,0.15388 -lp: 0.0205112,-0.0494196,0.153853 -lp: 0.0205022,-0.0491567,0.153826 -lp: 0.0204982,-0.0488936,0.153797 -lp: 0.0205719,-0.0486218,0.153728 -lp: 0.0205699,-0.0483594,0.153697 -lp: 0.02056,-0.0480985,0.153671 -lp: 0.0205479,-0.0478382,0.153646 -lp: 0.0205383,-0.0475781,0.153619 -lp: 0.0206089,-0.0473092,0.153552 -lp: 0.0206083,-0.047049,0.153521 -lp: 0.0205987,-0.0467902,0.153495 -lp: 0.0205922,-0.0465315,0.153467 -lp: 0.0205826,-0.0462736,0.153441 -lp: 0.0206587,-0.0460066,0.153371 -lp: 0.0205776,-0.0457575,0.153382 -lp: 0.0206491,-0.045492,0.153315 -lp: 0.02071,-0.0452281,0.153253 -lp: 0.0206988,-0.0449726,0.153228 -lp: 0.020683,-0.0447179,0.153205 -lp: 0.0206025,-0.0444706,0.153215 -lp: 0.0205916,-0.0442162,0.15319 -lp: 0.0206666,-0.0439532,0.153122 -lp: 0.0206683,-0.0436983,0.15309 -lp: 0.0206612,-0.0434447,0.153063 -lp: 0.0206553,-0.0431915,0.153036 -lp: 0.0206465,-0.0429389,0.15301 -lp: 0.0206403,-0.0426865,0.152983 -lp: 0.0206392,-0.0424339,0.152953 -lp: 0.020637,-0.0421818,0.152924 -lp: 0.0207009,-0.0419235,0.152861 -lp: 0.020688,-0.0416733,0.152838 -lp: 0.0206742,-0.0414236,0.152815 -lp: 0.020595,-0.0411807,0.152825 -lp: 0.0206573,-0.0409242,0.152763 -lp: 0.0207356,-0.0406666,0.152694 -lp: 0.0207301,-0.0404176,0.152666 -lp: 0.0207141,-0.0401699,0.152645 -lp: 0.0207035,-0.0399222,0.15262 -lp: 0.0206997,-0.0396741,0.152592 -lp: 0.0206932,-0.0394266,0.152566 -lp: 0.0206825,-0.0391799,0.152542 -lp: 0.0206753,-0.0389332,0.152516 -lp: 0.0206677,-0.038687,0.15249 -lp: 0.0206681,-0.0384403,0.15246 -lp: 0.0206655,-0.0381942,0.152432 -lp: 0.0207411,-0.0379414,0.152364 -lp: 0.0207338,-0.0376965,0.152338 -lp: 0.0207246,-0.0374522,0.152314 -lp: 0.0207116,-0.0372085,0.152291 -lp: 0.0207011,-0.0369649,0.152267 -lp: 0.0206912,-0.0367216,0.152243 -lp: 0.0207508,-0.0364725,0.152183 -lp: 0.0207481,-0.0362293,0.152156 -lp: 0.0207486,-0.0359861,0.152126 -lp: 0.020742,-0.0357438,0.1521 -lp: 0.0207313,-0.0355023,0.152077 -lp: 0.0207208,-0.035261,0.152053 -lp: 0.0207122,-0.0350199,0.152028 -lp: 0.0207103,-0.0347785,0.152 -lp: 0.0207042,-0.0345378,0.151975 -lp: 0.0207009,-0.0342972,0.151947 -lp: 0.0206964,-0.034057,0.151921 -lp: 0.0206886,-0.0338174,0.151896 -lp: 0.020686,-0.0335777,0.151868 -lp: 0.0206846,-0.0333382,0.15184 -lp: 0.0206749,-0.0330996,0.151817 -lp: 0.020665,-0.0328614,0.151793 -lp: 0.0206596,-0.0326231,0.151767 -lp: 0.0207996,-0.0323738,0.151668 -lp: 0.0207918,-0.0321363,0.151643 -lp: 0.0207142,-0.0319045,0.151654 -lp: 0.0207052,-0.0316677,0.15163 -lp: 0.0207721,-0.0314254,0.151568 -lp: 0.0207669,-0.0311889,0.151542 -lp: 0.0207654,-0.0309525,0.151515 -lp: 0.0207602,-0.0307165,0.151489 -lp: 0.0207546,-0.0304809,0.151463 -lp: 0.0207454,-0.0302458,0.15144 -lp: 0.0207392,-0.0300108,0.151415 -lp: 0.0207337,-0.029776,0.151389 -lp: 0.02073,-0.0295414,0.151363 -lp: 0.0207209,-0.0293074,0.151339 -lp: 0.0207139,-0.0290735,0.151315 -lp: 0.0207081,-0.0288398,0.15129 -lp: 0.020775,-0.0286014,0.151228 -lp: 0.0207677,-0.0283684,0.151204 -lp: 0.0207646,-0.0281353,0.151177 -lp: 0.0207567,-0.0279028,0.151153 -lp: 0.0207481,-0.0276707,0.15113 -lp: 0.0207422,-0.0274386,0.151105 -lp: 0.020804,-0.0272023,0.151046 -lp: 0.0208017,-0.0269705,0.151019 -lp: 0.0208006,-0.0267389,0.150992 -lp: 0.0207975,-0.0265077,0.150966 -lp: 0.0207903,-0.0262769,0.150942 -lp: 0.0207832,-0.0260465,0.150918 -lp: 0.020778,-0.0258161,0.150893 -lp: 0.020772,-0.025586,0.150868 -lp: 0.0207696,-0.0253559,0.150842 -lp: 0.0207736,-0.0251257,0.150812 -lp: 0.0207765,-0.0248958,0.150783 -lp: 0.0207707,-0.0246667,0.150759 -lp: 0.0207668,-0.0244377,0.150733 -lp: 0.020763,-0.0242089,0.150708 -lp: 0.0207579,-0.0239804,0.150683 -lp: 0.0207538,-0.0237521,0.150657 -lp: 0.0208132,-0.0235204,0.1506 -lp: 0.0208083,-0.0232926,0.150575 -lp: 0.0208042,-0.023065,0.15055 -lp: 0.0208,-0.0228376,0.150525 -lp: 0.020866,-0.0226066,0.150465 -lp: 0.0208614,-0.0223797,0.15044 -lp: 0.0208552,-0.0221532,0.150416 -lp: 0.0208514,-0.0219266,0.15039 -lp: 0.0208482,-0.0217003,0.150365 -lp: 0.0208464,-0.0214741,0.150339 -lp: 0.0208434,-0.0212482,0.150313 -lp: 0.0208437,-0.0210223,0.150286 -lp: 0.0208382,-0.020797,0.150262 -lp: 0.0208362,-0.0205716,0.150236 -lp: 0.0208339,-0.0203465,0.15021 -lp: 0.0208271,-0.0201218,0.150186 -lp: 0.0208171,-0.0198974,0.150164 -lp: 0.0208085,-0.0196732,0.150142 -lp: 0.020801,-0.0194491,0.150118 -lp: 0.0208036,-0.0192247,0.15009 -lp: 0.0209447,-0.0189942,0.149993 -lp: 0.0209461,-0.0187704,0.149965 -lp: 0.0209435,-0.0185469,0.14994 -lp: 0.0209366,-0.0183238,0.149917 -lp: 0.0209232,-0.0181012,0.149897 -lp: 0.0209132,-0.0178786,0.149875 -lp: 0.0209103,-0.0176558,0.14985 -lp: 0.020907,-0.0174333,0.149825 -lp: 0.02091,-0.0172107,0.149796 -lp: 0.0209093,-0.0169884,0.14977 -lp: 0.0209052,-0.0167665,0.149746 -lp: 0.0209045,-0.0165446,0.149719 -lp: 0.0209034,-0.0163228,0.149693 -lp: 0.0208989,-0.0161014,0.149669 -lp: 0.0208922,-0.0158802,0.149646 -lp: 0.0208853,-0.0156592,0.149623 -lp: 0.0208788,-0.0154384,0.149599 -lp: 0.0208759,-0.0152176,0.149574 -lp: 0.0208761,-0.0149968,0.149548 -lp: 0.0208784,-0.0147762,0.14952 -lp: 0.0208804,-0.0145557,0.149493 -lp: 0.0208751,-0.0143356,0.149469 -lp: 0.0208687,-0.0141157,0.149446 -lp: 0.0208615,-0.013896,0.149423 -lp: 0.0208591,-0.0136763,0.149398 -lp: 0.0209984,-0.0134522,0.149302 -lp: 0.0210019,-0.0132327,0.149274 -lp: 0.0209989,-0.0130136,0.149249 -lp: 0.0209928,-0.0127947,0.149226 -lp: 0.020986,-0.0125759,0.149203 -lp: 0.0209857,-0.0123571,0.149177 -lp: 0.0209827,-0.0121386,0.149153 -lp: 0.0209803,-0.0119202,0.149128 -lp: 0.0209824,-0.0117017,0.1491 -lp: 0.0209807,-0.0114836,0.149075 -lp: 0.0209799,-0.0112655,0.149049 -lp: 0.0209737,-0.0110478,0.149026 -lp: 0.0209709,-0.0108301,0.149002 -lp: 0.0209667,-0.0106125,0.148978 -lp: 0.0210404,-0.0103932,0.148915 -lp: 0.021044,-0.0101757,0.148887 -lp: 0.02104,-0.00995863,0.148863 -lp: 0.0210355,-0.00974166,0.148839 -lp: 0.0210297,-0.00952485,0.148816 -lp: 0.021027,-0.00930809,0.148792 -lp: 0.0210241,-0.00909146,0.148767 -lp: 0.0210144,-0.0088751,0.148746 -lp: 0.0210069,-0.00865881,0.148724 -lp: 0.020996,-0.00844271,0.148703 -lp: 0.0208187,-0.00822999,0.148765 -lp: 0.0208072,-0.00801404,0.148745 -lp: 0.0211167,-0.00435301,0.148153 -lp: 0.0211196,-0.00413892,0.148126 -lp: 0.0211055,-0.00392508,0.148108 -lp: 0.0210985,-0.00371126,0.148086 -lp: 0.0210302,-0.00349805,0.148094 -lp: 0.0210262,-0.00328435,0.14807 -lp: 0.0210261,-0.0030707,0.148044 -lp: 0.0210248,-0.00285716,0.14802 -lp: 0.0210885,-0.00264327,0.147962 -lp: 0.0210918,-0.0024299,0.147935 -lp: 0.0210853,-0.00221668,0.147913 -lp: 0.0210811,-0.00200351,0.147889 -lp: 0.0210105,-0.00179073,0.147899 -lp: 0.0210707,-0.00157743,0.147843 -lp: 0.0210699,-0.00136449,0.147818 -lp: 0.0210665,-0.00115163,0.147795 -lp: 0.021066,-0.000938842,0.147769 -lp: 0.0211334,-0.000725995,0.147711 -lp: 0.0211306,-0.000513391,0.147686 -lp: 0.0210513,-0.000300931,0.1477 -lp: 0.021049,-8.84293e-05,0.147676 -lp: 0.02112,0.000124,0.147615 -lp: 0.0211238,0.000336325,0.147588 -lp: 0.0211207,0.000548586,0.147564 -lp: 0.0210482,0.000760891,0.147574 -lp: 0.0210481,0.000973053,0.147549 -lp: 0.0211016,0.00118501,0.147497 -lp: 0.0210329,0.00139723,0.147506 -lp: 0.0211067,0.00160895,0.147444 -lp: 0.0211569,0.00562517,0.146938 -lp: 0.0211563,0.00583612,0.146913 -lp: 0.0211584,0.00604701,0.146886 -lp: 0.0211658,0.00625778,0.146858 -lp: 0.0211631,0.00646866,0.146834 -lp: 0.0212275,0.00667848,0.146777 -lp: 0.0212278,0.00688923,0.146751 -lp: 0.0212275,0.00709996,0.146726 -lp: 0.0211629,0.00731174,0.146733 -lp: 0.0211604,0.00752248,0.146709 -lp: 0.0211598,0.00773317,0.146684 -lp: 0.0211598,0.00794382,0.146658 -lp: 0.0212252,0.00815322,0.146601 -lp: 0.0212306,0.00836369,0.146573 -lp: 0.0212341,0.00857417,0.146546 -lp: 0.0212316,0.00878476,0.146522 -lp: 0.0212284,0.00899534,0.146499 -lp: 0.0212251,0.00920591,0.146475 -lp: 0.0212257,0.00941639,0.146449 -lp: 0.0212265,0.00962684,0.146424 -lp: 0.021225,0.00983734,0.146399 -lp: 0.0212229,0.0100478,0.146375 -lp: 0.0212169,0.0102584,0.146353 -lp: 0.0212128,0.010469,0.14633 -lp: 0.0211369,0.0106813,0.146342 -lp: 0.0212089,0.0108899,0.146281 -lp: 0.0211446,0.011102,0.146287 -lp: 0.0213206,0.0113078,0.146176 -lp: 0.0213132,0.0115184,0.146154 -lp: 0.0212282,0.0155196,0.145717 -lp: 0.0213065,0.0157273,0.145653 -lp: 0.021297,0.0159383,0.145633 -lp: 0.0212261,0.0161516,0.145642 -lp: 0.0212284,0.0163622,0.145616 -lp: 0.0212342,0.0165727,0.145588 -lp: 0.0212288,0.0167837,0.145565 -lp: 0.0212261,0.0169946,0.145541 -lp: 0.0212255,0.0172054,0.145516 -lp: 0.0212278,0.0174162,0.14549 -lp: 0.021228,0.0176271,0.145464 -lp: 0.0212252,0.0178381,0.14544 -lp: 0.0212246,0.0180491,0.145415 -lp: 0.0212308,0.0182598,0.145387 -lp: 0.021232,0.0184708,0.145361 -lp: 0.0212319,0.0186819,0.145336 -lp: 0.0212321,0.018893,0.145311 -lp: 0.02123,0.0191042,0.145286 -lp: 0.0212281,0.0193155,0.145262 -lp: 0.0212254,0.0195269,0.145238 -lp: 0.0212274,0.0197381,0.145212 -lp: 0.0212303,0.0199493,0.145185 -lp: 0.0212378,0.0201604,0.145156 -lp: 0.0212375,0.0203719,0.145131 -lp: 0.0213067,0.0205801,0.145072 -lp: 0.0213111,0.0207914,0.145044 -lp: 0.0212238,0.0210072,0.145061 -lp: 0.0212246,0.0212188,0.145035 -lp: 0.0212352,0.0252525,0.144547 -lp: 0.0213173,0.0254608,0.144481 -lp: 0.0213276,0.0256733,0.144451 -lp: 0.0213344,0.0258861,0.144422 -lp: 0.0212716,0.0261032,0.144427 -lp: 0.0212711,0.0263166,0.144402 -lp: 0.0212686,0.0265303,0.144377 -lp: 0.0212698,0.0267438,0.144351 -lp: 0.0212716,0.0269573,0.144325 -lp: 0.0212678,0.0271714,0.144301 -lp: 0.0212726,0.0273849,0.144273 -lp: 0.0212834,0.0275982,0.144242 -lp: 0.0212853,0.0278122,0.144215 -lp: 0.0212797,0.0280267,0.144192 -lp: 0.021271,0.0282416,0.144171 -lp: 0.0212689,0.0284561,0.144146 -lp: 0.0212694,0.0286705,0.14412 -lp: 0.0212728,0.0288849,0.144093 -lp: 0.0212857,0.0290987,0.144061 -lp: 0.0212963,0.0293128,0.14403 -lp: 0.0212983,0.0295276,0.144003 -lp: 0.0212888,0.0297432,0.143982 -lp: 0.0212827,0.0299588,0.143959 -lp: 0.0212833,0.030174,0.143933 -lp: 0.0212857,0.0303892,0.143906 -lp: 0.0212969,0.0306039,0.143875 -lp: 0.0213001,0.0308193,0.143848 -lp: 0.0212977,0.0310352,0.143823 -lp: 0.0213004,0.0312508,0.143796 -lp: 0.0213028,0.0314666,0.143769 -lp: 0.021308,0.0316823,0.14374 -lp: 0.021301,0.031899,0.143718 -lp: 0.0213039,0.0321151,0.143691 -lp: 0.0213092,0.0323312,0.143662 -lp: 0.0213121,0.0325476,0.143635 -lp: 0.0213123,0.0327643,0.143609 -lp: 0.0213186,0.0329807,0.14358 -lp: 0.021324,0.0331973,0.143551 -lp: 0.0213277,0.0334141,0.143523 -lp: 0.0213251,0.0336316,0.143498 -lp: 0.0213255,0.033849,0.143472 -lp: 0.0213297,0.0340662,0.143444 -lp: 0.021333,0.0342836,0.143416 -lp: 0.0213389,0.034501,0.143387 -lp: 0.0213413,0.0347188,0.14336 -lp: 0.0213401,0.034937,0.143334 -lp: 0.0213396,0.0351553,0.143309 -lp: 0.0213415,0.0353736,0.143281 -lp: 0.0213444,0.0355919,0.143254 -lp: 0.0213541,0.0358098,0.143223 -lp: 0.0213587,0.0360283,0.143194 -lp: 0.0213619,0.0362471,0.143167 -lp: 0.0213632,0.0364662,0.14314 -lp: 0.0213656,0.0366853,0.143112 -lp: 0.0213698,0.0369045,0.143084 -lp: 0.0215495,0.0529923,0.141067 -lp: 0.0214804,0.0532365,0.141072 -lp: 0.0214863,0.053472,0.141041 -lp: 0.0215685,0.0536984,0.140973 -lp: 0.02158,0.0539338,0.140939 -lp: 0.0215886,0.0541698,0.140907 -lp: 0.0215956,0.0544063,0.140875 -lp: 0.021522,0.0546531,0.140882 -lp: 0.0215209,0.0548913,0.140854 -lp: 0.0214432,0.0551394,0.140862 -lp: 0.021447,0.0553777,0.140832 -lp: 0.0214549,0.0556157,0.140799 -lp: 0.0214638,0.055854,0.140767 -lp: 0.0214798,0.0560916,0.14073 -lp: 0.021488,0.0563306,0.140697 -lp: 0.0214997,0.0565694,0.140663 -lp: 0.0215079,0.056809,0.14063 -lp: 0.0215106,0.0570497,0.1406 -lp: 0.0215035,0.057292,0.140575 -lp: 0.0215119,0.0575326,0.140542 -lp: 0.0215233,0.0577731,0.140507 -lp: 0.0215293,0.0580147,0.140475 -lp: 0.0215269,0.0582578,0.140447 -lp: 0.0215251,0.0585011,0.140419 -lp: 0.0215331,0.0587435,0.140386 -lp: 0.0215396,0.0589864,0.140354 -lp: 0.0214755,0.0592392,0.140355 -lp: 0.0215653,0.0594716,0.140283 -lp: 0.0215749,0.0597152,0.140249 -lp: 0.0215753,0.0599604,0.140219 -lp: 0.0215796,0.0602054,0.140188 -lp: 0.0215062,0.0604615,0.140193 -lp: 0.0216028,0.0606946,0.140118 -lp: 0.0216076,0.0609407,0.140086 -lp: 0.0215276,0.0611989,0.140095 -lp: 0.0215419,0.0614445,0.140058 -lp: 0.0215593,0.06169,0.14002 -lp: 0.0215729,0.0619364,0.139984 -lp: 0.0215771,0.0621845,0.139952 -lp: 0.0215808,0.0624331,0.13992 -lp: 0.0215841,0.0626821,0.139889 -lp: 0.0216719,0.0629195,0.139817 -lp: 0.021518,0.0631918,0.13986 -lp: 0.0215232,0.0634419,0.139828 -lp: 0.0215269,0.0636925,0.139796 -lp: 0.0215369,0.0639426,0.139761 -lp: 0.0215517,0.0641925,0.139724 -lp: 0.0216387,0.0644322,0.139652 -lp: 0.0215684,0.0646953,0.139655 -lp: 0.0215747,0.0649476,0.139622 -lp: 0.0215842,0.0651999,0.139587 -lp: 0.0215199,0.0654636,0.139587 -lp: 0.0215998,0.0657063,0.139519 -lp: 0.021608,0.0659601,0.139484 -lp: 0.0215262,0.0662278,0.139493 -lp: 0.0215334,0.0664826,0.139458 -lp: 0.0215539,0.0667359,0.139418 -lp: 0.0215679,0.0669906,0.139381 -lp: 0.0216467,0.0672359,0.139312 -lp: 0.0216576,0.0674919,0.139276 -lp: 0.0215891,0.0677606,0.139278 -lp: 0.02152,0.0680298,0.13928 -lp: 0.0215228,0.0682886,0.139247 -lp: 0.0215324,0.0685467,0.139212 -lp: 0.0216168,0.0687937,0.13914 -lp: 0.0216315,0.069052,0.139102 -lp: 0.0216397,0.0693117,0.139067 -lp: 0.0215698,0.0695842,0.139069 -lp: 0.0215821,0.0698443,0.139032 -lp: 0.0215921,0.0701053,0.138995 -lp: 0.0216037,0.0703664,0.138958 -lp: 0.021617,0.0706278,0.13892 -lp: 0.0216199,0.0708914,0.138887 -lp: 0.0216281,0.0711546,0.138852 -lp: 0.0216209,0.0714208,0.138823 -lp: 0.0216184,0.0716868,0.138793 -lp: 0.0216303,0.0719509,0.138755 -lp: 0.0216566,0.0722133,0.138711 -lp: 0.021678,0.0724769,0.138669 -lp: 0.0216048,0.0727566,0.138671 -lp: 0.0216127,0.0730235,0.138635 -lp: 0.0216233,0.0732905,0.138598 -lp: 0.0217226,0.0735434,0.138519 -lp: 0.0217309,0.0738118,0.138483 -lp: 0.0217435,0.07408,0.138444 -lp: 0.0217488,0.0743501,0.138409 -lp: 0.0215908,0.0746481,0.138451 -lp: 0.0215873,0.0749208,0.138421 -lp: 0.0215909,0.0751929,0.138386 -lp: 0.0216077,0.0754633,0.138345 -lp: 0.0216252,0.0757341,0.138304 -lp: 0.0216306,0.0760076,0.138269 -lp: 0.0216387,0.0762812,0.138232 -lp: 0.0216542,0.0765541,0.138192 -lp: 0.0216002,0.0768396,0.138184 -lp: 0.0216902,0.0771008,0.138108 -lp: 0.0217007,0.0773763,0.13807 -lp: 0.0217084,0.0776529,0.138033 -lp: 0.0216447,0.0779427,0.13803 -lp: 0.0216567,0.0782198,0.137991 -lp: 0.0216399,0.0785026,0.137965 -lp: 0.0216445,0.0787822,0.13793 -lp: 0.0215779,0.0790752,0.137927 -lp: 0.0215961,0.0793537,0.137885 -lp: 0.0216149,0.0796328,0.137842 -lp: 0.0216305,0.079913,0.137801 -lp: 0.0216321,0.0801965,0.137766 -lp: 0.0216438,0.0804787,0.137727 -lp: 0.0216581,0.0807611,0.137686 -lp: 0.021663,0.0810459,0.137649 -lp: 0.0216664,0.0813316,0.137613 -lp: 0.0216905,0.0816142,0.137567 -lp: 0.0217062,0.081899,0.137526 -lp: 0.0217239,0.0821841,0.137483 -lp: 0.0217419,0.0824699,0.13744 -lp: 0.0217538,0.0827574,0.137399 -lp: 0.0217725,0.0830443,0.137356 -lp: 0.0217787,0.0833343,0.137318 -lp: 0.0216961,0.0836416,0.137322 -lp: 0.0217062,0.0839323,0.137282 -lp: 0.021815,0.0842052,0.137196 -lp: 0.0217431,0.0845127,0.137194 -lp: 0.0217468,0.0848068,0.137157 -lp: 0.0216607,0.0851187,0.137162 -lp: 0.0216517,0.0854167,0.137131 -lp: 0.021588,0.085726,0.137125 -lp: 0.021612,0.0860193,0.137078 -lp: 0.0216258,0.0863152,0.137036 -lp: 0.0217203,0.0865963,0.136956 -lp: 0.0217424,0.0868921,0.136909 -lp: 0.0216766,0.0872058,0.136904 -lp: 0.021691,0.0875047,0.136861 -lp: 0.0216068,0.0878238,0.136865 -lp: 0.0216047,0.0881275,0.136829 -lp: 0.0215248,0.0884475,0.13683 -lp: 0.0216357,0.0887305,0.136742 -lp: 0.0217542,0.0890127,0.136649 -lp: 0.0217859,0.0893129,0.136598 -lp: 0.0217798,0.0896215,0.136564 -lp: 0.0216901,0.0899477,0.136569 -lp: 0.0217236,0.09025,0.136516 -lp: 0.0217455,0.0905555,0.136469 -lp: 0.0217627,0.0908628,0.136423 -lp: 0.0217802,0.0911709,0.136378 -lp: 0.0217796,0.0914835,0.136341 -lp: 0.0217932,0.0917941,0.136297 -lp: 0.0217967,0.0921076,0.136257 -lp: 0.0217219,0.0924381,0.136255 -lp: 0.0217492,0.0927486,0.136204 -lp: 0.0217727,0.0930607,0.136155 -lp: 0.0217816,0.0933768,0.136113 -lp: 0.0218888,0.0936733,0.136024 -lp: 0.0218174,0.0940078,0.13602 -lp: 0.0218221,0.0943275,0.135979 -lp: 0.0218421,0.0946449,0.135931 -lp: 0.0218621,0.0949632,0.135883 -lp: 0.0217913,0.0953017,0.135877 -lp: 0.0217909,0.0956263,0.135839 -lp: 0.0215854,0.0959957,0.135896 -lp: 0.0218472,0.0962662,0.135734 -lp: 0.0218499,0.0965931,0.135694 -lp: 0.0219847,0.0968926,0.135591 -lp: 0.0220042,0.0972178,0.135543 diff --git a/blaser_ros/cfg/LaserDetector.cfg b/blaser_ros/cfg/LaserDetector.cfg deleted file mode 100755 index c5c916c..0000000 --- a/blaser_ros/cfg/LaserDetector.cfg +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/env python -PACKAGE = "blaser_ros" - -from dynamic_reconfigure.parameter_generator_catkin import * - -gen = ParameterGenerator() - -gen.add("brightness_min", int_t, 0, "Lower threshold of laser brightness", 70, 0, 255) -gen.add("hue_min", int_t, 0, "Lower threshold of hue. For red, use min>max", 118, 0, 180) -gen.add("hue_max", int_t, 0, "Upper threshold of hue. For red, use min>max", 124, 0, 180) - -exit(gen.generate(PACKAGE, "blaser_ros", "LaserDetector")) \ No newline at end of file diff --git a/blaser_ros/config/cam1/cam_config/mei.yaml b/blaser_ros/config/cam1/cam_config/mei.yaml deleted file mode 100644 index ef9e27d..0000000 --- a/blaser_ros/config/cam1/cam_config/mei.yaml +++ /dev/null @@ -1,18 +0,0 @@ -%YAML:1.0 ---- -model_type: MEI -camera_name: camera -image_width: 640 -image_height: 480 -mirror_parameters: - xi: 1.3502445948332753e+00 -distortion_parameters: - k1: -4.1188542616300872e-01 - k2: 1.6538648308362075e-01 - p1: -2.1812231602790573e-03 - p2: -7.3095517337040368e-04 -projection_parameters: - gamma1: 7.9637024491283989e+02 - gamma2: 7.9638156665611143e+02 - u0: 3.2586063178697401e+02 - v0: 2.2243680096400752e+02 diff --git a/blaser_ros/config/cam1/cam_config/pinhole.yaml b/blaser_ros/config/cam1/cam_config/pinhole.yaml deleted file mode 100644 index 9897166..0000000 --- a/blaser_ros/config/cam1/cam_config/pinhole.yaml +++ /dev/null @@ -1,14 +0,0 @@ -%YAML:1.0 -camera_matrix: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [ 340.81091, 0. , 328.9219 , - 0. , 341.29199, 224.53255, - 0. , 0. , 1. ] - -distortion_coefficients: !!opencv-matrix - rows: 1 - cols: 5 - dt: d - data: [-0.263077, 0.046754, -0.001104, -0.000508, 0.000000] diff --git a/blaser_ros/config/cam1/env_config/.checkerboard.yaml.swp b/blaser_ros/config/cam1/env_config/.checkerboard.yaml.swp deleted file mode 100644 index 2c65895..0000000 Binary files a/blaser_ros/config/cam1/env_config/.checkerboard.yaml.swp and /dev/null differ diff --git a/blaser_ros/config/cam1/env_config/car_toys.yaml b/blaser_ros/config/cam1/env_config/car_toys.yaml deleted file mode 100644 index 97765c8..0000000 --- a/blaser_ros/config/cam1/env_config/car_toys.yaml +++ /dev/null @@ -1,6 +0,0 @@ -%YAML:1.0 -laser_ROI: [0, 0, 640, 320] -red_mask_1_h: [180, 255, 255] -red_mask_1_l: [173, 120, 60] -red_mask_2_h: [7, 255, 255] -red_mask_2_l: [0, 120, 40] diff --git a/blaser_ros/config/cam1/env_config/checkerboard.yaml b/blaser_ros/config/cam1/env_config/checkerboard.yaml deleted file mode 100644 index 6d7d63d..0000000 --- a/blaser_ros/config/cam1/env_config/checkerboard.yaml +++ /dev/null @@ -1,8 +0,0 @@ -%YAML:1.0 -image_width: 640 -image_height: 480 -laser_ROI: [100, 100, 30, 240] -red_mask_1_h_calib: [180, 255, 255] -red_mask_1_l_calib: [170, 50, 40] -red_mask_2_h_calib: [10, 255, 255] -red_mask_2_l_calib: [0, 50, 40] diff --git a/blaser_ros/config/cam1/target_config/checkerboard.yaml b/blaser_ros/config/cam1/target_config/checkerboard.yaml deleted file mode 100644 index 2fa43b3..0000000 --- a/blaser_ros/config/cam1/target_config/checkerboard.yaml +++ /dev/null @@ -1,5 +0,0 @@ -%YAML:1.0 -target_rows: 6 -target_cols: 9 -square_size: 0.03 # meters - diff --git a/blaser_ros/config/cam1/target_config/small_cb.yaml b/blaser_ros/config/cam1/target_config/small_cb.yaml deleted file mode 100644 index 057ad3e..0000000 --- a/blaser_ros/config/cam1/target_config/small_cb.yaml +++ /dev/null @@ -1,5 +0,0 @@ -%YAML:1.0 -target_rows: 4 -target_cols: 6 -square_size: 0.03 # meters - diff --git a/blaser_ros/config/cam2/cam_config/icra2021.yaml b/blaser_ros/config/cam2/cam_config/icra2021.yaml deleted file mode 100644 index 93254ae..0000000 --- a/blaser_ros/config/cam2/cam_config/icra2021.yaml +++ /dev/null @@ -1,18 +0,0 @@ -%YAML:1.0 ---- -model_type: MEI -camera_name: camera -image_width: 720 -image_height: 405 -mirror_parameters: - xi: 5.7602570603247061e-01 -distortion_parameters: - k1: -2.9874126664667061e-01 - k2: 9.5203350651380483e-02 - p1: 1.2930551699230442e-03 - p2: 2.7809768896184871e-03 -projection_parameters: - gamma1: 5.3270089970665867e+02 - gamma2: 5.3065647080334850e+02 - u0: 3.7609043648964234e+02 - v0: 1.9528125567529517e+02 diff --git a/blaser_ros/config/cam2/cam_config/mei.yaml b/blaser_ros/config/cam2/cam_config/mei.yaml deleted file mode 100644 index fd79d0c..0000000 --- a/blaser_ros/config/cam2/cam_config/mei.yaml +++ /dev/null @@ -1,18 +0,0 @@ -%YAML:1.0 ---- -model_type: MEI -camera_name: camera -image_width: 720 -image_height: 405 -mirror_parameters: - xi: 2.4416168888295084e+00 -distortion_parameters: - k1: 6.8975571389416923e-01 - k2: 2.1430508545870555e+00 - p1: -2.8123712670124939e-03 - p2: 7.6976435411558780e-05 -projection_parameters: - gamma1: 1.1219520741661877e+03 - gamma2: 1.1238613806730066e+03 - u0: 3.8054382166138168e+02 - v0: 1.9654743230743148e+02 diff --git a/blaser_ros/config/cam2/cam_config/ost.yaml b/blaser_ros/config/cam2/cam_config/ost.yaml deleted file mode 100644 index 544cab4..0000000 --- a/blaser_ros/config/cam2/cam_config/ost.yaml +++ /dev/null @@ -1,20 +0,0 @@ -image_width: 720 -image_height: 405 -camera_name: narrow_stereo -camera_matrix: - rows: 3 - cols: 3 - data: [327.569953, 0.000000, 366.279963, 0.000000, 328.646347, 200.676051, 0.000000, 0.000000, 1.000000] -distortion_model: plumb_bob -distortion_coefficients: - rows: 1 - cols: 5 - data: [-0.212206, 0.032621, -0.000697, 0.000473, 0.000000] -rectification_matrix: - rows: 3 - cols: 3 - data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] -projection_matrix: - rows: 3 - cols: 4 - data: [218.516113, 0.000000, 369.899502, 0.000000, 0.000000, 298.828003, 199.878592, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] diff --git a/blaser_ros/config/cam2/cam_config/pinhole.yaml b/blaser_ros/config/cam2/cam_config/pinhole.yaml deleted file mode 100644 index 40eeb3e..0000000 --- a/blaser_ros/config/cam2/cam_config/pinhole.yaml +++ /dev/null @@ -1,14 +0,0 @@ -%YAML:1.0 -camera_matrix: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [ 327.569953, 0.000000, 366.279963, - 0.000000, 328.646347, 200.676051, - 0.000000, 0.000000, 1.000000] - -distortion_coefficients: !!opencv-matrix - rows: 1 - cols: 5 - dt: d - data: [-0.212206, 0.032621, -0.000697, 0.000473, 0.000000] diff --git a/blaser_ros/config/cam2/env_config/.checkerboard.yaml.swp b/blaser_ros/config/cam2/env_config/.checkerboard.yaml.swp deleted file mode 100644 index 2c65895..0000000 Binary files a/blaser_ros/config/cam2/env_config/.checkerboard.yaml.swp and /dev/null differ diff --git a/blaser_ros/config/cam2/env_config/car_toys.yaml b/blaser_ros/config/cam2/env_config/car_toys.yaml deleted file mode 100644 index 97765c8..0000000 --- a/blaser_ros/config/cam2/env_config/car_toys.yaml +++ /dev/null @@ -1,6 +0,0 @@ -%YAML:1.0 -laser_ROI: [0, 0, 640, 320] -red_mask_1_h: [180, 255, 255] -red_mask_1_l: [173, 120, 60] -red_mask_2_h: [7, 255, 255] -red_mask_2_l: [0, 120, 40] diff --git a/blaser_ros/config/cam2/env_config/checkerboard.yaml b/blaser_ros/config/cam2/env_config/checkerboard.yaml deleted file mode 100644 index 9675880..0000000 --- a/blaser_ros/config/cam2/env_config/checkerboard.yaml +++ /dev/null @@ -1,8 +0,0 @@ -%YAML:1.0 -image_width: 720 -image_height: 405 -laser_ROI: [100, 100, 30, 100] -red_mask_1_h_calib: [180, 255, 255] -red_mask_1_l_calib: [170, 50, 40] -red_mask_2_h_calib: [10, 255, 255] -red_mask_2_l_calib: [0, 50, 40] diff --git a/blaser_ros/config/cam2/target_config/5mm_9x6.yaml b/blaser_ros/config/cam2/target_config/5mm_9x6.yaml deleted file mode 100644 index 79dc497..0000000 --- a/blaser_ros/config/cam2/target_config/5mm_9x6.yaml +++ /dev/null @@ -1,5 +0,0 @@ -%YAML:1.0 -target_rows: 6 -target_cols: 9 -square_size: 0.005 # meters - diff --git a/blaser_ros/config/cam2/target_config/checkerboard.yaml b/blaser_ros/config/cam2/target_config/checkerboard.yaml deleted file mode 100644 index 2fa43b3..0000000 --- a/blaser_ros/config/cam2/target_config/checkerboard.yaml +++ /dev/null @@ -1,5 +0,0 @@ -%YAML:1.0 -target_rows: 6 -target_cols: 9 -square_size: 0.03 # meters - diff --git a/blaser_ros/config/cam2/target_config/small_cb.yaml b/blaser_ros/config/cam2/target_config/small_cb.yaml deleted file mode 100644 index 057ad3e..0000000 --- a/blaser_ros/config/cam2/target_config/small_cb.yaml +++ /dev/null @@ -1,5 +0,0 @@ -%YAML:1.0 -target_rows: 4 -target_cols: 6 -square_size: 0.03 # meters - diff --git a/blaser_ros/config/resolution_analyser/res_analyser.yaml b/blaser_ros/config/resolution_analyser/res_analyser.yaml deleted file mode 100644 index bb604ac..0000000 --- a/blaser_ros/config/resolution_analyser/res_analyser.yaml +++ /dev/null @@ -1,35 +0,0 @@ -%YAML:1.0 ---- -# camera intrinsics -model_type: MEI -camera_name: camera -image_width: 720 -image_height: 405 -mirror_parameters: - xi: 5.7602570603247061e-01 -distortion_parameters: - k1: -2.9874126664667061e-01 - k2: 9.5203350651380483e-02 - p1: 1.2930551699230442e-03 - p2: 2.7809768896184871e-03 -projection_parameters: - gamma1: 5.3270089970665867e+02 - gamma2: 5.3065647080334850e+02 - u0: 3.7609043648964234e+02 - v0: 1.9528125567529517e+02 - -# laser projector -baseline: 0.01 # 1cm -elevation_min: -0.78 # 45 degrees -elevation_max: 0.78 - -# depth distribution -depth_type: Gaussian -depth_min: 0.025 -depth_max: 0.1 -depth_mean: 0.03 -depth_std: 0.02 - -# laser angle params -theta_min: 0.0 # verticle -theta_max: 1.2 # around 70 degrees \ No newline at end of file diff --git a/blaser_ros/config/trl6_calib.yaml b/blaser_ros/config/trl6_calib.yaml deleted file mode 100644 index fcbc3b4..0000000 --- a/blaser_ros/config/trl6_calib.yaml +++ /dev/null @@ -1,44 +0,0 @@ -%YAML:1.0 - -# camera -model_type: MEI -camera_name: camera -image_width: 1000 -image_height: 700 -mirror_parameters: - xi: 1.1933299845008256e+00 -distortion_parameters: - k1: -1.0307532762135361e+00 - k2: 7.2867705739311539e-01 - p1: -1.7115108692878054e-03 - p2: -2.3862940682902107e-04 -projection_parameters: - gamma1: 1.5368900494749112e+03 - gamma2: 1.5396215746367591e+03 - u0: 5.0511964199941451e+02 - v0: 2.1642723738028127e+02 -width: 1000 -height: 700 - - -# checkerboard parameters -target_rows: 7 -target_cols: 10 -square_size: 0.005 # meters - -# laser detection parameters for HSV thresholding -# For red laser that -hue_min: 118 -hue_max: 124 -sat_min: 150 -val_min: 70 # brightness -val_ratio: 0.05 # val_thresh = max(val_min, image_max_val * val_ratio) - -segment_length_min: 1 - -laser_ROI: [500, 100, 0, 0] # boundary width on left, right, top, bottom - -vis_laser_detection: 0 -laser_horizontal: 0 - - diff --git a/blaser_ros/config/trl6_slam.rviz b/blaser_ros/config/trl6_slam.rviz deleted file mode 100644 index 27f11c1..0000000 --- a/blaser_ros/config/trl6_slam.rviz +++ /dev/null @@ -1,853 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /VIO1 - - /VIO1/TF1/Frames1 - - /VIO1/TF1/Tree1 - - /VIO1/LaserVisibleWindow1/Autocompute Value Bounds1 - - /Map1/LaserRGB1/Autocompute Value Bounds1 - - /Map1/LaserCnt1/Autocompute Value Bounds1 - Splitter Ratio: 0.4651159942150116 - Tree Height: 402 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /VIO1/LaserVisibleWindow1/Autocompute Value Bounds1 - - /Map1/LaserRGB1/Autocompute Value Bounds1 - - /Map1/LaserCnt1/Autocompute Value Bounds1 - Splitter Ratio: 0.5 - Tree Height: 363 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 0.009999999776482582 - Class: rviz/Grid - Color: 130; 130; 130 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: -0.05000000074505806 - Plane: XY - Plane Cell Count: 100 - Reference Frame: - Value: false - - Class: rviz/Axes - Enabled: false - Length: 1 - Name: Axes - Radius: 0.10000000149011612 - Reference Frame: - Value: false - - Class: rviz/Image - Enabled: true - Image Topic: /feature_tracker/feature_img - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: tracked image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: false - Image Topic: /laser_detector/laser_vis_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: LaserVisImage - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: false - - Class: rviz/Group - Displays: - - Alpha: 1 - Buffer Length: 1 - Class: rviz/Path - Color: 0; 255; 0 - Enabled: false - Head Diameter: 0.30000001192092896 - Head Length: 0.20000000298023224 - Length: 0.30000001192092896 - Line Style: Lines - Line Width: 0.029999999329447746 - Name: Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: None - Radius: 0.029999999329447746 - Shaft Diameter: 0.10000000149011612 - Shaft Length: 0.10000000149011612 - Topic: /vins_estimator/path - Unreliable: false - Value: false - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /vins_estimator/camera_pose_visual - Name: camera_visual - Namespaces: - {} - Queue Size: 100 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 3000 - Enabled: false - Invert Rainbow: true - Max Color: 0; 0; 0 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: history_point - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 1 - Size (m): 0.5 - Style: Points - Topic: /vins_estimator/history_cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: false - Value: false - - Class: rviz/TF - Enabled: true - Frame Timeout: 1000 - Frames: - All Enabled: false - Marker Scale: 0.05000000074505806 - Name: TF - Show Arrows: false - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 0.20000000298023224 - Min Value: -0.22112953662872314 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 52; 101; 164 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserVisibleWindow - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.00019999999494757503 - Style: Points - Topic: /slam_estimator/laser_visible - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false - Autocompute Value Bounds: - Max Value: -0.0995621532201767 - Min Value: -0.1641932725906372 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 233; 185; 110 - Max Intensity: 140 - Min Color: 255; 0; 0 - Min Intensity: 50 - Name: current_point - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 13 - Size (m): 0.009999999776482582 - Style: Points - Topic: /slam_estimator/point_cloud2 - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: VIO - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_cand - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /vins_estimator/vlio_dbg/lpc_cand_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Class: rviz/PointStamped - Color: 204; 41; 204 - Enabled: true - History Length: 1 - Name: feature_2d - Radius: 0.009999999776482582 - Topic: /vins_estimator/vlio_dbg/feature_pt - Unreliable: false - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 252; 233; 79 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: feature_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 20 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/feature_pt_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 0.2196808159351349 - Min Value: 0.17004889249801636 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 239; 41; 41 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_pc_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_c - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0.2196808159351349 - Min Color: 0; 0; 0 - Min Intensity: 0.17004889249801636 - Name: laser_pc_2d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_cn - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_close_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 6 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_close_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_close_2d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 6 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_close_2d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: VL3d_debug - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 0; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NewLaserFrame - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 7 - Size (m): 9.999999747378752e-5 - Style: Points - Topic: /laser_rgb_est/new_pc_rgb - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 1000 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: RGBLaserCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 5 - Size (m): 9.999999747378752e-5 - Style: Points - Topic: /laser_rgb_est/new_pc_rgb - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: DemoVis - - Class: rviz/Group - Displays: - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/laser_normal - Name: LaserNormal - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: -0.08294937014579773 - Min Value: -0.11999999731779099 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserRGB - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 4 - Size (m): 0.0010000000474974513 - Style: Points - Topic: /slam_estimator/laser_pcd - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: -0.04353427141904831 - Min Value: -0.1026337519288063 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 1 - Min Color: 0; 0; 0 - Min Intensity: 1 - Name: LaserCnt - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.0005000000237487257 - Style: Spheres - Topic: /vins_estimator/laser_pcd_cnt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/laser_icp_match - Name: LaserAssociation - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 1 - Min Color: 0; 0; 0 - Min Intensity: 1 - Name: FeatureCnt - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.004999999888241291 - Style: Points - Topic: /vins_estimator/feature_pcd - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/feature_match - Name: FeatureAssociation - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/feature_bbox - Name: FeatureBBox - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 204; 0; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NewLaserFrame - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 5 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/new_laser_frame - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - Enabled: true - Name: Map - - Class: rviz/Image - Enabled: true - Image Topic: /slam_estimator/f_on_im - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: FeatureOnImage - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 237; 212; 0 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: WorldPtCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 20 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/icp_assoc_vis/world_pt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 239; 41; 41 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: OptPtCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.0003000000142492354 - Style: Spheres - Topic: /vins_estimator/icp_assoc_vis/opt_pt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/icp_assoc_vis/world_opt_link - Name: world_opt_link - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: true - Marker Topic: /vins_estimator/icp_assoc_vis/world_residual - Name: world_residual - Namespaces: - {} - Queue Size: 100 - Value: true - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/icp_assoc_vis/opt_residual - Name: opt_residual - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: true - Marker Topic: /vins_estimator/icp_assoc_vis/world_match - Name: world_match - Namespaces: - {} - Queue Size: 100 - Value: true - Enabled: false - Name: ICPAssocVis - - Class: rviz/Image - Enabled: true - Image Topic: /laser_detector/laser_vis_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Marker - Enabled: false - Marker Topic: /slam_estimator/key_poses - Name: Marker - Namespaces: - {} - Queue Size: 100 - Value: false - Enabled: true - Global Options: - Background Color: 0; 0; 0 - Default Light: true - Fixed Frame: world - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 0.2010522037744522 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.0039941612631082535 - Y: -0.012956541031599045 - Z: -0.06377584487199783 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 1.5647963285446167 - Target Frame: - Value: Orbit (rviz) - Yaw: 1.4595123529434204 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - FeatureOnImage: - collapsed: false - Height: 1385 - Hide Left Dock: false - Hide Right Dock: true - Image: - collapsed: false - LaserVisImage: - collapsed: false - QMainWindow State: 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 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1759 - X: 67 - Y: 27 - tracked image: - collapsed: false diff --git a/blaser_ros/config/trl6_slam.yaml b/blaser_ros/config/trl6_slam.yaml deleted file mode 100644 index e38b199..0000000 --- a/blaser_ros/config/trl6_slam.yaml +++ /dev/null @@ -1,170 +0,0 @@ -%YAML:1.0 - -sensor_type: 0 # 0 for blaser, 1 for pipeblaser - -#common parameters -imu_topic: "/imu" -laser_topic: "/laser_detector/laser_points" -image_visual_topic: "/blaser_camera/image_hexp" -image_profile_topic: "/blaser_camera/image_lexp" -output_path: "/home/blaser/Desktop/vins_output" - -# camera - -# 0821 LL using KB model -model_type: KANNALA_BRANDT -camera_name: camera -image_width: 1000 -image_height: 700 -projection_parameters: - k2: -1.6442621295975660e-01 - k3: 3.0797322841285522e-02 - k4: -3.4880451836893055e-02 - k5: 1.8922706417464980e-02 - mu: 7.0181883970036540e+02 - mv: 7.0317268581495978e+02 - u0: 5.0629495538746147e+02 - v0: 2.1660916321486852e+02 - -# # 0820 DC version -# model_type: MEI -# camera_name: camera -# image_width: 1000 -# image_height: 700 -# mirror_parameters: -# xi: 3.1993163015418709e+01 -# distortion_parameters: -# k1: -1.1057655507699939e+01 -# k2: 4.1476619251102575e+03 -# p1: -3.5190907287160678e-02 -# p2: 2.2439209402131115e-02 -# projection_parameters: -# gamma1: 2.3106557046229165e+04 -# gamma2: 2.3149102246138438e+04 -# u0: 5.0471425675203875e+02 -# v0: 2.1937935969106067e+02 - -# # 0820 LL working version -# model_type: MEI -# camera_name: camera -# image_width: 1000 -# image_height: 700 -# mirror_parameters: -# xi: 3.2012119754785829e+01 -# distortion_parameters: -# k1: -1.1061216580375628e+01 -# k2: 4.1608246878212613e+03 -# p1: -3.5211358574601163e-02 -# p2: 2.2452561933505050e-02 -# projection_parameters: -# gamma1: 2.3119833376479648e+04 -# gamma2: 2.3162403001089599e+04 -# u0: 5.0471423124456055e+02 -# v0: 2.1937936021168335e+02 - - -# Extrinsic parameter between IMU and Camera. -estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it. - # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess. - # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning. -#If you choose 0 or 1, you should write down the following matrix. -extrinsicRotation: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [-0.99961933, -0.00808748, -0.02637793, - 0.02638251, -0.0004602, -0.99965182, - 0.00807252, -0.99996719, 0.00067339] - -#Translation from camera frame to imu frame, imu^T_cam -extrinsicTranslation: !!opencv-matrix - rows: 3 - cols: 1 - dt: d - # data: [0.00416818, 0.02023904, -0.00090114] #from Kalibr - data: [0.0135, 0.013, -0.0094] # from CAD - -#feature traker paprameters -max_cnt: 100 # max feature number in feature tracking -min_dist: 20 # min distance between two features -corner_quality: 0.01 -freq: 0 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image -F_threshold: 1.0 # ransac threshold (pixel) -show_track: 1 # publish tracking image as topic -equalize: 0 # if image is too dark or light, trun on equalize to find enough features -fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points - -#optimization parameters -max_solver_time: 0.022 # max solver itration time (ms), to guarantee real time -max_num_iterations: 8 # max solver itrations, to guarantee real time -keyframe_parallax: 30.0 # 30 # keyframe selection threshold (pixel) - -#imu parameters The more accurate parameters you provide, the better performance -acc_n: 0.1 # accelerometer measurement noise standard deviation. #0.2 -gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 -acc_w: 0.01 # accelerometer bias random work noise standard deviation. #0.02 -gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5 - -#acc_n: 0.2 #0.01 # accelerometer measurement noise standard deviation. #0.2 -#gyr_n: 0.05 #0.0025 # gyroscope measurement noise standard deviation. #0.05 -#acc_w: 0.02 #0.001 # accelerometer bias random work noise standard deviation. #0.02 -#gyr_w: 4.0e-5 #2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5 - - -g_norm: 9.80665 # gravity magnitude - -#loop closure parameters -loop_closure: 0 # start loop closure -load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path' -fast_relocalization: 0 # useful in real-time and large project -pose_graph_save_path: "/home/ubuntu/Desktop/vins_output/pose_graph/" # save and load path - -#unsynchronization parameters -estimate_td: 1 # online estimate time offset between camera and imu -td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock) - -#rolling shutter parameters -rolling_shutter: 1 # 0: global shutter camera, 1: rolling shutter camera -rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet). - -static_initialization: 0 - -#visualization parameters -save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0 -visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results -visualize_camera_size: 0.01 # size of camera marker in RVIZ -visualize_camera_line_width: 0.002 - -use_encoder: 0 - -# image parameters -width: 1000 -height: 700 -center_u: 5.0471423124456055e+02 -center_v: 2.1937936021168335e+02 - -# laser triangulation parameters -# laser_plane: [-4613.02,3.924,-100,109.235] # old working ver -laser_plane: [-5992.34,34.5386,-100,140.78] #0821LL -# laser_plane: [-5719.46,31.6129,-100.0,134.645] # Daqian based on 0820LL -#laser plane: [-6801.8,45.8367,-100.0,159.858] # 0820LL data -#laser plane: [-10427.9,78.6371,-100.0,238.168] # 0819 data -laser_depth_range: [0.01, 1.0] # distance between 3d point & camera - -# laser detection parameters -hue_min: 118 -hue_max: 124 -sat_min: 150 -val_min: 70 # brightness -val_ratio: 0.05 # val_thresh = max(val_min, image_max_val * val_ratio) - -segment_length_min: 1 - -laser_ROI: [500, 100, 0, 0] # boundary width on left, right, top, bottom - -vis_laser_detection: 0 -laser_horizontal: 0 - -#mask_file: "/home/pipe/catkin_ws/pipe_blaser_ws/src/pipe_blaser_ros/config/v2_mask.png" -mask_file: "/home/blaser/catkin_ws/blaser_ws/src/pipe_blaser_ros/config/mask_v2_170d.png" - diff --git a/blaser_ros/config/trl6_slam_0821LL_Final.yaml b/blaser_ros/config/trl6_slam_0821LL_Final.yaml deleted file mode 100644 index e38b199..0000000 --- a/blaser_ros/config/trl6_slam_0821LL_Final.yaml +++ /dev/null @@ -1,170 +0,0 @@ -%YAML:1.0 - -sensor_type: 0 # 0 for blaser, 1 for pipeblaser - -#common parameters -imu_topic: "/imu" -laser_topic: "/laser_detector/laser_points" -image_visual_topic: "/blaser_camera/image_hexp" -image_profile_topic: "/blaser_camera/image_lexp" -output_path: "/home/blaser/Desktop/vins_output" - -# camera - -# 0821 LL using KB model -model_type: KANNALA_BRANDT -camera_name: camera -image_width: 1000 -image_height: 700 -projection_parameters: - k2: -1.6442621295975660e-01 - k3: 3.0797322841285522e-02 - k4: -3.4880451836893055e-02 - k5: 1.8922706417464980e-02 - mu: 7.0181883970036540e+02 - mv: 7.0317268581495978e+02 - u0: 5.0629495538746147e+02 - v0: 2.1660916321486852e+02 - -# # 0820 DC version -# model_type: MEI -# camera_name: camera -# image_width: 1000 -# image_height: 700 -# mirror_parameters: -# xi: 3.1993163015418709e+01 -# distortion_parameters: -# k1: -1.1057655507699939e+01 -# k2: 4.1476619251102575e+03 -# p1: -3.5190907287160678e-02 -# p2: 2.2439209402131115e-02 -# projection_parameters: -# gamma1: 2.3106557046229165e+04 -# gamma2: 2.3149102246138438e+04 -# u0: 5.0471425675203875e+02 -# v0: 2.1937935969106067e+02 - -# # 0820 LL working version -# model_type: MEI -# camera_name: camera -# image_width: 1000 -# image_height: 700 -# mirror_parameters: -# xi: 3.2012119754785829e+01 -# distortion_parameters: -# k1: -1.1061216580375628e+01 -# k2: 4.1608246878212613e+03 -# p1: -3.5211358574601163e-02 -# p2: 2.2452561933505050e-02 -# projection_parameters: -# gamma1: 2.3119833376479648e+04 -# gamma2: 2.3162403001089599e+04 -# u0: 5.0471423124456055e+02 -# v0: 2.1937936021168335e+02 - - -# Extrinsic parameter between IMU and Camera. -estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it. - # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess. - # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning. -#If you choose 0 or 1, you should write down the following matrix. -extrinsicRotation: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [-0.99961933, -0.00808748, -0.02637793, - 0.02638251, -0.0004602, -0.99965182, - 0.00807252, -0.99996719, 0.00067339] - -#Translation from camera frame to imu frame, imu^T_cam -extrinsicTranslation: !!opencv-matrix - rows: 3 - cols: 1 - dt: d - # data: [0.00416818, 0.02023904, -0.00090114] #from Kalibr - data: [0.0135, 0.013, -0.0094] # from CAD - -#feature traker paprameters -max_cnt: 100 # max feature number in feature tracking -min_dist: 20 # min distance between two features -corner_quality: 0.01 -freq: 0 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image -F_threshold: 1.0 # ransac threshold (pixel) -show_track: 1 # publish tracking image as topic -equalize: 0 # if image is too dark or light, trun on equalize to find enough features -fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points - -#optimization parameters -max_solver_time: 0.022 # max solver itration time (ms), to guarantee real time -max_num_iterations: 8 # max solver itrations, to guarantee real time -keyframe_parallax: 30.0 # 30 # keyframe selection threshold (pixel) - -#imu parameters The more accurate parameters you provide, the better performance -acc_n: 0.1 # accelerometer measurement noise standard deviation. #0.2 -gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 -acc_w: 0.01 # accelerometer bias random work noise standard deviation. #0.02 -gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5 - -#acc_n: 0.2 #0.01 # accelerometer measurement noise standard deviation. #0.2 -#gyr_n: 0.05 #0.0025 # gyroscope measurement noise standard deviation. #0.05 -#acc_w: 0.02 #0.001 # accelerometer bias random work noise standard deviation. #0.02 -#gyr_w: 4.0e-5 #2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5 - - -g_norm: 9.80665 # gravity magnitude - -#loop closure parameters -loop_closure: 0 # start loop closure -load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path' -fast_relocalization: 0 # useful in real-time and large project -pose_graph_save_path: "/home/ubuntu/Desktop/vins_output/pose_graph/" # save and load path - -#unsynchronization parameters -estimate_td: 1 # online estimate time offset between camera and imu -td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock) - -#rolling shutter parameters -rolling_shutter: 1 # 0: global shutter camera, 1: rolling shutter camera -rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet). - -static_initialization: 0 - -#visualization parameters -save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0 -visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results -visualize_camera_size: 0.01 # size of camera marker in RVIZ -visualize_camera_line_width: 0.002 - -use_encoder: 0 - -# image parameters -width: 1000 -height: 700 -center_u: 5.0471423124456055e+02 -center_v: 2.1937936021168335e+02 - -# laser triangulation parameters -# laser_plane: [-4613.02,3.924,-100,109.235] # old working ver -laser_plane: [-5992.34,34.5386,-100,140.78] #0821LL -# laser_plane: [-5719.46,31.6129,-100.0,134.645] # Daqian based on 0820LL -#laser plane: [-6801.8,45.8367,-100.0,159.858] # 0820LL data -#laser plane: [-10427.9,78.6371,-100.0,238.168] # 0819 data -laser_depth_range: [0.01, 1.0] # distance between 3d point & camera - -# laser detection parameters -hue_min: 118 -hue_max: 124 -sat_min: 150 -val_min: 70 # brightness -val_ratio: 0.05 # val_thresh = max(val_min, image_max_val * val_ratio) - -segment_length_min: 1 - -laser_ROI: [500, 100, 0, 0] # boundary width on left, right, top, bottom - -vis_laser_detection: 0 -laser_horizontal: 0 - -#mask_file: "/home/pipe/catkin_ws/pipe_blaser_ws/src/pipe_blaser_ros/config/v2_mask.png" -mask_file: "/home/blaser/catkin_ws/blaser_ws/src/pipe_blaser_ros/config/mask_v2_170d.png" - diff --git a/blaser_ros/config/trl6_slam_210821.yaml b/blaser_ros/config/trl6_slam_210821.yaml deleted file mode 100644 index 9db6365..0000000 --- a/blaser_ros/config/trl6_slam_210821.yaml +++ /dev/null @@ -1,131 +0,0 @@ -%YAML:1.0 - -sensor_type: 0 # 0 for blaser, 1 for pipeblaser - -#common parameters -imu_topic: "/imu" -laser_topic: "/laser_detector/laser_points" -image_visual_topic: "/blaser_camera/image_hexp" -image_profile_topic: "/blaser_camera/image_lexp" -output_path: "/home/dcheng/Desktop/vins_output" - -# camera -model_type: MEI -camera_name: camera -image_width: 1000 -image_height: 700 -mirror_parameters: - xi: 3.1993163015418709e+01 -distortion_parameters: - k1: -1.1057655507699939e+01 - k2: 4.1476619251102575e+03 - p1: -3.5190907287160678e-02 - p2: 2.2439209402131115e-02 -projection_parameters: - gamma1: 2.3106557046229165e+04 - gamma2: 2.3149102246138438e+04 - u0: 5.0471425675203875e+02 - v0: 2.1937935969106067e+02 - - -# Extrinsic parameter between IMU and Camera. -estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it. - # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess. - # 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning. -#If you choose 0 or 1, you should write down the following matrix. -extrinsicRotation: !!opencv-matrix - rows: 3 - cols: 3 - dt: d - data: [-0.99961933, -0.00808748, -0.02637793, - 0.02638251, -0.0004602, -0.99965182, - 0.00807252, -0.99996719, 0.00067339] - -#Translation from camera frame to imu frame, imu^T_cam -extrinsicTranslation: !!opencv-matrix - rows: 3 - cols: 1 - dt: d - data: [0.00416818, 0.02023904, -0.00090114] - - -#feature traker paprameters -max_cnt: 100 # max feature number in feature tracking -min_dist: 20 # min distance between two features -corner_quality: 0.01 -freq: 0 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image -F_threshold: 1.0 # ransac threshold (pixel) -show_track: 1 # publish tracking image as topic -equalize: 0 # if image is too dark or light, trun on equalize to find enough features -fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points - -#optimization parameters -max_solver_time: 0.022 # max solver itration time (ms), to guarantee real time -max_num_iterations: 8 # max solver itrations, to guarantee real time -keyframe_parallax: 30.0 # 30 # keyframe selection threshold (pixel) - -#imu parameters The more accurate parameters you provide, the better performance -acc_n: 0.1 # accelerometer measurement noise standard deviation. #0.2 -gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 -acc_w: 0.01 # accelerometer bias random work noise standard deviation. #0.02 -gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5 - -#acc_n: 0.2 #0.01 # accelerometer measurement noise standard deviation. #0.2 -#gyr_n: 0.05 #0.0025 # gyroscope measurement noise standard deviation. #0.05 -#acc_w: 0.02 #0.001 # accelerometer bias random work noise standard deviation. #0.02 -#gyr_w: 4.0e-5 #2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5 - - -g_norm: 9.80665 # gravity magnitude - -#loop closure parameters -loop_closure: 0 # start loop closure -load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path' -fast_relocalization: 0 # useful in real-time and large project -pose_graph_save_path: "/home/ubuntu/Desktop/vins_output/pose_graph/" # save and load path - -#unsynchronization parameters -estimate_td: 1 # online estimate time offset between camera and imu -td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock) - -#rolling shutter parameters -rolling_shutter: 1 # 0: global shutter camera, 1: rolling shutter camera -rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet). - -static_initialization: 0 - -#visualization parameters -save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0 -visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results -visualize_camera_size: 0.01 # size of camera marker in RVIZ -visualize_camera_line_width: 0.002 - -use_encoder: 0 - -# image parameters -width: 1000 -height: 700 -center_u: 5.0471425675203875e+02 -center_v: 2.1937935969106067e+02 - -# laser triangulation parameters -laser_plane: [-5719.46,31.6129,-100.0,134.645] -laser_depth_range: [0.01, 1.0] # distance between 3d point & camera - -# laser detection parameters -hue_min: 118 -hue_max: 124 -sat_min: 150 -val_min: 70 # brightness -val_ratio: 0.05 # val_thresh = max(val_min, image_max_val * val_ratio) - -segment_length_min: 1 - -laser_ROI: [500, 100, 0, 0] # boundary width on left, right, top, bottom - -vis_laser_detection: 0 -laser_horizontal: 0 - -#mask_file: "/home/pipe/catkin_ws/pipe_blaser_ws/src/pipe_blaser_ros/config/v2_mask.png" -mask_file: "/home/dcheng/catkin_ws/blaser_ws/src/pipe_blaser_ros/config/mask_v2_170d.png" - diff --git a/blaser_ros/config/vlio_rviz_config.rviz b/blaser_ros/config/vlio_rviz_config.rviz deleted file mode 100644 index fe13f99..0000000 --- a/blaser_ros/config/vlio_rviz_config.rviz +++ /dev/null @@ -1,844 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /VIO1 - - /VIO1/TF1/Frames1 - - /VIO1/TF1/Tree1 - - /VIO1/LaserVisibleWindow1/Autocompute Value Bounds1 - - /Map1/LaserRGB1/Autocompute Value Bounds1 - - /Map1/LaserCnt1/Autocompute Value Bounds1 - - /Image1 - Splitter Ratio: 0.4651159942150116 - Tree Height: 693 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /VIO1/LaserVisibleWindow1/Autocompute Value Bounds1 - - /Map1/LaserRGB1/Autocompute Value Bounds1 - - /Map1/LaserCnt1/Autocompute Value Bounds1 - Splitter Ratio: 0.5 - Tree Height: 358 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 0.009999999776482582 - Class: rviz/Grid - Color: 130; 130; 130 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: -0.05000000074505806 - Plane: XY - Plane Cell Count: 100 - Reference Frame: - Value: false - - Class: rviz/Axes - Enabled: false - Length: 1 - Name: Axes - Radius: 0.10000000149011612 - Reference Frame: - Value: false - - Class: rviz/Image - Enabled: true - Image Topic: /feature_tracker/feature_img - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: tracked image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: false - Image Topic: /laser_detector/laser_vis_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: LaserVisImage - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: false - - Class: rviz/Group - Displays: - - Alpha: 1 - Buffer Length: 1 - Class: rviz/Path - Color: 0; 255; 0 - Enabled: false - Head Diameter: 0.30000001192092896 - Head Length: 0.20000000298023224 - Length: 0.30000001192092896 - Line Style: Lines - Line Width: 0.029999999329447746 - Name: Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: None - Radius: 0.029999999329447746 - Shaft Diameter: 0.10000000149011612 - Shaft Length: 0.10000000149011612 - Topic: /vins_estimator/path - Unreliable: false - Value: false - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /vins_estimator/camera_pose_visual - Name: camera_visual - Namespaces: - {} - Queue Size: 100 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 3000 - Enabled: false - Invert Rainbow: true - Max Color: 0; 0; 0 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: history_point - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 1 - Size (m): 0.5 - Style: Points - Topic: /vins_estimator/history_cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: false - Value: false - - Class: rviz/TF - Enabled: true - Frame Timeout: 1000 - Frames: - All Enabled: false - Marker Scale: 0.05000000074505806 - Name: TF - Show Arrows: false - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 0.20000000298023224 - Min Value: -0.22112953662872314 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 52; 101; 164 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserVisibleWindow - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.00019999999494757503 - Style: Points - Topic: /vins_estimator/laser_window - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false - Autocompute Value Bounds: - Max Value: -0.0995621532201767 - Min Value: -0.1641932725906372 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 233; 185; 110 - Max Intensity: 140 - Min Color: 255; 0; 0 - Min Intensity: 50 - Name: current_point - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 13 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/point_cloud2 - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: VIO - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_cand - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /vins_estimator/vlio_dbg/lpc_cand_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Class: rviz/PointStamped - Color: 204; 41; 204 - Enabled: true - History Length: 1 - Name: feature_2d - Radius: 0.009999999776482582 - Topic: /vins_estimator/vlio_dbg/feature_pt - Unreliable: false - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 252; 233; 79 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: feature_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 20 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/feature_pt_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 0.2196808159351349 - Min Value: 0.17004889249801636 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 239; 41; 41 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_pc_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_c - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0.2196808159351349 - Min Color: 0; 0; 0 - Min Intensity: 0.17004889249801636 - Name: laser_pc_2d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_cn - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_close_3d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 6 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_close_3d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: laser_close_2d - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 6 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/vlio_dbg/lpc_close_2d - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: VL3d_debug - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 0; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NewLaserFrame - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 7 - Size (m): 9.999999747378752e-5 - Style: Points - Topic: /laser_rgb_est/new_pc_rgb - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 1000 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: RGBLaserCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 5 - Size (m): 9.999999747378752e-5 - Style: Points - Topic: /laser_rgb_est/new_pc_rgb - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: DemoVis - - Class: rviz/Group - Displays: - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/laser_normal - Name: LaserNormal - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: -0.08294937014579773 - Min Value: -0.11999999731779099 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserRGB - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 4 - Size (m): 0.0010000000474974513 - Style: Points - Topic: /vins_estimator/laser_pcd - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: -0.04353427141904831 - Min Value: -0.1026337519288063 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 1 - Min Color: 0; 0; 0 - Min Intensity: 1 - Name: LaserCnt - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.0005000000237487257 - Style: Spheres - Topic: /vins_estimator/laser_pcd_cnt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/laser_icp_match - Name: LaserAssociation - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 1 - Min Color: 0; 0; 0 - Min Intensity: 1 - Name: FeatureCnt - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.004999999888241291 - Style: Points - Topic: /vins_estimator/feature_pcd - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/feature_match - Name: FeatureAssociation - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/feature_bbox - Name: FeatureBBox - Namespaces: - {} - Queue Size: 100 - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 204; 0; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NewLaserFrame - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 5 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/new_laser_frame - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - Enabled: true - Name: Map - - Class: rviz/Image - Enabled: true - Image Topic: /vins_estimator/f_on_im - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 237; 212; 0 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: WorldPtCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 20 - Size (m): 0.009999999776482582 - Style: Points - Topic: /vins_estimator/icp_assoc_vis/world_pt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 239; 41; 41 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: OptPtCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.0003000000142492354 - Style: Spheres - Topic: /vins_estimator/icp_assoc_vis/opt_pt - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/icp_assoc_vis/world_opt_link - Name: world_opt_link - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: true - Marker Topic: /vins_estimator/icp_assoc_vis/world_residual - Name: world_residual - Namespaces: - {} - Queue Size: 100 - Value: true - - Class: rviz/Marker - Enabled: false - Marker Topic: /vins_estimator/icp_assoc_vis/opt_residual - Name: opt_residual - Namespaces: - {} - Queue Size: 100 - Value: false - - Class: rviz/Marker - Enabled: true - Marker Topic: /vins_estimator/icp_assoc_vis/world_match - Name: world_match - Namespaces: - {} - Queue Size: 100 - Value: true - Enabled: false - Name: ICPAssocVis - - Class: rviz/Image - Enabled: true - Image Topic: /ring_laser_triangulator/laser_vis_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 0; 0; 0 - Default Light: true - Fixed Frame: world - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 2.8520445823669434 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.10116031765937805 - Y: 0.4000096321105957 - Z: 0.07418225705623627 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.004797247238457203 - Target Frame: - Value: Orbit (rviz) - Yaw: 2.7099976539611816 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 2103 - Hide Left Dock: false - Hide Right Dock: true - Image: - collapsed: false - LaserVisImage: - collapsed: false - QMainWindow State: 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 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1983 - X: 3901 - Y: 27 - tracked image: - collapsed: false diff --git a/blaser_ros/include/blaser_ros/common.h b/blaser_ros/include/blaser_ros/common.h deleted file mode 100644 index cd3b384..0000000 --- a/blaser_ros/include/blaser_ros/common.h +++ /dev/null @@ -1,32 +0,0 @@ -// -// Created by dcheng on 5/28/20. -// - -#ifndef VIO_BLASER_COMMON_H -#define VIO_BLASER_COMMON_H - -#include -#include -#include -#include -#include -#include -#include - -using std::cout; -using std::endl; -using Eigen::Matrix3d; -using Eigen::Matrix4d; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::Vector4d; -using Eigen::Quaterniond; -using Eigen::RowVector3d; - -template -T lerp(T a, T b, T t) -{ - return a + t * (b - a); -} - -#endif //VIO_BLASER_COMMON_H diff --git a/blaser_ros/include/blaser_ros/laser_detector.h b/blaser_ros/include/blaser_ros/laser_detector.h deleted file mode 100644 index c787c97..0000000 --- a/blaser_ros/include/blaser_ros/laser_detector.h +++ /dev/null @@ -1,64 +0,0 @@ -// -// Created by dcheng on 4/11/20. -// - -#ifndef LASER_DETECTOR_LASER_DETECTOR_H -#define LASER_DETECTOR_LASER_DETECTOR_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "camodocal/camera_models/CameraFactory.h" -#include "camodocal/camera_models/CataCamera.h" -#include "camodocal/camera_models/PinholeCamera.h" - -#include -#include - -/** - * Laser Detector class. - * Only detects laser and publish 2D pixels and 3D points. - * Does not do any point cloud management work. Leave that to VLIO. - */ -class LaserDetector -{ -public: - explicit LaserDetector(std::string& config_fn, const std::string& nh_name); - -private: - void readParams(const std::string& config_fn); - - void laser_im_cb(const sensor_msgs::ImageConstPtr im_msg); - - void laser_extract_param_cb(blaser_ros::LaserDetectorConfig& config, - uint32_t level); - - /***** dynamic reconfigures *****/ - dynamic_reconfigure::Server reconfigure_server_; - dynamic_reconfigure::Server::CallbackType reconfigure_f_; - - /***** data containers *****/ - camodocal::CameraPtr m_camera_; - LaserStripeDetector lsd_; - Laser2Dto3DPtr laser_lift_; - - std::vector laser_plane_; - - std::vector laser_depth_range_; - - /***** ros subs & pubs *****/ - ros::NodeHandle nh_; - ros::Subscriber laser_im_sub_; - ros::Publisher laser_pc_pub_; - ros::Publisher laser_vis_im_pub_; - - std::string image_profile_topic_; -}; - -#endif //LASER_DETECTOR_LASER_DETECTOR_H diff --git a/blaser_ros/include/blaser_ros/laser_geometry_utils.h b/blaser_ros/include/blaser_ros/laser_geometry_utils.h deleted file mode 100644 index bbda026..0000000 --- a/blaser_ros/include/blaser_ros/laser_geometry_utils.h +++ /dev/null @@ -1,37 +0,0 @@ -// -// Created by dcheng on 4/11/20. -// - -#ifndef VIO_BLASER_LASER_GEOMETRY_UTILS_H -#define VIO_BLASER_LASER_GEOMETRY_UTILS_H - -#include -#include -#include -#include - -class Laser2Dto3D -{ -public: - /** - * Constructor for class - * @tparam V4_t vector of 4, like Eigen::Vector4d, std::vector, etc. - * @param plane_params laser param vector of 4: ax + by + cz + d = 0 - */ - explicit Laser2Dto3D(const std::vector &plane_params); - - /** - * Lift 2d laser pixels to 3d space - * @param pts_norm normalized 2d pixels (undistorted) - * @param pts_3d output laser points in 3d - */ - void ptsNormTo3D(const std::vector& pts_norm, - std::vector& pts_3d); - -private: - Eigen::Vector4d plane_; -}; - -typedef std::shared_ptr Laser2Dto3DPtr; - -#endif //VIO_BLASER_LASER_GEOMETRY_UTILS_H diff --git a/blaser_ros/include/blaser_ros/laser_rgb_estimator.h b/blaser_ros/include/blaser_ros/laser_rgb_estimator.h deleted file mode 100644 index d2d5708..0000000 --- a/blaser_ros/include/blaser_ros/laser_rgb_estimator.h +++ /dev/null @@ -1,150 +0,0 @@ -// -// Created by dcheng on 5/27/20. -// - -#ifndef VIO_BLASER_LASER_RGB_ESTIMATOR_H -#define VIO_BLASER_LASER_RGB_ESTIMATOR_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "camodocal/camera_models/CameraFactory.h" -#include "camodocal/camera_models/CataCamera.h" -#include "camodocal/camera_models/PinholeCamera.h" - -typedef pcl::PointCloud pcl_xyz; -typedef pcl::PointCloud pcl_xyzrgb; - -class ImageFrame -{ -public: - explicit ImageFrame(cv_bridge::CvImageConstPtr p_cv_im); - - const Matrix4d &getTwc() const; - void setTwc(const Matrix4d &twc_); - - double getStamp() const; - - const cv::Mat &getImage() const; - - bool isFSetPose() const; - -private: - void changeBrightness(double alpha, double beta); - cv::Mat image_; - - double stamp_; - - Matrix4d Twc_; - - bool f_set_pose_; -}; - -typedef std::shared_ptr ImageFramePtr; - -class LaserFrame -{ -public: - explicit LaserFrame(sensor_msgs::PointCloudConstPtr msg); - - bool loadPCfromMsg(sensor_msgs::PointCloudConstPtr msg); - - bool genPcW(const Matrix4d& Twc); - - double getStamp() const; - - pcl::PointCloud::Ptr &getPPcRgbW(); - -private: - double stamp_; - - pcl_xyzrgb::Ptr p_pc_rgb_c_; - pcl_xyzrgb::Ptr p_pc_rgb_w_; -}; - -typedef std::shared_ptr LaserFramePtr; - - -/** - * 1. resource in: - * 1.1 laser: new laser frame, feed into container - * 1.2 image: new image frame, feed into container - * 1.3 odom: set corresponding image frame (should be the nf_bef + 1 th image in vector) - * Twc, trigger data proc and sliding window - * 2. resource proc: - * 2.1 Interpolate pose for laser frame nf_aft before the image frame - * 2.2 Find RGB value with k frames. X o X O X o X - * 2.3 Add this laser frame into whole point cloud - * 3. resource free (sliding window) - * 3.1 Delete first image frame - * 3.2 Delete the laser frame that got RGBed. - */ -class LaserRGBEstimator -{ -public: - LaserRGBEstimator(); - - void image_cb(sensor_msgs::ImageConstPtr msg); - - void laser_cb(sensor_msgs::PointCloudConstPtr msg); - - void odom_cb(nav_msgs::OdometryConstPtr msg); - - template - RowVector3d estPointColorWithImage(const PointT& p_w, ImageFramePtr pif); - - /** - * [start, end) - * @param plf - * @param start - * @param end - * @return - */ - bool estLaserFrameColor(LaserFramePtr plf, - std::deque::iterator start, - std::deque::iterator end); - - bool slide_window(); - - bool pubPcRGB(); - -private: - void init(); - - bool initSlideWindow(size_t idx_im_pose); - - size_t setImagePose(nav_msgs::OdometryConstPtr msg); - - // sliding windows - std::deque image_sw_; - std::deque laser_sw_; - bool f_sw_init_; - - // result (and fixed) point cloud - pcl_xyzrgb::Ptr whole_pc_rgb_; - pcl_xyzrgb::Ptr new_pc_rgb_; - - // parameters - static const uint8_t nf_bef_, nf_aft_; - camodocal::CameraPtr m_camera_; - Matrix4d Tic_; - int status; - - // ros related - ros::NodeHandle nh_; - ros::Subscriber image_sub_; - ros::Subscriber laser_sub_; - ros::Subscriber odom_sub_; - ros::Publisher pc_rgb_pub_; - ros::Publisher new_pc_rgb_pub_; -}; - - - -#endif //VIO_BLASER_LASER_RGB_ESTIMATOR_H diff --git a/blaser_ros/include/blaser_ros/resolution_analyser.h b/blaser_ros/include/blaser_ros/resolution_analyser.h deleted file mode 100644 index 2d02c25..0000000 --- a/blaser_ros/include/blaser_ros/resolution_analyser.h +++ /dev/null @@ -1,88 +0,0 @@ -// -// Created by dcheng on 11/23/20. -// - -#ifndef VIO_BLASER_RESOLUTION_ANALYSER_H -#define VIO_BLASER_RESOLUTION_ANALYSER_H - -#include -#include "camodocal/camera_models/CameraFactory.h" -#include "camodocal/camera_models/CataCamera.h" -#include "camodocal/camera_models/PinholeCamera.h" - -class LaserProjector -{ -public: - LaserProjector(const std::string& config_fn, double theta); - - bool project(double depth, size_t n_pts, std::vector& pts) const; - - double elevation_min_; - double elevation_max_; - -private: - double baseline_; - double theta_; // 0 is vertical - - Eigen::Matrix4d Tcl_; -}; - -class DepthDistribution -{ -public: - DepthDistribution(const std::string& config_fn); - - std::vector> weighted_depths_; // depth, weight - - static const int NUM_DEPTHS = 100; - -private: - void readParams(const std::string& config_fn); - - void genWeightedDepthsUniform(); - void genWeightedDepthsGaussian(); - - enum { - Gaussian, - Uniform - } type; - - double min; - double max; - - // gaussian params - double mean; - double std; -}; - -class ResolutionAnalyser -{ -public: - ResolutionAnalyser(const std::string& config_fn); - - void evalRes(); - - void evalRes(const std::vector& thetas); - - double evalResAtTheta(double theta, - std::vector& depths, std::vector& ress, - std::vector& weights, bool is_vis = false); - - double evalResAtDepth(double depth, const LaserProjector& laser_projector, - bool is_vis = false); - -private: - - - void readParam(const std::string& config_fn); - - camodocal::CameraPtr m_camera_; - DepthDistribution depth_distribution_; - const std::string config_fn_; - static const int NUM_THETAS = 100; - constexpr static const double DEPTH_DELTA = 0.001; - double theta_min_; - double theta_max_; -}; - -#endif //VIO_BLASER_RESOLUTION_ANALYSER_H diff --git a/blaser_ros/include/blaser_ros/third_party/matplotlibcpp.h b/blaser_ros/include/blaser_ros/third_party/matplotlibcpp.h deleted file mode 100644 index 214adfb..0000000 --- a/blaser_ros/include/blaser_ros/third_party/matplotlibcpp.h +++ /dev/null @@ -1,2986 +0,0 @@ -#pragma once - -// Python headers must be included before any system headers, since -// they define _POSIX_C_SOURCE -#include - -#include -#include -#include -#include -#include -#include -#include -#include // requires c++11 support -#include -#include // std::stod - -#ifndef WITHOUT_NUMPY -# define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION -# include - -# ifdef WITH_OPENCV -# include -# endif // WITH_OPENCV - -/* - * A bunch of constants were removed in OpenCV 4 in favour of enum classes, so - * define the ones we need here. - */ -# if CV_MAJOR_VERSION > 3 -# define CV_BGR2RGB cv::COLOR_BGR2RGB -# define CV_BGRA2RGBA cv::COLOR_BGRA2RGBA -# endif -#endif // WITHOUT_NUMPY - -#if PY_MAJOR_VERSION >= 3 -# define PyString_FromString PyUnicode_FromString -# define PyInt_FromLong PyLong_FromLong -# define PyString_FromString PyUnicode_FromString -#endif - - -namespace matplotlibcpp { -namespace detail { - -static std::string s_backend; - -struct _interpreter { - PyObject* s_python_function_arrow; - PyObject *s_python_function_show; - PyObject *s_python_function_close; - PyObject *s_python_function_draw; - PyObject *s_python_function_pause; - PyObject *s_python_function_save; - PyObject *s_python_function_figure; - PyObject *s_python_function_fignum_exists; - PyObject *s_python_function_plot; - PyObject *s_python_function_quiver; - PyObject* s_python_function_contour; - PyObject *s_python_function_semilogx; - PyObject *s_python_function_semilogy; - PyObject *s_python_function_loglog; - PyObject *s_python_function_fill; - PyObject *s_python_function_fill_between; - PyObject *s_python_function_hist; - PyObject *s_python_function_imshow; - PyObject *s_python_function_scatter; - PyObject *s_python_function_boxplot; - PyObject *s_python_function_subplot; - PyObject *s_python_function_subplot2grid; - PyObject *s_python_function_legend; - PyObject *s_python_function_xlim; - PyObject *s_python_function_ion; - PyObject *s_python_function_ginput; - PyObject *s_python_function_ylim; - PyObject *s_python_function_title; - PyObject *s_python_function_axis; - PyObject *s_python_function_axhline; - PyObject *s_python_function_axvline; - PyObject *s_python_function_axvspan; - PyObject *s_python_function_xlabel; - PyObject *s_python_function_ylabel; - PyObject *s_python_function_gca; - PyObject *s_python_function_xticks; - PyObject *s_python_function_yticks; - PyObject* s_python_function_margins; - PyObject *s_python_function_tick_params; - PyObject *s_python_function_grid; - PyObject* s_python_function_cla; - PyObject *s_python_function_clf; - PyObject *s_python_function_errorbar; - PyObject *s_python_function_annotate; - PyObject *s_python_function_tight_layout; - PyObject *s_python_colormap; - PyObject *s_python_empty_tuple; - PyObject *s_python_function_stem; - PyObject *s_python_function_xkcd; - PyObject *s_python_function_text; - PyObject *s_python_function_suptitle; - PyObject *s_python_function_bar; - PyObject *s_python_function_barh; - PyObject *s_python_function_colorbar; - PyObject *s_python_function_subplots_adjust; - PyObject *s_python_function_rcparams; - PyObject *s_python_function_spy; - - /* For now, _interpreter is implemented as a singleton since its currently not possible to have - multiple independent embedded python interpreters without patching the python source code - or starting a separate process for each. [1] - Furthermore, many python objects expect that they are destructed in the same thread as they - were constructed. [2] So for advanced usage, a `kill()` function is provided so that library - users can manually ensure that the interpreter is constructed and destroyed within the - same thread. - - 1: http://bytes.com/topic/python/answers/793370-multiple-independent-python-interpreters-c-c-program - 2: https://github.com/lava/matplotlib-cpp/pull/202#issue-436220256 - */ - - static _interpreter& get() { - return interkeeper(false); - } - - static _interpreter& kill() { - return interkeeper(true); - } - - // Stores the actual singleton object referenced by `get()` and `kill()`. - static _interpreter& interkeeper(bool should_kill) { - static _interpreter ctx; - if (should_kill) - ctx.~_interpreter(); - return ctx; - } - - PyObject* safe_import(PyObject* module, std::string fname) { - PyObject* fn = PyObject_GetAttrString(module, fname.c_str()); - - if (!fn) - throw std::runtime_error(std::string("Couldn't find required function: ") + fname); - - if (!PyFunction_Check(fn)) - throw std::runtime_error(fname + std::string(" is unexpectedly not a PyFunction.")); - - return fn; - } - -private: - -#ifndef WITHOUT_NUMPY -# if PY_MAJOR_VERSION >= 3 - - void *import_numpy() { - import_array(); // initialize C-API - return NULL; - } - -# else - - void import_numpy() { - import_array(); // initialize C-API - } - -# endif -#endif - - _interpreter() { - - // optional but recommended -#if PY_MAJOR_VERSION >= 3 - wchar_t name[] = L"plotting"; -#else - char name[] = "plotting"; -#endif - Py_SetProgramName(name); - Py_Initialize(); - - wchar_t const *dummy_args[] = {L"Python", NULL}; // const is needed because literals must not be modified - wchar_t const **argv = dummy_args; - int argc = sizeof(dummy_args)/sizeof(dummy_args[0])-1; - -#if PY_MAJOR_VERSION >= 3 - PySys_SetArgv(argc, const_cast(argv)); -#else - PySys_SetArgv(argc, (char **)(argv)); -#endif - -#ifndef WITHOUT_NUMPY - import_numpy(); // initialize numpy C-API -#endif - - PyObject* matplotlibname = PyString_FromString("matplotlib"); - PyObject* pyplotname = PyString_FromString("matplotlib.pyplot"); - PyObject* cmname = PyString_FromString("matplotlib.cm"); - PyObject* pylabname = PyString_FromString("pylab"); - if (!pyplotname || !pylabname || !matplotlibname || !cmname) { - throw std::runtime_error("couldnt create string"); - } - - PyObject* matplotlib = PyImport_Import(matplotlibname); - - Py_DECREF(matplotlibname); - if (!matplotlib) { - PyErr_Print(); - throw std::runtime_error("Error loading module matplotlib!"); - } - - // matplotlib.use() must be called *before* pylab, matplotlib.pyplot, - // or matplotlib.backends is imported for the first time - if (!s_backend.empty()) { - PyObject_CallMethod(matplotlib, const_cast("use"), const_cast("s"), s_backend.c_str()); - } - - - - PyObject* pymod = PyImport_Import(pyplotname); - Py_DECREF(pyplotname); - if (!pymod) { throw std::runtime_error("Error loading module matplotlib.pyplot!"); } - - s_python_colormap = PyImport_Import(cmname); - Py_DECREF(cmname); - if (!s_python_colormap) { throw std::runtime_error("Error loading module matplotlib.cm!"); } - - PyObject* pylabmod = PyImport_Import(pylabname); - Py_DECREF(pylabname); - if (!pylabmod) { throw std::runtime_error("Error loading module pylab!"); } - - s_python_function_arrow = safe_import(pymod, "arrow"); - s_python_function_show = safe_import(pymod, "show"); - s_python_function_close = safe_import(pymod, "close"); - s_python_function_draw = safe_import(pymod, "draw"); - s_python_function_pause = safe_import(pymod, "pause"); - s_python_function_figure = safe_import(pymod, "figure"); - s_python_function_fignum_exists = safe_import(pymod, "fignum_exists"); - s_python_function_plot = safe_import(pymod, "plot"); - s_python_function_quiver = safe_import(pymod, "quiver"); - s_python_function_contour = safe_import(pymod, "contour"); - s_python_function_semilogx = safe_import(pymod, "semilogx"); - s_python_function_semilogy = safe_import(pymod, "semilogy"); - s_python_function_loglog = safe_import(pymod, "loglog"); - s_python_function_fill = safe_import(pymod, "fill"); - s_python_function_fill_between = safe_import(pymod, "fill_between"); - s_python_function_hist = safe_import(pymod,"hist"); - s_python_function_scatter = safe_import(pymod,"scatter"); - s_python_function_boxplot = safe_import(pymod,"boxplot"); - s_python_function_subplot = safe_import(pymod, "subplot"); - s_python_function_subplot2grid = safe_import(pymod, "subplot2grid"); - s_python_function_legend = safe_import(pymod, "legend"); - s_python_function_xlim = safe_import(pymod, "xlim"); - s_python_function_ylim = safe_import(pymod, "ylim"); - s_python_function_title = safe_import(pymod, "title"); - s_python_function_axis = safe_import(pymod, "axis"); - s_python_function_axhline = safe_import(pymod, "axhline"); - s_python_function_axvline = safe_import(pymod, "axvline"); - s_python_function_axvspan = safe_import(pymod, "axvspan"); - s_python_function_xlabel = safe_import(pymod, "xlabel"); - s_python_function_ylabel = safe_import(pymod, "ylabel"); - s_python_function_gca = safe_import(pymod, "gca"); - s_python_function_xticks = safe_import(pymod, "xticks"); - s_python_function_yticks = safe_import(pymod, "yticks"); - s_python_function_margins = safe_import(pymod, "margins"); - s_python_function_tick_params = safe_import(pymod, "tick_params"); - s_python_function_grid = safe_import(pymod, "grid"); - s_python_function_ion = safe_import(pymod, "ion"); - s_python_function_ginput = safe_import(pymod, "ginput"); - s_python_function_save = safe_import(pylabmod, "savefig"); - s_python_function_annotate = safe_import(pymod,"annotate"); - s_python_function_cla = safe_import(pymod, "cla"); - s_python_function_clf = safe_import(pymod, "clf"); - s_python_function_errorbar = safe_import(pymod, "errorbar"); - s_python_function_tight_layout = safe_import(pymod, "tight_layout"); - s_python_function_stem = safe_import(pymod, "stem"); - s_python_function_xkcd = safe_import(pymod, "xkcd"); - s_python_function_text = safe_import(pymod, "text"); - s_python_function_suptitle = safe_import(pymod, "suptitle"); - s_python_function_bar = safe_import(pymod,"bar"); - s_python_function_barh = safe_import(pymod, "barh"); - s_python_function_colorbar = PyObject_GetAttrString(pymod, "colorbar"); - s_python_function_subplots_adjust = safe_import(pymod,"subplots_adjust"); - s_python_function_rcparams = PyObject_GetAttrString(pymod, "rcParams"); - s_python_function_spy = PyObject_GetAttrString(pymod, "spy"); -#ifndef WITHOUT_NUMPY - s_python_function_imshow = safe_import(pymod, "imshow"); -#endif - s_python_empty_tuple = PyTuple_New(0); - } - - ~_interpreter() { - Py_Finalize(); - } -}; - -} // end namespace detail - -/// Select the backend -/// -/// **NOTE:** This must be called before the first plot command to have -/// any effect. -/// -/// Mainly useful to select the non-interactive 'Agg' backend when running -/// matplotlibcpp in headless mode, for example on a machine with no display. -/// -/// See also: https://matplotlib.org/2.0.2/api/matplotlib_configuration_api.html#matplotlib.use -inline void backend(const std::string& name) -{ - detail::s_backend = name; -} - -inline bool annotate(std::string annotation, double x, double y) -{ - detail::_interpreter::get(); - - PyObject * xy = PyTuple_New(2); - PyObject * str = PyString_FromString(annotation.c_str()); - - PyTuple_SetItem(xy,0,PyFloat_FromDouble(x)); - PyTuple_SetItem(xy,1,PyFloat_FromDouble(y)); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "xy", xy); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, str); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_annotate, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); - - return res; -} - -namespace detail { - -#ifndef WITHOUT_NUMPY -// Type selector for numpy array conversion -template struct select_npy_type { const static NPY_TYPES type = NPY_NOTYPE; }; //Default -template <> struct select_npy_type { const static NPY_TYPES type = NPY_DOUBLE; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_FLOAT; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_BOOL; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT8; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_SHORT; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT8; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_USHORT; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_ULONG; }; -template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; - -// Sanity checks; comment them out or change the numpy type below if you're compiling on -// a platform where they don't apply -static_assert(sizeof(long long) == 8); -template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; -static_assert(sizeof(unsigned long long) == 8); -template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; - -template -PyObject* get_array(const std::vector& v) -{ - npy_intp vsize = v.size(); - NPY_TYPES type = select_npy_type::type; - if (type == NPY_NOTYPE) { - size_t memsize = v.size()*sizeof(double); - double* dp = static_cast(::malloc(memsize)); - for (size_t i=0; i(varray), NPY_ARRAY_OWNDATA); - return varray; - } - - PyObject* varray = PyArray_SimpleNewFromData(1, &vsize, type, (void*)(v.data())); - return varray; -} - - -template -PyObject* get_2darray(const std::vector<::std::vector>& v) -{ - if (v.size() < 1) throw std::runtime_error("get_2d_array v too small"); - - npy_intp vsize[2] = {static_cast(v.size()), - static_cast(v[0].size())}; - - PyArrayObject *varray = - (PyArrayObject *)PyArray_SimpleNew(2, vsize, NPY_DOUBLE); - - double *vd_begin = static_cast(PyArray_DATA(varray)); - - for (const ::std::vector &v_row : v) { - if (v_row.size() != static_cast(vsize[1])) - throw std::runtime_error("Missmatched array size"); - std::copy(v_row.begin(), v_row.end(), vd_begin); - vd_begin += vsize[1]; - } - - return reinterpret_cast(varray); -} - -#else // fallback if we don't have numpy: copy every element of the given vector - -template -PyObject* get_array(const std::vector& v) -{ - PyObject* list = PyList_New(v.size()); - for(size_t i = 0; i < v.size(); ++i) { - PyList_SetItem(list, i, PyFloat_FromDouble(v.at(i))); - } - return list; -} - -#endif // WITHOUT_NUMPY - -// sometimes, for labels and such, we need string arrays -inline PyObject * get_array(const std::vector& strings) -{ - PyObject* list = PyList_New(strings.size()); - for (std::size_t i = 0; i < strings.size(); ++i) { - PyList_SetItem(list, i, PyString_FromString(strings[i].c_str())); - } - return list; -} - -// not all matplotlib need 2d arrays, some prefer lists of lists -template -PyObject* get_listlist(const std::vector>& ll) -{ - PyObject* listlist = PyList_New(ll.size()); - for (std::size_t i = 0; i < ll.size(); ++i) { - PyList_SetItem(listlist, i, get_array(ll[i])); - } - return listlist; -} - -} // namespace detail - -/// Plot a line through the given x and y data points.. -/// -/// See: https://matplotlib.org/3.2.1/api/_as_gen/matplotlib.pyplot.plot.html -template -bool plot(const std::vector &x, const std::vector &y, const std::map& keywords) -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - // using numpy arrays - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - // construct positional args - PyObject* args = PyTuple_New(2); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -// TODO - it should be possible to make this work by implementing -// a non-numpy alternative for `detail::get_2darray()`. -#ifndef WITHOUT_NUMPY -template -void plot_surface(const std::vector<::std::vector> &x, - const std::vector<::std::vector> &y, - const std::vector<::std::vector> &z, - const std::map &keywords = - std::map(), - const long fig_number=0) -{ - detail::_interpreter::get(); - - // We lazily load the modules here the first time this function is called - // because I'm not sure that we can assume "matplotlib installed" implies - // "mpl_toolkits installed" on all platforms, and we don't want to require - // it for people who don't need 3d plots. - static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; - if (!mpl_toolkitsmod) { - detail::_interpreter::get(); - - PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); - PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); - if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } - - mpl_toolkitsmod = PyImport_Import(mpl_toolkits); - Py_DECREF(mpl_toolkits); - if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } - - axis3dmod = PyImport_Import(axis3d); - Py_DECREF(axis3d); - if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } - } - - assert(x.size() == y.size()); - assert(y.size() == z.size()); - - // using numpy arrays - PyObject *xarray = detail::get_2darray(x); - PyObject *yarray = detail::get_2darray(y); - PyObject *zarray = detail::get_2darray(z); - - // construct positional args - PyObject *args = PyTuple_New(3); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - PyTuple_SetItem(args, 2, zarray); - - // Build up the kw args. - PyObject *kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "rstride", PyInt_FromLong(1)); - PyDict_SetItemString(kwargs, "cstride", PyInt_FromLong(1)); - - PyObject *python_colormap_coolwarm = PyObject_GetAttrString( - detail::_interpreter::get().s_python_colormap, "coolwarm"); - - PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm); - - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - if (it->first == "linewidth" || it->first == "alpha") { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyFloat_FromDouble(std::stod(it->second))); - } else { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - } - - PyObject *fig_args = PyTuple_New(1); - PyObject* fig = nullptr; - PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); - PyObject *fig_exists = - PyObject_CallObject( - detail::_interpreter::get().s_python_function_fignum_exists, fig_args); - if (!PyObject_IsTrue(fig_exists)) { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - detail::_interpreter::get().s_python_empty_tuple); - } else { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - fig_args); - } - Py_DECREF(fig_exists); - if (!fig) throw std::runtime_error("Call to figure() failed."); - - PyObject *gca_kwargs = PyDict_New(); - PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); - - PyObject *gca = PyObject_GetAttrString(fig, "gca"); - if (!gca) throw std::runtime_error("No gca"); - Py_INCREF(gca); - PyObject *axis = PyObject_Call( - gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); - - if (!axis) throw std::runtime_error("No axis"); - Py_INCREF(axis); - - Py_DECREF(gca); - Py_DECREF(gca_kwargs); - - PyObject *plot_surface = PyObject_GetAttrString(axis, "plot_surface"); - if (!plot_surface) throw std::runtime_error("No surface"); - Py_INCREF(plot_surface); - PyObject *res = PyObject_Call(plot_surface, args, kwargs); - if (!res) throw std::runtime_error("failed surface"); - Py_DECREF(plot_surface); - - Py_DECREF(axis); - Py_DECREF(args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); -} - -template -void contour(const std::vector<::std::vector> &x, - const std::vector<::std::vector> &y, - const std::vector<::std::vector> &z, - const std::map &keywords = {}) -{ - detail::_interpreter::get(); - - // using numpy arrays - PyObject *xarray = detail::get_2darray(x); - PyObject *yarray = detail::get_2darray(y); - PyObject *zarray = detail::get_2darray(z); - - // construct positional args - PyObject *args = PyTuple_New(3); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - PyTuple_SetItem(args, 2, zarray); - - // Build up the kw args. - PyObject *kwargs = PyDict_New(); - - PyObject *python_colormap_coolwarm = PyObject_GetAttrString( - detail::_interpreter::get().s_python_colormap, "coolwarm"); - - PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm); - - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - - PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_contour, args, kwargs); - if (!res) - throw std::runtime_error("failed contour"); - - Py_DECREF(args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); -} - -template -void spy(const std::vector<::std::vector> &x, - const double markersize = -1, // -1 for default matplotlib size - const std::map &keywords = {}) -{ - detail::_interpreter::get(); - - PyObject *xarray = detail::get_2darray(x); - - PyObject *kwargs = PyDict_New(); - if (markersize != -1) { - PyDict_SetItemString(kwargs, "markersize", PyFloat_FromDouble(markersize)); - } - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - - PyObject *plot_args = PyTuple_New(1); - PyTuple_SetItem(plot_args, 0, xarray); - - PyObject *res = PyObject_Call( - detail::_interpreter::get().s_python_function_spy, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); -} -#endif // WITHOUT_NUMPY - -template -void plot3(const std::vector &x, - const std::vector &y, - const std::vector &z, - const std::map &keywords = - std::map(), - const long fig_number=0) -{ - detail::_interpreter::get(); - - // Same as with plot_surface: We lazily load the modules here the first time - // this function is called because I'm not sure that we can assume "matplotlib - // installed" implies "mpl_toolkits installed" on all platforms, and we don't - // want to require it for people who don't need 3d plots. - static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; - if (!mpl_toolkitsmod) { - detail::_interpreter::get(); - - PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); - PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); - if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } - - mpl_toolkitsmod = PyImport_Import(mpl_toolkits); - Py_DECREF(mpl_toolkits); - if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } - - axis3dmod = PyImport_Import(axis3d); - Py_DECREF(axis3d); - if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } - } - - assert(x.size() == y.size()); - assert(y.size() == z.size()); - - PyObject *xarray = detail::get_array(x); - PyObject *yarray = detail::get_array(y); - PyObject *zarray = detail::get_array(z); - - // construct positional args - PyObject *args = PyTuple_New(3); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - PyTuple_SetItem(args, 2, zarray); - - // Build up the kw args. - PyObject *kwargs = PyDict_New(); - - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - - PyObject *fig_args = PyTuple_New(1); - PyObject* fig = nullptr; - PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); - PyObject *fig_exists = - PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, fig_args); - if (!PyObject_IsTrue(fig_exists)) { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - detail::_interpreter::get().s_python_empty_tuple); - } else { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - fig_args); - } - if (!fig) throw std::runtime_error("Call to figure() failed."); - - PyObject *gca_kwargs = PyDict_New(); - PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); - - PyObject *gca = PyObject_GetAttrString(fig, "gca"); - if (!gca) throw std::runtime_error("No gca"); - Py_INCREF(gca); - PyObject *axis = PyObject_Call( - gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); - - if (!axis) throw std::runtime_error("No axis"); - Py_INCREF(axis); - - Py_DECREF(gca); - Py_DECREF(gca_kwargs); - - PyObject *plot3 = PyObject_GetAttrString(axis, "plot"); - if (!plot3) throw std::runtime_error("No 3D line plot"); - Py_INCREF(plot3); - PyObject *res = PyObject_Call(plot3, args, kwargs); - if (!res) throw std::runtime_error("Failed 3D line plot"); - Py_DECREF(plot3); - - Py_DECREF(axis); - Py_DECREF(args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); -} - -template -bool stem(const std::vector &x, const std::vector &y, const std::map& keywords) -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - // using numpy arrays - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - // construct positional args - PyObject* args = PyTuple_New(2); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for (std::map::const_iterator it = - keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call( - detail::_interpreter::get().s_python_function_stem, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if (res) - Py_DECREF(res); - - return res; -} - -template< typename Numeric > -bool fill(const std::vector& x, const std::vector& y, const std::map& keywords) -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - // using numpy arrays - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - // construct positional args - PyObject* args = PyTuple_New(2); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if (res) Py_DECREF(res); - - return res; -} - -template< typename Numeric > -bool fill_between(const std::vector& x, const std::vector& y1, const std::vector& y2, const std::map& keywords) -{ - assert(x.size() == y1.size()); - assert(x.size() == y2.size()); - - detail::_interpreter::get(); - - // using numpy arrays - PyObject* xarray = detail::get_array(x); - PyObject* y1array = detail::get_array(y1); - PyObject* y2array = detail::get_array(y2); - - // construct positional args - PyObject* args = PyTuple_New(3); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, y1array); - PyTuple_SetItem(args, 2, y2array); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill_between, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -template -bool arrow(Numeric x, Numeric y, Numeric end_x, Numeric end_y, const std::string& fc = "r", - const std::string ec = "k", Numeric head_length = 0.25, Numeric head_width = 0.1625) { - PyObject* obj_x = PyFloat_FromDouble(x); - PyObject* obj_y = PyFloat_FromDouble(y); - PyObject* obj_end_x = PyFloat_FromDouble(end_x); - PyObject* obj_end_y = PyFloat_FromDouble(end_y); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "fc", PyString_FromString(fc.c_str())); - PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); - PyDict_SetItemString(kwargs, "head_width", PyFloat_FromDouble(head_width)); - PyDict_SetItemString(kwargs, "head_length", PyFloat_FromDouble(head_length)); - - PyObject* plot_args = PyTuple_New(4); - PyTuple_SetItem(plot_args, 0, obj_x); - PyTuple_SetItem(plot_args, 1, obj_y); - PyTuple_SetItem(plot_args, 2, obj_end_x); - PyTuple_SetItem(plot_args, 3, obj_end_y); - - PyObject* res = - PyObject_Call(detail::_interpreter::get().s_python_function_arrow, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if (res) - Py_DECREF(res); - - return res; -} - -template< typename Numeric> -bool hist(const std::vector& y, long bins=10,std::string color="b", - double alpha=1.0, bool cumulative=false) -{ - detail::_interpreter::get(); - - PyObject* yarray = detail::get_array(y); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); - PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); - PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); - PyDict_SetItemString(kwargs, "cumulative", cumulative ? Py_True : Py_False); - - PyObject* plot_args = PyTuple_New(1); - - PyTuple_SetItem(plot_args, 0, yarray); - - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); - - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -#ifndef WITHOUT_NUMPY -namespace detail { - -inline void imshow(void *ptr, const NPY_TYPES type, const int rows, const int columns, const int colors, const std::map &keywords, PyObject** out) -{ - assert(type == NPY_UINT8 || type == NPY_FLOAT); - assert(colors == 1 || colors == 3 || colors == 4); - - detail::_interpreter::get(); - - // construct args - npy_intp dims[3] = { rows, columns, colors }; - PyObject *args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyArray_SimpleNewFromData(colors == 1 ? 2 : 3, dims, type, ptr)); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_imshow, args, kwargs); - Py_DECREF(args); - Py_DECREF(kwargs); - if (!res) - throw std::runtime_error("Call to imshow() failed"); - if (out) - *out = res; - else - Py_DECREF(res); -} - -} // namespace detail - -inline void imshow(const unsigned char *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) -{ - detail::imshow((void *) ptr, NPY_UINT8, rows, columns, colors, keywords, out); -} - -inline void imshow(const float *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) -{ - detail::imshow((void *) ptr, NPY_FLOAT, rows, columns, colors, keywords, out); -} - -#ifdef WITH_OPENCV -void imshow(const cv::Mat &image, const std::map &keywords = {}) -{ - // Convert underlying type of matrix, if needed - cv::Mat image2; - NPY_TYPES npy_type = NPY_UINT8; - switch (image.type() & CV_MAT_DEPTH_MASK) { - case CV_8U: - image2 = image; - break; - case CV_32F: - image2 = image; - npy_type = NPY_FLOAT; - break; - default: - image.convertTo(image2, CV_MAKETYPE(CV_8U, image.channels())); - } - - // If color image, convert from BGR to RGB - switch (image2.channels()) { - case 3: - cv::cvtColor(image2, image2, CV_BGR2RGB); - break; - case 4: - cv::cvtColor(image2, image2, CV_BGRA2RGBA); - } - - detail::imshow(image2.data, npy_type, image2.rows, image2.cols, image2.channels(), keywords); -} -#endif // WITH_OPENCV -#endif // WITHOUT_NUMPY - -template -bool scatter(const std::vector& x, - const std::vector& y, - const double s=1.0, // The marker size in points**2 - const std::map & keywords = {}) -{ - detail::_interpreter::get(); - - assert(x.size() == y.size()); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s)); - for (const auto& it : keywords) - { - PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); - } - - PyObject* plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -template - bool scatter_colored(const std::vector& x, - const std::vector& y, - const std::vector& colors, - const double s=1.0, // The marker size in points**2 - const std::map & keywords = {}) - { - detail::_interpreter::get(); - - assert(x.size() == y.size()); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - PyObject* colors_array = detail::get_array(colors); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s)); - PyDict_SetItemString(kwargs, "c", colors_array); - - for (const auto& it : keywords) - { - PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); - } - - PyObject* plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; - } - - -template -bool scatter(const std::vector& x, - const std::vector& y, - const std::vector& z, - const double s=1.0, // The marker size in points**2 - const std::map & keywords = {}, - const long fig_number=0) { - detail::_interpreter::get(); - - // Same as with plot_surface: We lazily load the modules here the first time - // this function is called because I'm not sure that we can assume "matplotlib - // installed" implies "mpl_toolkits installed" on all platforms, and we don't - // want to require it for people who don't need 3d plots. - static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; - if (!mpl_toolkitsmod) { - detail::_interpreter::get(); - - PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); - PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); - if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } - - mpl_toolkitsmod = PyImport_Import(mpl_toolkits); - Py_DECREF(mpl_toolkits); - if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } - - axis3dmod = PyImport_Import(axis3d); - Py_DECREF(axis3d); - if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } - } - - assert(x.size() == y.size()); - assert(y.size() == z.size()); - - PyObject *xarray = detail::get_array(x); - PyObject *yarray = detail::get_array(y); - PyObject *zarray = detail::get_array(z); - - // construct positional args - PyObject *args = PyTuple_New(3); - PyTuple_SetItem(args, 0, xarray); - PyTuple_SetItem(args, 1, yarray); - PyTuple_SetItem(args, 2, zarray); - - // Build up the kw args. - PyObject *kwargs = PyDict_New(); - - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - PyObject *fig_args = PyTuple_New(1); - PyObject* fig = nullptr; - PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); - PyObject *fig_exists = - PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, fig_args); - if (!PyObject_IsTrue(fig_exists)) { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - detail::_interpreter::get().s_python_empty_tuple); - } else { - fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - fig_args); - } - Py_DECREF(fig_exists); - if (!fig) throw std::runtime_error("Call to figure() failed."); - - PyObject *gca_kwargs = PyDict_New(); - PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); - - PyObject *gca = PyObject_GetAttrString(fig, "gca"); - if (!gca) throw std::runtime_error("No gca"); - Py_INCREF(gca); - PyObject *axis = PyObject_Call( - gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); - - if (!axis) throw std::runtime_error("No axis"); - Py_INCREF(axis); - - Py_DECREF(gca); - Py_DECREF(gca_kwargs); - - PyObject *plot3 = PyObject_GetAttrString(axis, "scatter"); - if (!plot3) throw std::runtime_error("No 3D line plot"); - Py_INCREF(plot3); - PyObject *res = PyObject_Call(plot3, args, kwargs); - if (!res) throw std::runtime_error("Failed 3D line plot"); - Py_DECREF(plot3); - - Py_DECREF(axis); - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(fig); - if (res) Py_DECREF(res); - return res; - -} - -template -bool boxplot(const std::vector>& data, - const std::vector& labels = {}, - const std::map & keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* listlist = detail::get_listlist(data); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, listlist); - - PyObject* kwargs = PyDict_New(); - - // kwargs needs the labels, if there are (the correct number of) labels - if (!labels.empty() && labels.size() == data.size()) { - PyDict_SetItemString(kwargs, "labels", detail::get_array(labels)); - } - - // take care of the remaining keywords - for (const auto& it : keywords) - { - PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); - - return res; -} - -template -bool boxplot(const std::vector& data, - const std::map & keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* vector = detail::get_array(data); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, vector); - - PyObject* kwargs = PyDict_New(); - for (const auto& it : keywords) - { - PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); - - return res; -} - -template -bool bar(const std::vector & x, - const std::vector & y, - std::string ec = "black", - std::string ls = "-", - double lw = 1.0, - const std::map & keywords = {}) -{ - detail::_interpreter::get(); - - PyObject * xarray = detail::get_array(x); - PyObject * yarray = detail::get_array(y); - - PyObject * kwargs = PyDict_New(); - - PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); - PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str())); - PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw)); - - for (std::map::const_iterator it = - keywords.begin(); - it != keywords.end(); - ++it) { - PyDict_SetItemString( - kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject * plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject * res = PyObject_Call( - detail::_interpreter::get().s_python_function_bar, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); - - return res; -} - -template -bool bar(const std::vector & y, - std::string ec = "black", - std::string ls = "-", - double lw = 1.0, - const std::map & keywords = {}) -{ - using T = typename std::remove_reference::type::value_type; - - detail::_interpreter::get(); - - std::vector x; - for (std::size_t i = 0; i < y.size(); i++) { x.push_back(i); } - - return bar(x, y, ec, ls, lw, keywords); -} - - -template -bool barh(const std::vector &x, const std::vector &y, std::string ec = "black", std::string ls = "-", double lw = 1.0, const std::map &keywords = { }) { - PyObject *xarray = detail::get_array(x); - PyObject *yarray = detail::get_array(y); - - PyObject *kwargs = PyDict_New(); - - PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); - PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str())); - PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw)); - - for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject *plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_barh, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); - - return res; -} - - -inline bool subplots_adjust(const std::map& keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - for (std::map::const_iterator it = - keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyFloat_FromDouble(it->second)); - } - - - PyObject* plot_args = PyTuple_New(0); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_subplots_adjust, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -template< typename Numeric> -bool named_hist(std::string label,const std::vector& y, long bins=10, std::string color="b", double alpha=1.0) -{ - detail::_interpreter::get(); - - PyObject* yarray = detail::get_array(y); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(label.c_str())); - PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); - PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); - PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); - - - PyObject* plot_args = PyTuple_New(1); - PyTuple_SetItem(plot_args, 0, yarray); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); - - Py_DECREF(plot_args); - Py_DECREF(kwargs); - if(res) Py_DECREF(res); - - return res; -} - -template -bool plot(const std::vector& x, const std::vector& y, const std::string& s = "") -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(s.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); - - Py_DECREF(plot_args); - if(res) Py_DECREF(res); - - return res; -} - -template -bool contour(const std::vector& x, const std::vector& y, - const std::vector& z, - const std::map& keywords = {}) { - assert(x.size() == y.size() && x.size() == z.size()); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - PyObject* zarray = detail::get_array(z); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, zarray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for (std::map::const_iterator it = keywords.begin(); - it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = - PyObject_Call(detail::_interpreter::get().s_python_function_contour, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) - Py_DECREF(res); - - return res; -} - -template -bool quiver(const std::vector& x, const std::vector& y, const std::vector& u, const std::vector& w, const std::map& keywords = {}) -{ - assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - PyObject* uarray = detail::get_array(u); - PyObject* warray = detail::get_array(w); - - PyObject* plot_args = PyTuple_New(4); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, uarray); - PyTuple_SetItem(plot_args, 3, warray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call( - detail::_interpreter::get().s_python_function_quiver, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) - Py_DECREF(res); - - return res; -} - -template -bool quiver(const std::vector& x, const std::vector& y, const std::vector& z, const std::vector& u, const std::vector& w, const std::vector& v, const std::map& keywords = {}) -{ - //set up 3d axes stuff - static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; - if (!mpl_toolkitsmod) { - detail::_interpreter::get(); - - PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); - PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); - if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } - - mpl_toolkitsmod = PyImport_Import(mpl_toolkits); - Py_DECREF(mpl_toolkits); - if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } - - axis3dmod = PyImport_Import(axis3d); - Py_DECREF(axis3d); - if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } - } - - //assert sizes match up - assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size() && x.size() == z.size() && x.size() == v.size() && u.size() == v.size()); - - //set up parameters - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - PyObject* zarray = detail::get_array(z); - PyObject* uarray = detail::get_array(u); - PyObject* warray = detail::get_array(w); - PyObject* varray = detail::get_array(v); - - PyObject* plot_args = PyTuple_New(6); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, zarray); - PyTuple_SetItem(plot_args, 3, uarray); - PyTuple_SetItem(plot_args, 4, warray); - PyTuple_SetItem(plot_args, 5, varray); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - //get figure gca to enable 3d projection - PyObject *fig = - PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, - detail::_interpreter::get().s_python_empty_tuple); - if (!fig) throw std::runtime_error("Call to figure() failed."); - - PyObject *gca_kwargs = PyDict_New(); - PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); - - PyObject *gca = PyObject_GetAttrString(fig, "gca"); - if (!gca) throw std::runtime_error("No gca"); - Py_INCREF(gca); - PyObject *axis = PyObject_Call( - gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); - - if (!axis) throw std::runtime_error("No axis"); - Py_INCREF(axis); - Py_DECREF(gca); - Py_DECREF(gca_kwargs); - - //plot our boys bravely, plot them strongly, plot them with a wink and clap - PyObject *plot3 = PyObject_GetAttrString(axis, "quiver"); - if (!plot3) throw std::runtime_error("No 3D line plot"); - Py_INCREF(plot3); - PyObject* res = PyObject_Call( - plot3, plot_args, kwargs); - if (!res) throw std::runtime_error("Failed 3D plot"); - Py_DECREF(plot3); - Py_DECREF(axis); - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) - Py_DECREF(res); - - return res; -} - -template -bool stem(const std::vector& x, const std::vector& y, const std::string& s = "") -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(s.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_stem, plot_args); - - Py_DECREF(plot_args); - if (res) - Py_DECREF(res); - - return res; -} - -template -bool semilogx(const std::vector& x, const std::vector& y, const std::string& s = "") -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(s.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogx, plot_args); - - Py_DECREF(plot_args); - if(res) Py_DECREF(res); - - return res; -} - -template -bool semilogy(const std::vector& x, const std::vector& y, const std::string& s = "") -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(s.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogy, plot_args); - - Py_DECREF(plot_args); - if(res) Py_DECREF(res); - - return res; -} - -template -bool loglog(const std::vector& x, const std::vector& y, const std::string& s = "") -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(s.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_loglog, plot_args); - - Py_DECREF(plot_args); - if(res) Py_DECREF(res); - - return res; -} - -template -bool errorbar(const std::vector &x, const std::vector &y, const std::vector &yerr, const std::map &keywords = {}) -{ - assert(x.size() == y.size()); - - detail::_interpreter::get(); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - PyObject* yerrarray = detail::get_array(yerr); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyDict_SetItemString(kwargs, "yerr", yerrarray); - - PyObject *plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_errorbar, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - - if (res) - Py_DECREF(res); - else - throw std::runtime_error("Call to errorbar() failed."); - - return res; -} - -template -bool named_plot(const std::string& name, const std::vector& y, const std::string& format = "") -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(2); - - PyTuple_SetItem(plot_args, 0, yarray); - PyTuple_SetItem(plot_args, 1, pystring); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) Py_DECREF(res); - - return res; -} - -template -bool named_plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) Py_DECREF(res); - - return res; -} - -template -bool named_semilogx(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogx, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) Py_DECREF(res); - - return res; -} - -template -bool named_semilogy(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogy, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) Py_DECREF(res); - - return res; -} - -template -bool named_loglog(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") -{ - detail::_interpreter::get(); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_loglog, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - if (res) Py_DECREF(res); - - return res; -} - -template -bool plot(const std::vector& y, const std::string& format = "") -{ - std::vector x(y.size()); - for(size_t i=0; i -bool plot(const std::vector& y, const std::map& keywords) -{ - std::vector x(y.size()); - for(size_t i=0; i -bool stem(const std::vector& y, const std::string& format = "") -{ - std::vector x(y.size()); - for (size_t i = 0; i < x.size(); ++i) x.at(i) = i; - return stem(x, y, format); -} - -template -void text(Numeric x, Numeric y, const std::string& s = "") -{ - detail::_interpreter::get(); - - PyObject* args = PyTuple_New(3); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(y)); - PyTuple_SetItem(args, 2, PyString_FromString(s.c_str())); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_text, args); - if(!res) throw std::runtime_error("Call to text() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -inline void colorbar(PyObject* mappable = NULL, const std::map& keywords = {}) -{ - if (mappable == NULL) - throw std::runtime_error("Must call colorbar with PyObject* returned from an image, contour, surface, etc."); - - detail::_interpreter::get(); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, mappable); - - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(it->second)); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_colorbar, args, kwargs); - if(!res) throw std::runtime_error("Call to colorbar() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - - -inline long figure(long number = -1) -{ - detail::_interpreter::get(); - - PyObject *res; - if (number == -1) - res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple); - else { - assert(number > 0); - - // Make sure interpreter is initialised - detail::_interpreter::get(); - - PyObject *args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyLong_FromLong(number)); - res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, args); - Py_DECREF(args); - } - - if(!res) throw std::runtime_error("Call to figure() failed."); - - PyObject* num = PyObject_GetAttrString(res, "number"); - if (!num) throw std::runtime_error("Could not get number attribute of figure object"); - const long figureNumber = PyLong_AsLong(num); - - Py_DECREF(num); - Py_DECREF(res); - - return figureNumber; -} - -inline bool fignum_exists(long number) -{ - detail::_interpreter::get(); - - PyObject *args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyLong_FromLong(number)); - PyObject *res = PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, args); - if(!res) throw std::runtime_error("Call to fignum_exists() failed."); - - bool ret = PyObject_IsTrue(res); - Py_DECREF(res); - Py_DECREF(args); - - return ret; -} - -inline void figure_size(size_t w, size_t h) -{ - detail::_interpreter::get(); - - const size_t dpi = 100; - PyObject* size = PyTuple_New(2); - PyTuple_SetItem(size, 0, PyFloat_FromDouble((double)w / dpi)); - PyTuple_SetItem(size, 1, PyFloat_FromDouble((double)h / dpi)); - - PyObject* kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "figsize", size); - PyDict_SetItemString(kwargs, "dpi", PyLong_FromSize_t(dpi)); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_figure, - detail::_interpreter::get().s_python_empty_tuple, kwargs); - - Py_DECREF(kwargs); - - if(!res) throw std::runtime_error("Call to figure_size() failed."); - Py_DECREF(res); -} - -inline void legend() -{ - detail::_interpreter::get(); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple); - if(!res) throw std::runtime_error("Call to legend() failed."); - - Py_DECREF(res); -} - -inline void legend(const std::map& keywords) -{ - detail::_interpreter::get(); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple, kwargs); - if(!res) throw std::runtime_error("Call to legend() failed."); - - Py_DECREF(kwargs); - Py_DECREF(res); -} - -template -inline void set_aspect(Numeric ratio) -{ - detail::_interpreter::get(); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(ratio)); - PyObject* kwargs = PyDict_New(); - - PyObject *ax = - PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, - detail::_interpreter::get().s_python_empty_tuple); - if (!ax) throw std::runtime_error("Call to gca() failed."); - Py_INCREF(ax); - - PyObject *set_aspect = PyObject_GetAttrString(ax, "set_aspect"); - if (!set_aspect) throw std::runtime_error("Attribute set_aspect not found."); - Py_INCREF(set_aspect); - - PyObject *res = PyObject_Call(set_aspect, args, kwargs); - if (!res) throw std::runtime_error("Call to set_aspect() failed."); - Py_DECREF(set_aspect); - - Py_DECREF(ax); - Py_DECREF(args); - Py_DECREF(kwargs); -} - -inline void set_aspect_equal() -{ - // expect ratio == "equal". Leaving error handling to matplotlib. - detail::_interpreter::get(); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyString_FromString("equal")); - PyObject* kwargs = PyDict_New(); - - PyObject *ax = - PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, - detail::_interpreter::get().s_python_empty_tuple); - if (!ax) throw std::runtime_error("Call to gca() failed."); - Py_INCREF(ax); - - PyObject *set_aspect = PyObject_GetAttrString(ax, "set_aspect"); - if (!set_aspect) throw std::runtime_error("Attribute set_aspect not found."); - Py_INCREF(set_aspect); - - PyObject *res = PyObject_Call(set_aspect, args, kwargs); - if (!res) throw std::runtime_error("Call to set_aspect() failed."); - Py_DECREF(set_aspect); - - Py_DECREF(ax); - Py_DECREF(args); - Py_DECREF(kwargs); -} - -template -void ylim(Numeric left, Numeric right) -{ - detail::_interpreter::get(); - - PyObject* list = PyList_New(2); - PyList_SetItem(list, 0, PyFloat_FromDouble(left)); - PyList_SetItem(list, 1, PyFloat_FromDouble(right)); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, list); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); - if(!res) throw std::runtime_error("Call to ylim() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -template -void xlim(Numeric left, Numeric right) -{ - detail::_interpreter::get(); - - PyObject* list = PyList_New(2); - PyList_SetItem(list, 0, PyFloat_FromDouble(left)); - PyList_SetItem(list, 1, PyFloat_FromDouble(right)); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, list); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); - if(!res) throw std::runtime_error("Call to xlim() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - - -inline std::array xlim() -{ - PyObject* args = PyTuple_New(0); - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); - - if(!res) throw std::runtime_error("Call to xlim() failed."); - - Py_DECREF(res); - - PyObject* left = PyTuple_GetItem(res,0); - PyObject* right = PyTuple_GetItem(res,1); - return { PyFloat_AsDouble(left), PyFloat_AsDouble(right) }; -} - - -inline std::array ylim() -{ - PyObject* args = PyTuple_New(0); - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); - - if(!res) throw std::runtime_error("Call to ylim() failed."); - - Py_DECREF(res); - - PyObject* left = PyTuple_GetItem(res,0); - PyObject* right = PyTuple_GetItem(res,1); - return { PyFloat_AsDouble(left), PyFloat_AsDouble(right) }; -} - -template -inline void xticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) -{ - assert(labels.size() == 0 || ticks.size() == labels.size()); - - detail::_interpreter::get(); - - // using numpy array - PyObject* ticksarray = detail::get_array(ticks); - - PyObject* args; - if(labels.size() == 0) { - // construct positional args - args = PyTuple_New(1); - PyTuple_SetItem(args, 0, ticksarray); - } else { - // make tuple of tick labels - PyObject* labelstuple = PyTuple_New(labels.size()); - for (size_t i = 0; i < labels.size(); i++) - PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); - - // construct positional args - args = PyTuple_New(2); - PyTuple_SetItem(args, 0, ticksarray); - PyTuple_SetItem(args, 1, labelstuple); - } - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xticks, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if(!res) throw std::runtime_error("Call to xticks() failed"); - - Py_DECREF(res); -} - -template -inline void xticks(const std::vector &ticks, const std::map& keywords) -{ - xticks(ticks, {}, keywords); -} - -template -inline void yticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) -{ - assert(labels.size() == 0 || ticks.size() == labels.size()); - - detail::_interpreter::get(); - - // using numpy array - PyObject* ticksarray = detail::get_array(ticks); - - PyObject* args; - if(labels.size() == 0) { - // construct positional args - args = PyTuple_New(1); - PyTuple_SetItem(args, 0, ticksarray); - } else { - // make tuple of tick labels - PyObject* labelstuple = PyTuple_New(labels.size()); - for (size_t i = 0; i < labels.size(); i++) - PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); - - // construct positional args - args = PyTuple_New(2); - PyTuple_SetItem(args, 0, ticksarray); - PyTuple_SetItem(args, 1, labelstuple); - } - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_yticks, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if(!res) throw std::runtime_error("Call to yticks() failed"); - - Py_DECREF(res); -} - -template -inline void yticks(const std::vector &ticks, const std::map& keywords) -{ - yticks(ticks, {}, keywords); -} - -template inline void margins(Numeric margin) -{ - // construct positional args - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin)); - - PyObject* res = - PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); - if (!res) - throw std::runtime_error("Call to margins() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -template inline void margins(Numeric margin_x, Numeric margin_y) -{ - // construct positional args - PyObject* args = PyTuple_New(2); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin_x)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(margin_y)); - - PyObject* res = - PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); - if (!res) - throw std::runtime_error("Call to margins() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - - -inline void tick_params(const std::map& keywords, const std::string axis = "both") -{ - detail::_interpreter::get(); - - // construct positional args - PyObject* args; - args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyString_FromString(axis.c_str())); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_tick_params, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - if (!res) throw std::runtime_error("Call to tick_params() failed"); - - Py_DECREF(res); -} - -inline void subplot(long nrows, long ncols, long plot_number) -{ - detail::_interpreter::get(); - - // construct positional args - PyObject* args = PyTuple_New(3); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(nrows)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(ncols)); - PyTuple_SetItem(args, 2, PyFloat_FromDouble(plot_number)); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot, args); - if(!res) throw std::runtime_error("Call to subplot() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -inline void subplot2grid(long nrows, long ncols, long rowid=0, long colid=0, long rowspan=1, long colspan=1) -{ - detail::_interpreter::get(); - - PyObject* shape = PyTuple_New(2); - PyTuple_SetItem(shape, 0, PyLong_FromLong(nrows)); - PyTuple_SetItem(shape, 1, PyLong_FromLong(ncols)); - - PyObject* loc = PyTuple_New(2); - PyTuple_SetItem(loc, 0, PyLong_FromLong(rowid)); - PyTuple_SetItem(loc, 1, PyLong_FromLong(colid)); - - PyObject* args = PyTuple_New(4); - PyTuple_SetItem(args, 0, shape); - PyTuple_SetItem(args, 1, loc); - PyTuple_SetItem(args, 2, PyLong_FromLong(rowspan)); - PyTuple_SetItem(args, 3, PyLong_FromLong(colspan)); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot2grid, args); - if(!res) throw std::runtime_error("Call to subplot2grid() failed."); - - Py_DECREF(shape); - Py_DECREF(loc); - Py_DECREF(args); - Py_DECREF(res); -} - -inline void title(const std::string &titlestr, const std::map &keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* pytitlestr = PyString_FromString(titlestr.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pytitlestr); - - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_title, args, kwargs); - if(!res) throw std::runtime_error("Call to title() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - -inline void suptitle(const std::string &suptitlestr, const std::map &keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* pysuptitlestr = PyString_FromString(suptitlestr.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pysuptitlestr); - - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_suptitle, args, kwargs); - if(!res) throw std::runtime_error("Call to suptitle() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - -inline void axis(const std::string &axisstr) -{ - detail::_interpreter::get(); - - PyObject* str = PyString_FromString(axisstr.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, str); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_axis, args); - if(!res) throw std::runtime_error("Call to title() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -inline void axhline(double y, double xmin = 0., double xmax = 1., const std::map& keywords = std::map()) -{ - detail::_interpreter::get(); - - // construct positional args - PyObject* args = PyTuple_New(3); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(y)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmin)); - PyTuple_SetItem(args, 2, PyFloat_FromDouble(xmax)); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axhline, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); -} - -inline void axvline(double x, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) -{ - detail::_interpreter::get(); - - // construct positional args - PyObject* args = PyTuple_New(3); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(ymin)); - PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymax)); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvline, args, kwargs); - - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); -} - -inline void axvspan(double xmin, double xmax, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) -{ - // construct positional args - PyObject* args = PyTuple_New(4); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(xmin)); - PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmax)); - PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymin)); - PyTuple_SetItem(args, 3, PyFloat_FromDouble(ymax)); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - if (it->first == "linewidth" || it->first == "alpha") { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyFloat_FromDouble(std::stod(it->second))); - } else { - PyDict_SetItemString(kwargs, it->first.c_str(), - PyString_FromString(it->second.c_str())); - } - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvspan, args, kwargs); - Py_DECREF(args); - Py_DECREF(kwargs); - - if(res) Py_DECREF(res); -} - -inline void xlabel(const std::string &str, const std::map &keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* pystr = PyString_FromString(str.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pystr); - - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xlabel, args, kwargs); - if(!res) throw std::runtime_error("Call to xlabel() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - -inline void ylabel(const std::string &str, const std::map& keywords = {}) -{ - detail::_interpreter::get(); - - PyObject* pystr = PyString_FromString(str.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pystr); - - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_ylabel, args, kwargs); - if(!res) throw std::runtime_error("Call to ylabel() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - -inline void set_zlabel(const std::string &str, const std::map& keywords = {}) -{ - detail::_interpreter::get(); - - // Same as with plot_surface: We lazily load the modules here the first time - // this function is called because I'm not sure that we can assume "matplotlib - // installed" implies "mpl_toolkits installed" on all platforms, and we don't - // want to require it for people who don't need 3d plots. - static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; - if (!mpl_toolkitsmod) { - PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); - PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); - if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } - - mpl_toolkitsmod = PyImport_Import(mpl_toolkits); - Py_DECREF(mpl_toolkits); - if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } - - axis3dmod = PyImport_Import(axis3d); - Py_DECREF(axis3d); - if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } - } - - PyObject* pystr = PyString_FromString(str.c_str()); - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pystr); - - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject *ax = - PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, - detail::_interpreter::get().s_python_empty_tuple); - if (!ax) throw std::runtime_error("Call to gca() failed."); - Py_INCREF(ax); - - PyObject *zlabel = PyObject_GetAttrString(ax, "set_zlabel"); - if (!zlabel) throw std::runtime_error("Attribute set_zlabel not found."); - Py_INCREF(zlabel); - - PyObject *res = PyObject_Call(zlabel, args, kwargs); - if (!res) throw std::runtime_error("Call to set_zlabel() failed."); - Py_DECREF(zlabel); - - Py_DECREF(ax); - Py_DECREF(args); - Py_DECREF(kwargs); - if (res) Py_DECREF(res); -} - -inline void grid(bool flag) -{ - detail::_interpreter::get(); - - PyObject* pyflag = flag ? Py_True : Py_False; - Py_INCREF(pyflag); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pyflag); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_grid, args); - if(!res) throw std::runtime_error("Call to grid() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -inline void show(const bool block = true) -{ - detail::_interpreter::get(); - - PyObject* res; - if(block) - { - res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_show, - detail::_interpreter::get().s_python_empty_tuple); - } - else - { - PyObject *kwargs = PyDict_New(); - PyDict_SetItemString(kwargs, "block", Py_False); - res = PyObject_Call( detail::_interpreter::get().s_python_function_show, detail::_interpreter::get().s_python_empty_tuple, kwargs); - Py_DECREF(kwargs); - } - - - if (!res) throw std::runtime_error("Call to show() failed."); - - Py_DECREF(res); -} - -inline void close() -{ - detail::_interpreter::get(); - - PyObject* res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_close, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) throw std::runtime_error("Call to close() failed."); - - Py_DECREF(res); -} - -inline void xkcd() { - detail::_interpreter::get(); - - PyObject* res; - PyObject *kwargs = PyDict_New(); - - res = PyObject_Call(detail::_interpreter::get().s_python_function_xkcd, - detail::_interpreter::get().s_python_empty_tuple, kwargs); - - Py_DECREF(kwargs); - - if (!res) - throw std::runtime_error("Call to show() failed."); - - Py_DECREF(res); -} - -inline void draw() -{ - detail::_interpreter::get(); - - PyObject* res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_draw, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) throw std::runtime_error("Call to draw() failed."); - - Py_DECREF(res); -} - -template -inline void pause(Numeric interval) -{ - detail::_interpreter::get(); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyFloat_FromDouble(interval)); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_pause, args); - if(!res) throw std::runtime_error("Call to pause() failed."); - - Py_DECREF(args); - Py_DECREF(res); -} - -inline void save(const std::string& filename, const int dpi=0) -{ - detail::_interpreter::get(); - - PyObject* pyfilename = PyString_FromString(filename.c_str()); - - PyObject* args = PyTuple_New(1); - PyTuple_SetItem(args, 0, pyfilename); - - PyObject* kwargs = PyDict_New(); - - if(dpi > 0) - { - PyDict_SetItemString(kwargs, "dpi", PyLong_FromLong(dpi)); - } - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_save, args, kwargs); - if (!res) throw std::runtime_error("Call to save() failed."); - - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(res); -} - -inline void rcparams(const std::map& keywords = {}) { - detail::_interpreter::get(); - PyObject* args = PyTuple_New(0); - PyObject* kwargs = PyDict_New(); - for (auto it = keywords.begin(); it != keywords.end(); ++it) { - if ("text.usetex" == it->first) - PyDict_SetItemString(kwargs, it->first.c_str(), PyLong_FromLong(std::stoi(it->second.c_str()))); - else PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); - } - - PyObject * update = PyObject_GetAttrString(detail::_interpreter::get().s_python_function_rcparams, "update"); - PyObject * res = PyObject_Call(update, args, kwargs); - if(!res) throw std::runtime_error("Call to rcParams.update() failed."); - Py_DECREF(args); - Py_DECREF(kwargs); - Py_DECREF(update); - Py_DECREF(res); -} - -inline void clf() { - detail::_interpreter::get(); - - PyObject *res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_clf, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) throw std::runtime_error("Call to clf() failed."); - - Py_DECREF(res); -} - -inline void cla() { - detail::_interpreter::get(); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_cla, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) - throw std::runtime_error("Call to cla() failed."); - - Py_DECREF(res); -} - -inline void ion() { - detail::_interpreter::get(); - - PyObject *res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_ion, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) throw std::runtime_error("Call to ion() failed."); - - Py_DECREF(res); -} - -inline std::vector> ginput(const int numClicks = 1, const std::map& keywords = {}) -{ - detail::_interpreter::get(); - - PyObject *args = PyTuple_New(1); - PyTuple_SetItem(args, 0, PyLong_FromLong(numClicks)); - - // construct keyword args - PyObject* kwargs = PyDict_New(); - for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) - { - PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); - } - - PyObject* res = PyObject_Call( - detail::_interpreter::get().s_python_function_ginput, args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(args); - if (!res) throw std::runtime_error("Call to ginput() failed."); - - const size_t len = PyList_Size(res); - std::vector> out; - out.reserve(len); - for (size_t i = 0; i < len; i++) { - PyObject *current = PyList_GetItem(res, i); - std::array position; - position[0] = PyFloat_AsDouble(PyTuple_GetItem(current, 0)); - position[1] = PyFloat_AsDouble(PyTuple_GetItem(current, 1)); - out.push_back(position); - } - Py_DECREF(res); - - return out; -} - -// Actually, is there any reason not to call this automatically for every plot? -inline void tight_layout() { - detail::_interpreter::get(); - - PyObject *res = PyObject_CallObject( - detail::_interpreter::get().s_python_function_tight_layout, - detail::_interpreter::get().s_python_empty_tuple); - - if (!res) throw std::runtime_error("Call to tight_layout() failed."); - - Py_DECREF(res); -} - -// Support for variadic plot() and initializer lists: - -namespace detail { - -template -using is_function = typename std::is_function>>::type; - -template -struct is_callable_impl; - -template -struct is_callable_impl -{ - typedef is_function type; -}; // a non-object is callable iff it is a function - -template -struct is_callable_impl -{ - struct Fallback { void operator()(); }; - struct Derived : T, Fallback { }; - - template struct Check; - - template - static std::true_type test( ... ); // use a variadic function to make sure (1) it accepts everything and (2) its always the worst match - - template - static std::false_type test( Check* ); - -public: - typedef decltype(test(nullptr)) type; - typedef decltype(&Fallback::operator()) dtype; - static constexpr bool value = type::value; -}; // an object is callable iff it defines operator() - -template -struct is_callable -{ - // dispatch to is_callable_impl or is_callable_impl depending on whether T is of class type or not - typedef typename is_callable_impl::value, T>::type type; -}; - -template -struct plot_impl { }; - -template<> -struct plot_impl -{ - template - bool operator()(const IterableX& x, const IterableY& y, const std::string& format) - { - detail::_interpreter::get(); - - // 2-phase lookup for distance, begin, end - using std::distance; - using std::begin; - using std::end; - - auto xs = distance(begin(x), end(x)); - auto ys = distance(begin(y), end(y)); - assert(xs == ys && "x and y data must have the same number of elements!"); - - PyObject* xlist = PyList_New(xs); - PyObject* ylist = PyList_New(ys); - PyObject* pystring = PyString_FromString(format.c_str()); - - auto itx = begin(x), ity = begin(y); - for(size_t i = 0; i < xs; ++i) { - PyList_SetItem(xlist, i, PyFloat_FromDouble(*itx++)); - PyList_SetItem(ylist, i, PyFloat_FromDouble(*ity++)); - } - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xlist); - PyTuple_SetItem(plot_args, 1, ylist); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); - - Py_DECREF(plot_args); - if(res) Py_DECREF(res); - - return res; - } -}; - -template<> -struct plot_impl -{ - template - bool operator()(const Iterable& ticks, const Callable& f, const std::string& format) - { - if(begin(ticks) == end(ticks)) return true; - - // We could use additional meta-programming to deduce the correct element type of y, - // but all values have to be convertible to double anyways - std::vector y; - for(auto x : ticks) y.push_back(f(x)); - return plot_impl()(ticks,y,format); - } -}; - -} // end namespace detail - -// recursion stop for the above -template -bool plot() { return true; } - -template -bool plot(const A& a, const B& b, const std::string& format, Args... args) -{ - return detail::plot_impl::type>()(a,b,format) && plot(args...); -} - -/* - * This group of plot() functions is needed to support initializer lists, i.e. calling - * plot( {1,2,3,4} ) - */ -inline bool plot(const std::vector& x, const std::vector& y, const std::string& format = "") { - return plot(x,y,format); -} - -inline bool plot(const std::vector& y, const std::string& format = "") { - return plot(y,format); -} - -inline bool plot(const std::vector& x, const std::vector& y, const std::map& keywords) { - return plot(x,y,keywords); -} - -/* - * This class allows dynamic plots, ie changing the plotted data without clearing and re-plotting - */ -class Plot -{ -public: - // default initialization with plot label, some data and format - template - Plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { - detail::_interpreter::get(); - - assert(x.size() == y.size()); - - PyObject* kwargs = PyDict_New(); - if(name != "") - PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); - - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* pystring = PyString_FromString(format.c_str()); - - PyObject* plot_args = PyTuple_New(3); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - PyTuple_SetItem(plot_args, 2, pystring); - - PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); - - Py_DECREF(kwargs); - Py_DECREF(plot_args); - - if(res) - { - line= PyList_GetItem(res, 0); - - if(line) - set_data_fct = PyObject_GetAttrString(line,"set_data"); - else - Py_DECREF(line); - Py_DECREF(res); - } - } - - // shorter initialization with name or format only - // basically calls line, = plot([], []) - Plot(const std::string& name = "", const std::string& format = "") - : Plot(name, std::vector(), std::vector(), format) {} - - template - bool update(const std::vector& x, const std::vector& y) { - assert(x.size() == y.size()); - if(set_data_fct) - { - PyObject* xarray = detail::get_array(x); - PyObject* yarray = detail::get_array(y); - - PyObject* plot_args = PyTuple_New(2); - PyTuple_SetItem(plot_args, 0, xarray); - PyTuple_SetItem(plot_args, 1, yarray); - - PyObject* res = PyObject_CallObject(set_data_fct, plot_args); - if (res) Py_DECREF(res); - return res; - } - return false; - } - - // clears the plot but keep it available - bool clear() { - return update(std::vector(), std::vector()); - } - - // definitely remove this line - void remove() { - if(line) - { - auto remove_fct = PyObject_GetAttrString(line,"remove"); - PyObject* args = PyTuple_New(0); - PyObject* res = PyObject_CallObject(remove_fct, args); - if (res) Py_DECREF(res); - } - decref(); - } - - ~Plot() { - decref(); - } -private: - - void decref() { - if(line) - Py_DECREF(line); - if(set_data_fct) - Py_DECREF(set_data_fct); - } - - - PyObject* line = nullptr; - PyObject* set_data_fct = nullptr; -}; - -} // end namespace matplotlibcpp \ No newline at end of file diff --git a/blaser_ros/launch/blaser_driver.launch b/blaser_ros/launch/blaser_driver.launch deleted file mode 100644 index 6b24694..0000000 --- a/blaser_ros/launch/blaser_driver.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/blaser_ros/launch/blaser_open_serial.sh b/blaser_ros/launch/blaser_open_serial.sh deleted file mode 100644 index edb7118..0000000 --- a/blaser_ros/launch/blaser_open_serial.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/bash - -# open Blaser serial port -sudo chmod 666 /dev/ttyACM0 - -# exit gracefully by returning a status -exit 0 \ No newline at end of file diff --git a/blaser_ros/launch/bring_up_blaser.launch b/blaser_ros/launch/bring_up_blaser.launch deleted file mode 100644 index 48473ef..0000000 --- a/blaser_ros/launch/bring_up_blaser.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - \ No newline at end of file diff --git a/blaser_ros/launch/laser_detector_minia1001.launch b/blaser_ros/launch/laser_detector_minia1001.launch deleted file mode 100644 index 8e12578..0000000 --- a/blaser_ros/launch/laser_detector_minia1001.launch +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/blaser_ros/launch/laser_detector_vio.launch b/blaser_ros/launch/laser_detector_vio.launch deleted file mode 100644 index d13d5b7..0000000 --- a/blaser_ros/launch/laser_detector_vio.launch +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/blaser_ros/launch/laser_rgb_estimator.launch b/blaser_ros/launch/laser_rgb_estimator.launch deleted file mode 100644 index b5c2031..0000000 --- a/blaser_ros/launch/laser_rgb_estimator.launch +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/blaser_ros/launch/trl6_sensor_proc.launch b/blaser_ros/launch/trl6_sensor_proc.launch deleted file mode 100644 index b62e263..0000000 --- a/blaser_ros/launch/trl6_sensor_proc.launch +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/blaser_ros/launch/trl6_slam.launch b/blaser_ros/launch/trl6_slam.launch deleted file mode 100644 index ab8d41d..0000000 --- a/blaser_ros/launch/trl6_slam.launch +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/blaser_ros/matlab/numerical_diff.m b/blaser_ros/matlab/numerical_diff.m deleted file mode 100644 index 043c02d..0000000 --- a/blaser_ros/matlab/numerical_diff.m +++ /dev/null @@ -1,28 +0,0 @@ -function [] = numerical_diff(dim) -%NUMERICAL_DIFF Summary of this function goes here -% Detailed explanation goes here -axang = [0.6, 0.0, 0.8, 0.5]; -phi = axang(1:3) * axang(4); -p2 = [1; 2; 2.3]; -p1 = [1.6344; 1.7954; 1.3992]; -trans = [.1; .2; .35]; -normal = [0.3; 0.2; 1.0]; -normal = normal / norm(normal); - -[e1, J1] = p2l_so3(phi, trans, p2, p1, normal); -delta = [0 0 0]; -epsilon = 1e-11; -delta(dim) = epsilon; -[e2, J2] = p2l_so3(phi + delta, trans, p2, p1, normal); -disp("numerical diff:") -disp((e2 - e1) / epsilon); -disp("Jacobian:"); -disp(J1(dim)); - -[e3, J3] = p2l_so3(phi, trans + reshape(delta, 3, 1), p2, p1, normal); -disp("trans numerical diff:") -disp((e3 - e1) / epsilon); -disp("normal:"); -disp(-normal(dim)); - -end diff --git a/blaser_ros/matlab/numerical_diff_p2p.m b/blaser_ros/matlab/numerical_diff_p2p.m deleted file mode 100644 index 4b67e3e..0000000 --- a/blaser_ros/matlab/numerical_diff_p2p.m +++ /dev/null @@ -1,22 +0,0 @@ -function [] = numerical_diff_p2p(dim) -%NUMERICAL_DIFF Summary of this function goes here -% Detailed explanation goes here -axang = [0.6, 0.0, 0.8, 0.5]; -phi = axang(1:3) * axang(4); -p2 = [1; 2; 2.3]; -p1 = [1.6344; 1.7954; 1.3992]; -trans = [.1; .2; .35]; -normal = [0.3; 0.2; 1.0]; -normal = normal / norm(normal); - -[e1, J1] = p2p_so3(phi, trans, p2, p1); -delta = [0 0 0]; -epsilon = 1e-11; -delta(dim) = epsilon; -[e2, J2] = p2p_so3(phi + delta, trans, p2, p1); -disp("numerical diff:") -disp((e2 - e1) / epsilon); -disp("Jacobian:"); -disp(J1(:, dim)); - -end diff --git a/blaser_ros/matlab/p2l_so3.m b/blaser_ros/matlab/p2l_so3.m deleted file mode 100644 index c8dd177..0000000 --- a/blaser_ros/matlab/p2l_so3.m +++ /dev/null @@ -1,9 +0,0 @@ -function [e, J] = p2l_so3(phi, trans, dst, src, normal) -%P2L_SO3 Summary of this function goes here -% Detailed explanation goes here - axang = [reshape(phi, [1,3]) / norm(phi), norm(phi)]; - R = axang2rotm(axang); - normal = reshape(normal, [1, 3]); - e = normal * (dst - (R * src + trans)); - J = -cross(R * reshape(src, [3,1]) + trans, normal); -end \ No newline at end of file diff --git a/blaser_ros/matlab/p2p_so3.m b/blaser_ros/matlab/p2p_so3.m deleted file mode 100644 index e3c3f8b..0000000 --- a/blaser_ros/matlab/p2p_so3.m +++ /dev/null @@ -1,8 +0,0 @@ -function [e, J] = p2p_so3(phi, trans, dst, src) -%P2L_SO3 Summary of this function goes here -% Detailed explanation goes here - axang = [reshape(phi, [1,3]) / norm(phi), norm(phi)]; - R = axang2rotm(axang); - e = dst - (R * src + trans); - J = skew_sym(R * reshape(src, [3,1]) + trans); -end \ No newline at end of file diff --git a/blaser_ros/matlab/skew_sym.m b/blaser_ros/matlab/skew_sym.m deleted file mode 100644 index 68f329b..0000000 --- a/blaser_ros/matlab/skew_sym.m +++ /dev/null @@ -1,8 +0,0 @@ -function [X] = skew_sym(x) -%SKEW_SYM Summary of this function goes here -% Detailed explanation goes here -X = [ 0, -x(3), x(2); - x(3), 0, -x(1); - -x(2), x(1), 0]; -end - diff --git a/blaser_ros/package.xml b/blaser_ros/package.xml deleted file mode 100644 index ad76d73..0000000 --- a/blaser_ros/package.xml +++ /dev/null @@ -1,81 +0,0 @@ - - - blaser_ros - 0.0.0 - The blaser_ros package - - - - - dcheng - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - geometry_msgs - pcl_conversions - pcl_ros - roscpp - sensor_msgs - std_msgs - dynamic_reconfigure - - geometry_msgs - pcl_conversions - pcl_ros - roscpp - sensor_msgs - std_msgs - dynamic_reconfigure - - geometry_msgs - pcl_conversions - pcl_ros - roscpp - sensor_msgs - std_msgs - dynamic_reconfigure - - - - - - - diff --git a/blaser_ros/scripts/.ipynb_checkpoints/Untitled-checkpoint.ipynb b/blaser_ros/scripts/.ipynb_checkpoints/Untitled-checkpoint.ipynb deleted file mode 100644 index 7fec515..0000000 --- a/blaser_ros/scripts/.ipynb_checkpoints/Untitled-checkpoint.ipynb +++ /dev/null @@ -1,6 +0,0 @@ -{ - "cells": [], - "metadata": {}, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/blaser_ros/scripts/.ipynb_checkpoints/Untitled1-checkpoint.ipynb b/blaser_ros/scripts/.ipynb_checkpoints/Untitled1-checkpoint.ipynb deleted file mode 100644 index 09c3d25..0000000 --- a/blaser_ros/scripts/.ipynb_checkpoints/Untitled1-checkpoint.ipynb +++ /dev/null @@ -1,177 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [], - "source": [ - "import cv2\n", - "import numpy as np\n", - "from scipy.spatial.transform import Rotation\n", - "from math import sin, cos, radians, degrees, pi\n", - "np.set_printoptions(suppress=True)" - ] - }, - { - "cell_type": "code", - "execution_count": 58, - "metadata": {}, - "outputs": [], - "source": [ - "def skew(vector):\n", - " return np.array([[0, -vector[2], vector[1]], \n", - " [vector[2], 0, -vector[0]], \n", - " [-vector[1], vector[0], 0]])\n", - "\n", - "def evalRt(R_est, t_est, euler, t):\n", - " euler_est = Rotation.from_matrix(R_est).as_euler('xyz')\n", - " t_est = t_est.reshape(3)\n", - " for i in range(3):\n", - " if euler_est[i] > pi / 2:\n", - " euler_est[i] -= pi\n", - " euler_err = np.linalg.norm(np.minimum(np.abs(euler_est - euler), np.abs(euler - euler_est))) / np.linalg.norm(euler)\n", - " t_est = t_est / np.linalg.norm(t_est) * np.linalg.norm(t) # rescale\n", - " t_err = np.linalg.norm(np.abs(t - t_est)) / np.linalg.norm(t)\n", - " print(\"t ground truth: \", t)\n", - " print(\"t est: \",t_est)\n", - " print(\"euelr gt: \", euler)\n", - " print(\"euler est: \", euler_est)\n", - " print(\"t err: \", t_err)\n", - " print(\"euler err: \", euler_err)\n", - " print(\"\\n\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Generate 3d points and 2d pixels" - ] - }, - { - "cell_type": "code", - "execution_count": 93, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[ 0.00017365 0. -0.00001519]\n" - ] - } - ], - "source": [ - "# initialize transformation\n", - "baseline = 0.03162277 # distance from joint to camera optical center, 1cm\n", - "theta = radians(10)\n", - "euler = np.array([0, theta, 0]) # joint rotation angle in degrees\n", - "R = Rotation.from_euler('xyz', euler, degrees=False)\n", - "t = np.array([baseline * sin(theta), 0, -(baseline - baseline * cos(theta))])\n", - "T = np.zeros((4, 4))\n", - "T[:3, :3] = R.as_matrix()\n", - "T[3,3] = 1.\n", - "T[:3, 3] = t\n", - "print(t)\n", - "\n", - "# set initial points (10), x [-0.2, 0.2], y in [-0.15, .15], z in [0.1, .3]\n", - "N_PTS = 50\n", - "pt_w = np.random.random((N_PTS, 3))\n", - "pt_w[:, 0] = pt_w[:, 0] * 0.4 - 0.2\n", - "pt_w[:, 1] = pt_w[:, 1] * 0.3 - 0.15\n", - "pt_w[:, 2] = pt_w[:, 2] * 0.2 + 0.1\n", - "\n", - "pt_w_h = np.ones((N_PTS, 4)) # homogeneous coordinates\n", - "pt_w_h[:, :3] = pt_w\n", - "\n", - "# get pixels in 2d with noise and integer round up error\n", - "K = np.array([[339.4, 0, 321.9], [0, 339.7, 226.2], [0, 0, 1.]])\n", - "puv1 = (np.matmul(K, pt_w_h.T[:3, :]) / np.tile(np.matmul(K, pt_w_h.T[:3, :])[2,:], (3,1)))[:2, :].T\n", - "puv2 = (np.matmul(K, np.matmul(T, pt_w_h.T)[:3, :]) / np.tile(np.matmul(K, np.matmul(T, pt_w_h.T)[:3, :])[2, :], (3,1)))[:2,:].T\n", - "puv1_ni = np.int32(np.rint(puv1 + np.random.normal(scale=3, size=(N_PTS, 2))))\n", - "puv2_ni = np.int32(np.rint(puv2 + np.random.normal(scale=3, size=(N_PTS, 2))))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Estimate fundamental, solve for R t, and eval error rate" - ] - }, - { - "cell_type": "code", - "execution_count": 94, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "t ground truth: [ 0.00017365 0. -0.00001519]\n", - "t est: [ 0.00011085 -0.00005606 0.00012229]\n", - "euelr gt: [0. 0.17453293 0. ]\n", - "euler est: [ 0.00236088 0.16613908 -0.01244973]\n", - "t err: 0.9248080861440643\n", - "euler err: 0.08708698848396756\n", - "\n", - "\n", - "t ground truth: [ 0.00017365 0. -0.00001519]\n", - "t est: [-0.00011085 0.00005606 -0.00012229]\n", - "euelr gt: [0. 0.17453293 0. ]\n", - "euler est: [-1.27486603 -1.09307996 -2.37478036]\n", - "t err: 1.7733386602120174\n", - "euler err: 17.065783856553942\n", - "\n", - "\n" - ] - } - ], - "source": [ - "F, mask = cv2.findFundamentalMat(puv1_ni, puv2_ni, cv2.FM_8POINT)\n", - "E = K.T.dot(F).dot(K)\n", - "R1, R2, t_est = cv2.decomposeEssentialMat(E)\n", - "evalRt(R1, t_est, euler, t)\n", - "evalRt(R2, -t_est, euler, t)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "euler_err = np.array([[0.045597, 0.060830479],\n", - " [0.049696935, 0.020570586, 0.044756, 0.0260176, 0.0147433], \n", - " [0.073563, 0.0446892, 0.03898206, 0.037205022, 0.02512616],\n", - " [0.0280946, 0.04086644, 0.11912304, 0.054875145, 0.0382422190]])\n", - "t_err = np.array([[1.062793, 0.661449],\n", - " [0.864721, 0.259404678, 1.760131, 0.8736392, 1.265848], \n", - " [0.15310397, 0.0980089, 0.15720568, 0.26181809, 0.15266775],\n", - " [0.00240634, 0.018018, 0.0529681, 0.0141170, 0.00673846]])" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.9" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/blaser_ros/scripts/.ipynb_checkpoints/laser_calib_test-checkpoint.ipynb b/blaser_ros/scripts/.ipynb_checkpoints/laser_calib_test-checkpoint.ipynb deleted file mode 100644 index 2fd6442..0000000 --- a/blaser_ros/scripts/.ipynb_checkpoints/laser_calib_test-checkpoint.ipynb +++ /dev/null @@ -1,6 +0,0 @@ -{ - "cells": [], - "metadata": {}, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/blaser_ros/scripts/.ipynb_checkpoints/vis_laser_calib_result-checkpoint.ipynb b/blaser_ros/scripts/.ipynb_checkpoints/vis_laser_calib_result-checkpoint.ipynb deleted file mode 100644 index abc2e8b..0000000 --- a/blaser_ros/scripts/.ipynb_checkpoints/vis_laser_calib_result-checkpoint.ipynb +++ /dev/null @@ -1,911 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from matplotlib import pyplot as plt\n", - "import math\n", - "%matplotlib notebook\n" - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": {}, - "outputs": [], - "source": [ - "# read plane parameters and laser points\n", - "result_file = open('../calib_result.txt')\n", - "raw_data = result_file.readlines()\n", - "plane_params = np.fromstring(raw_data[1].strip(), dtype=float, sep=',')\n", - "pts = np.zeros((len(raw_data) - 3, 3))\n", - "for i in range(len(raw_data) - 3):\n", - " pts[i] = np.fromstring(raw_data[i + 3].strip(), dtype=float, sep=',')\n" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "metadata": {}, - "outputs": [], - "source": [ - "# generate plane\n", - "min_x = np.min(pts[:, 0])\n", - "max_x = np.max(pts[:, 0])\n", - "min_y = np.min(pts[:, 1])\n", - "max_y = np.max(pts[:, 1])\n", - "min_z = np.min(pts[:, 2])\n", - "max_z = np.max(pts[:, 2])\n", - "pl_xx, pl_yy = np.meshgrid(np.linspace(min_x - 0.1, max_x + 0.1),\n", - " np.linspace(min_y - 0.1, np.max(max_y + 0.1))\n", - "pl_z = (-plane_params[0] * pl_xx - plane_params[1] * pl_yy - plane_params[3]) / plane_params[2]" - ] - }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [ - { - "data": { - "application/javascript": [ - "/* Put everything inside the global mpl namespace */\n", - "window.mpl = {};\n", - "\n", - "\n", - "mpl.get_websocket_type = function() {\n", - " if (typeof(WebSocket) !== 'undefined') {\n", - " return WebSocket;\n", - " } else if (typeof(MozWebSocket) !== 'undefined') {\n", - " return MozWebSocket;\n", - " } else {\n", - " alert('Your browser does not have WebSocket support. ' +\n", - " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n", - " 'Firefox 4 and 5 are also supported but you ' +\n", - " 'have to enable WebSockets in about:config.');\n", - " };\n", - "}\n", - "\n", - "mpl.figure = function(figure_id, websocket, ondownload, parent_element) {\n", - " this.id = figure_id;\n", - "\n", - " this.ws = websocket;\n", - "\n", - " this.supports_binary = (this.ws.binaryType != undefined);\n", - "\n", - " if (!this.supports_binary) {\n", - " var warnings = document.getElementById(\"mpl-warnings\");\n", - " if (warnings) {\n", - " warnings.style.display = 'block';\n", - " warnings.textContent = (\n", - " \"This browser does not support binary websocket messages. \" +\n", - " \"Performance may be slow.\");\n", - " }\n", - " }\n", - "\n", - " this.imageObj = new Image();\n", - "\n", - " this.context = undefined;\n", - " this.message = undefined;\n", - " this.canvas = undefined;\n", - " this.rubberband_canvas = undefined;\n", - " this.rubberband_context = undefined;\n", - " this.format_dropdown = undefined;\n", - "\n", - " this.image_mode = 'full';\n", - "\n", - " this.root = $('
');\n", - " this._root_extra_style(this.root)\n", - " this.root.attr('style', 'display: inline-block');\n", - "\n", - " $(parent_element).append(this.root);\n", - "\n", - " this._init_header(this);\n", - " this._init_canvas(this);\n", - " this._init_toolbar(this);\n", - "\n", - " var fig = this;\n", - "\n", - " this.waiting = false;\n", - "\n", - " this.ws.onopen = function () {\n", - " fig.send_message(\"supports_binary\", {value: fig.supports_binary});\n", - " fig.send_message(\"send_image_mode\", {});\n", - " if (mpl.ratio != 1) {\n", - " fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.ratio});\n", - " }\n", - " fig.send_message(\"refresh\", {});\n", - " }\n", - "\n", - " this.imageObj.onload = function() {\n", - " if (fig.image_mode == 'full') {\n", - " // Full images could contain transparency (where diff images\n", - " // almost always do), so we need to clear the canvas so that\n", - " // there is no ghosting.\n", - " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n", - " }\n", - " fig.context.drawImage(fig.imageObj, 0, 0);\n", - " };\n", - "\n", - " this.imageObj.onunload = function() {\n", - " fig.ws.close();\n", - " }\n", - "\n", - " this.ws.onmessage = this._make_on_message_function(this);\n", - "\n", - " this.ondownload = ondownload;\n", - "}\n", - "\n", - "mpl.figure.prototype._init_header = function() {\n", - " var titlebar = $(\n", - " '
');\n", - " var titletext = $(\n", - " '
');\n", - " titlebar.append(titletext)\n", - " this.root.append(titlebar);\n", - " this.header = titletext[0];\n", - "}\n", - "\n", - "\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n", - "\n", - "}\n", - "\n", - "\n", - "mpl.figure.prototype._root_extra_style = function(canvas_div) {\n", - "\n", - "}\n", - "\n", - "mpl.figure.prototype._init_canvas = function() {\n", - " var fig = this;\n", - "\n", - " var canvas_div = $('
');\n", - "\n", - " canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n", - "\n", - " function canvas_keyboard_event(event) {\n", - " return fig.key_event(event, event['data']);\n", - " }\n", - "\n", - " canvas_div.keydown('key_press', canvas_keyboard_event);\n", - " canvas_div.keyup('key_release', canvas_keyboard_event);\n", - " this.canvas_div = canvas_div\n", - " this._canvas_extra_style(canvas_div)\n", - " this.root.append(canvas_div);\n", - "\n", - " var canvas = $('');\n", - " canvas.addClass('mpl-canvas');\n", - " canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n", - "\n", - " this.canvas = canvas[0];\n", - " this.context = canvas[0].getContext(\"2d\");\n", - "\n", - " var backingStore = this.context.backingStorePixelRatio ||\n", - "\tthis.context.webkitBackingStorePixelRatio ||\n", - "\tthis.context.mozBackingStorePixelRatio ||\n", - "\tthis.context.msBackingStorePixelRatio ||\n", - "\tthis.context.oBackingStorePixelRatio ||\n", - "\tthis.context.backingStorePixelRatio || 1;\n", - "\n", - " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n", - "\n", - " var rubberband = $('');\n", - " rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n", - "\n", - " var pass_mouse_events = true;\n", - "\n", - " canvas_div.resizable({\n", - " start: function(event, ui) {\n", - " pass_mouse_events = false;\n", - " },\n", - " resize: function(event, ui) {\n", - " fig.request_resize(ui.size.width, ui.size.height);\n", - " },\n", - " stop: function(event, ui) {\n", - " pass_mouse_events = true;\n", - " fig.request_resize(ui.size.width, ui.size.height);\n", - " },\n", - " });\n", - "\n", - " function mouse_event_fn(event) {\n", - " if (pass_mouse_events)\n", - " return fig.mouse_event(event, event['data']);\n", - " }\n", - "\n", - " rubberband.mousedown('button_press', mouse_event_fn);\n", - " rubberband.mouseup('button_release', mouse_event_fn);\n", - " // Throttle sequential mouse events to 1 every 20ms.\n", - " rubberband.mousemove('motion_notify', mouse_event_fn);\n", - "\n", - " rubberband.mouseenter('figure_enter', mouse_event_fn);\n", - " rubberband.mouseleave('figure_leave', mouse_event_fn);\n", - "\n", - " canvas_div.on(\"wheel\", function (event) {\n", - " event = event.originalEvent;\n", - " event['data'] = 'scroll'\n", - " if (event.deltaY < 0) {\n", - " event.step = 1;\n", - " } else {\n", - " event.step = -1;\n", - " }\n", - " mouse_event_fn(event);\n", - " });\n", - "\n", - " canvas_div.append(canvas);\n", - " canvas_div.append(rubberband);\n", - "\n", - " this.rubberband = rubberband;\n", - " this.rubberband_canvas = rubberband[0];\n", - " this.rubberband_context = rubberband[0].getContext(\"2d\");\n", - " this.rubberband_context.strokeStyle = \"#000000\";\n", - "\n", - " this._resize_canvas = function(width, height) {\n", - " // Keep the size of the canvas, canvas container, and rubber band\n", - " // canvas in synch.\n", - " canvas_div.css('width', width)\n", - " canvas_div.css('height', height)\n", - "\n", - " canvas.attr('width', width * mpl.ratio);\n", - " canvas.attr('height', height * mpl.ratio);\n", - " canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n", - "\n", - " rubberband.attr('width', width);\n", - " rubberband.attr('height', height);\n", - " }\n", - "\n", - " // Set the figure to an initial 600x600px, this will subsequently be updated\n", - " // upon first draw.\n", - " this._resize_canvas(600, 600);\n", - "\n", - " // Disable right mouse context menu.\n", - " $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\n", - " return false;\n", - " });\n", - "\n", - " function set_focus () {\n", - " canvas.focus();\n", - " canvas_div.focus();\n", - " }\n", - "\n", - " window.setTimeout(set_focus, 100);\n", - "}\n", - "\n", - "mpl.figure.prototype._init_toolbar = function() {\n", - " var fig = this;\n", - "\n", - " var nav_element = $('
');\n", - " nav_element.attr('style', 'width: 100%');\n", - " this.root.append(nav_element);\n", - "\n", - " // Define a callback function for later on.\n", - " function toolbar_event(event) {\n", - " return fig.toolbar_button_onclick(event['data']);\n", - " }\n", - " function toolbar_mouse_event(event) {\n", - " return fig.toolbar_button_onmouseover(event['data']);\n", - " }\n", - "\n", - " for(var toolbar_ind in mpl.toolbar_items) {\n", - " var name = mpl.toolbar_items[toolbar_ind][0];\n", - " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n", - " var image = mpl.toolbar_items[toolbar_ind][2];\n", - " var method_name = mpl.toolbar_items[toolbar_ind][3];\n", - "\n", - " if (!name) {\n", - " // put a spacer in here.\n", - " continue;\n", - " }\n", - " var button = $('');\n", - " button.click(method_name, toolbar_event);\n", - " button.mouseover(tooltip, toolbar_mouse_event);\n", - " nav_element.append(button);\n", - " }\n", - "\n", - " // Add the status bar.\n", - " var status_bar = $('');\n", - " nav_element.append(status_bar);\n", - " this.message = status_bar[0];\n", - "\n", - " // Add the close button to the window.\n", - " var buttongrp = $('
');\n", - " var button = $('');\n", - " button.click(function (evt) { fig.handle_close(fig, {}); } );\n", - " button.mouseover('Stop Interaction', toolbar_mouse_event);\n", - " buttongrp.append(button);\n", - " var titlebar = this.root.find($('.ui-dialog-titlebar'));\n", - " titlebar.prepend(buttongrp);\n", - "}\n", - "\n", - "mpl.figure.prototype._root_extra_style = function(el){\n", - " var fig = this\n", - " el.on(\"remove\", function(){\n", - "\tfig.close_ws(fig, {});\n", - " });\n", - "}\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function(el){\n", - " // this is important to make the div 'focusable\n", - " el.attr('tabindex', 0)\n", - " // reach out to IPython and tell the keyboard manager to turn it's self\n", - " // off when our div gets focus\n", - "\n", - " // location in version 3\n", - " if (IPython.notebook.keyboard_manager) {\n", - " IPython.notebook.keyboard_manager.register_events(el);\n", - " }\n", - " else {\n", - " // location in version 2\n", - " IPython.keyboard_manager.register_events(el);\n", - " }\n", - "\n", - "}\n", - "\n", - "mpl.figure.prototype._key_event_extra = function(event, name) {\n", - " var manager = IPython.notebook.keyboard_manager;\n", - " if (!manager)\n", - " manager = IPython.keyboard_manager;\n", - "\n", - " // Check for shift+enter\n", - " if (event.shiftKey && event.which == 13) {\n", - " this.canvas_div.blur();\n", - " // select the cell after this one\n", - " var index = IPython.notebook.find_cell_index(this.cell_info[0]);\n", - " IPython.notebook.select(index + 1);\n", - " }\n", - "}\n", - "\n", - "mpl.figure.prototype.handle_save = function(fig, msg) {\n", - " fig.ondownload(fig, null);\n", - "}\n", - "\n", - "\n", - "mpl.find_output_cell = function(html_output) {\n", - " // Return the cell and output element which can be found *uniquely* in the notebook.\n", - " // Note - this is a bit hacky, but it is done because the \"notebook_saving.Notebook\"\n", - " // IPython event is triggered only after the cells have been serialised, which for\n", - " // our purposes (turning an active figure into a static one), is too late.\n", - " var cells = IPython.notebook.get_cells();\n", - " var ncells = cells.length;\n", - " for (var i=0; i= 3 moved mimebundle to data attribute of output\n", - " data = data.data;\n", - " }\n", - " if (data['text/html'] == html_output) {\n", - " return [cell, data, j];\n", - " }\n", - " }\n", - " }\n", - " }\n", - "}\n", - "\n", - "// Register the function which deals with the matplotlib target/channel.\n", - "// The kernel may be null if the page has been refreshed.\n", - "if (IPython.notebook.kernel != null) {\n", - " IPython.notebook.kernel.comm_manager.register_target('matplotlib', mpl.mpl_figure_comm);\n", - "}\n" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "text/html": [ - "" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "euler_err = np.array([[0.049696935, 0.020570586, 0.044756, 0.0260176, 0.0147433], \n", - " [0.046620757, 0.101748, 0.0957834, 0.0514320, 0.079585],\n", - " [0.073563, 0.0446892, 0.03898206, 0.037205022, 0.02512616],\n", - " [0.047176, 0.025889, 0.0115295, 0.0872496, 0.039396811],\n", - " [0.0280946, 0.04086644, 0.11912304, 0.054875145, 0.0382422190]])\n", - "t_err = np.array([[0.864721, 0.259404678, 1.760131, 0.8736392, 1.265848], \n", - " [0.3701675, 1.0649895, 0.5555488, 0.276301, 0.86642252],\n", - " [0.15310397, 0.0980089, 0.15720568, 0.26181809, 0.15266775],\n", - " [0.04077893, 0.008541906305, 0.065378099, 0.08126958, 0.015522921],\n", - " [0.00240634, 0.018018, 0.0529681, 0.0141170, 0.00673846]])\n", - "euler_err_avr = np.mean(euler_err, axis=1)\n", - "t_err_avr = np.mean(t_err, axis=1)\n", - "baselines = np.array([0.01, 0.03162277, 0.1, 0.3162277, 1.])\n", - "plt.plot(baselines*100, euler_err_avr * 100, label='angular error')\n", - "plt.plot(baselines*100, t_err_avr * 100, label='translational error')\n", - "plt.legend()\n", - "plt.ylabel(\"error rate %\")\n", - "plt.xlabel(\"translational motion (cm)\")\n", - "plt.xscale(\"log\")\n", - "plt.show()\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.9" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/blaser_ros/scripts/im_hsv_shower.py b/blaser_ros/scripts/im_hsv_shower.py deleted file mode 100755 index 3c5590b..0000000 --- a/blaser_ros/scripts/im_hsv_shower.py +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env python3 -import cv2 -import sys -from matplotlib import pyplot as plt - -if __name__ == '__main__': - if len(sys.argv) != 2: - print("usage: python3 im_hsv_shower.py image_file") - exit(0) - im = cv2.imread(sys.argv[1]) - im_blur = cv2.medianBlur(im, 3) - im_hsv = cv2.cvtColor(im_blur, cv2.COLOR_BGR2HSV) - - f, ax = plt.subplots(1,2) - ax[0].imshow(im_hsv) - ax[1].imshow(cv2.cvtColor(im_blur, cv2.COLOR_BGR2RGB)) - plt.show() diff --git a/blaser_ros/scripts/im_saver.py b/blaser_ros/scripts/im_saver.py deleted file mode 100755 index a82d8bd..0000000 --- a/blaser_ros/scripts/im_saver.py +++ /dev/null @@ -1,34 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import cv2 -from cv_bridge import CvBridge -from sensor_msgs.msg import Image -import sys - -def image_cb(data): - global image_cnt - img = CvBridge().imgmsg_to_cv2(data, 'bgr8') - cv2.imshow('blaser image', img) - cmd = cv2.waitKey(32) - # save image if pressed 's' or space key - if cmd == ord('s') or cmd == 32: - print("Saved image no. %03d!" % image_cnt) - cv2.imwrite('img'+('%03d' % image_cnt)+'.png', img) - image_cnt += 1 - elif cmd == ord('q'): - print("Exit im_saver") - rospy.signal_shutdown("User commanded exit") - -if __name__ == '__main__': - image_cnt = 1 - rospy.init_node('im_saver') - if len(sys.argv) < 2: - print("Usage: python im_saver topic_name [starting_index]") - exit(0) - if len(sys.argv) >= 3: - image_cnt = int(sys.argv[2]) - image_topic = sys.argv[1] - rospy.Subscriber(image_topic, Image, image_cb) - print('Press "s" to save image or "q" to exit!') - rospy.spin() - diff --git a/blaser_ros/scripts/img001.png b/blaser_ros/scripts/img001.png deleted file mode 100644 index aa541e0..0000000 Binary files a/blaser_ros/scripts/img001.png and /dev/null differ diff --git a/blaser_ros/scripts/imu_driver.py b/blaser_ros/scripts/imu_driver.py deleted file mode 100755 index 89e4668..0000000 --- a/blaser_ros/scripts/imu_driver.py +++ /dev/null @@ -1,68 +0,0 @@ -#!/usr/bin/env python -import serial -from sensor_msgs.msg import Imu -import rospy -import math - -imu_pub = rospy.Publisher('/imu', Imu, queue_size = 50) -time_offset = 0 # machine time - imu time - -def imuTime2machineTime(imu_time): - return imu_time + time_offset - -def str2msg(data): - msg = Imu() - assert(time_offset != 0) - imu_values = data.rstrip().split('\t') - assert(len(imu_values) == 7) - msg.header.stamp = rospy.Time(imuTime2machineTime(float(imu_values[0]))) - msg.header.frame_id = "imu" - msg.linear_acceleration.x = float(imu_values[1]) - msg.linear_acceleration.y = float(imu_values[2]) - msg.linear_acceleration.z = float(imu_values[3]) - msg.angular_velocity.x = float(imu_values[4]) / 180 * math.pi - msg.angular_velocity.y = float(imu_values[5]) / 180 * math.pi - msg.angular_velocity.z = float(imu_values[6]) / 180 * math.pi - - return msg - -def initTimestamp(): - global time_offset - # discard frames in the beginning - ser.flushOutput() - ser.flushInput() - for i in range(50): - ser.readline() - - # do a cross time difference - num_cross_td = 1 - time_offset = 0 - for i in range(num_cross_td): - t_machine_1 = rospy.Time.now().to_sec() - data1 = ser.readline() - data2 = ser.readline() - t_machine_2 = rospy.Time.now().to_sec() - - t_imu_1 = float(data1.split('\t')[0]) - t_imu_2 = float(data2.split('\t')[0]) - - time_offset += (t_machine_1 - t_imu_1 + t_machine_2 - t_imu_2) / (2 * num_cross_td) - print("set time offset: ", time_offset) - - -def loop(): - while not rospy.is_shutdown(): - data_str = ser.readline() - msg = str2msg(data_str) - imu_pub.publish(msg) - - -if __name__ == '__main__': - try: - ser = serial.Serial('/dev/ttyACM0', 9600) - except: - ser = serial.Serial('/dev/ttyACM0', 9600) - - rospy.init_node('imu_driver') - initTimestamp() - loop() diff --git a/blaser_ros/scripts/laser_calib_test.ipynb b/blaser_ros/scripts/laser_calib_test.ipynb deleted file mode 100644 index ecbafaf..0000000 --- a/blaser_ros/scripts/laser_calib_test.ipynb +++ /dev/null @@ -1,90 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from matplotlib import pyplot as plt\n", - "from mpl_toolkits.mplot3d import axes3d, Axes3D\n", - "import math\n", - "import sys" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [], - "source": [ - "def draw_frame(ax, R, t):\n", - " axis_len = 0.1\n", - " origin = t.flatten()\n", - " end_x = (t + axis_len * R[:, 0]).flatten()\n", - " end_y = (t + axis_len * R[:, 1]).flatten()\n", - " end_z = (t + axis_len * R[:, 2]).flatten()\n", - " axes_len = 0.1\n", - " ax.plot([origin[0], end_x[0]], [origin[1], end_x[1]], [origin[2], end_x[2]],\n", - " color='red', linewidth=2)\n", - " ax.plot([origin[0], end_y[0]], [origin[1], end_y[1]], [origin[2], end_y[2]],\n", - " color='green', linewidth=2)\n", - " ax.plot([origin[0], end_z[0]], [origin[1], end_z[1]], [origin[2], end_z[2]],\n", - " color='blue', linewidth=2)" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure()\n", - "ax = fig.add_subplot(111,projection='3d')\n", - "draw_frame(ax, np.eye(3), np.zeros((3,1)))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.9" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/blaser_ros/scripts/laser_resolution_analyze.py b/blaser_ros/scripts/laser_resolution_analyze.py deleted file mode 100644 index afefd07..0000000 --- a/blaser_ros/scripts/laser_resolution_analyze.py +++ /dev/null @@ -1,157 +0,0 @@ -import numpy as np -from matplotlib import pyplot as plt -from matplotlib import cm -from math import sin, cos, pi -from scipy import signal - -im_sensor_size = [4e-3, 3e-3] - - -def calcImPlaneZ(fov): - """ - Assume sensor size is 3 x 4 mm - :param fov: fov of camera - :return: depth of image plane - """ - return im_sensor_size[0] / 2 * cos(fov / 2.) - - -def calcLaserPt(d, theta, phi): - """ - - :param d: - :param theta: - :param phi: - :return: - """ - return np.array([-d * cos(phi) * sin(theta), - -d * sin(phi), - d * cos(phi) * cos(theta)]) - - -def ptInImPlane(pt): - """ - Given 3d point in camera frame, calculate its 2d position on image plane, - i.e. 3d point with z = image plane depth. - :param pt: coordinate in 3d camera frame - """ - return -im_sensor_size[0] / 2 < pt[0] < im_sensor_size[0] / 2 \ - and -im_sensor_size[1] / 2 < pt[1] < im_sensor_size[1] / 2 - - -def calcRes(l, theta, phi, fov, d): - """ - Function to calculate resolution, defined by the projective length of a - unit-length line segment on the laser ray, given the camera's field of view - and configuration of laser. - We make the following assumptions: - 1. Camera is perfect pin-hole. - 2. laser origin has zero depth in camera frame. - :param l: baseline, distance between camera origin and laser origin - :param theta: angle between laser plane and line connecting laser and - camera origin - :param phi: elevation angle of laser ray - :param fov: field of view of camera in degrees. - :param d: distance - :return: resolution - """ - laser_origin = np.array([l, 0., 0.]) - ray1 = calcLaserPt(d, theta, phi) - ray2 = calcLaserPt(d + 0.001, theta, phi) - pt1_cam = laser_origin + ray1 - pt1_im_plane = pt1_cam[0:2] / pt1_cam[2] * calcImPlaneZ(fov) - pt2_cam = laser_origin + ray2 - pt2_im_plane = pt2_cam[0:2] / pt2_cam[2] * calcImPlaneZ(fov) - - if not (ptInImPlane(pt1_im_plane) and ptInImPlane(pt2_im_plane)): - return -1 - else: - return np.linalg.norm(pt2_im_plane - pt1_im_plane) - - -def calcResLine(l, theta, phi, fov): - """ - Calculate average resolution along a line, from 3 to 25 centimeters - :param l: - :param theta: - :param phi: - :param fov: - :return: - """ - gaussian_weights = signal.gaussian(29, std=10)[7:] - res_arr = np.zeros(22) - for i in range(22): - res = calcRes(l, theta, phi, fov, i * 0.01 + 0.03) - if res < 0: - return -1 - else: - res_arr[i] = res - avr_res = res_arr.dot(gaussian_weights) / np.sum(gaussian_weights) - return avr_res - - -def calcShpericalSectorArea(fov): - return 1 - cos(fov/2) - - -if __name__ == '__main__': - l = 0.02 - d = 0.1 - # analyze theta and fov at d = 0.1 - - thetas = np.linspace(0, pi * 4 / 9, 100) # 0 ~ 80 degrees - fovs = np.linspace(pi / 3, pi / 9 * 8, 100) # 60 ~ 160 degrees - X, Y = np.meshgrid(thetas, fovs) - Z = np.zeros((100, 100)) - for i in range(100): - for j in range(100): - res = calcResLine(l, thetas[i], 0, fovs[j]) - if res > 0: - Z[j,i] = res - else: - Z[j,i] = np.nan - - fig = plt.figure() - ax = fig.gca(projection="3d") - surf = ax.plot_surface(X / pi * 180, Y / pi * 180, Z, cmap=cm.coolwarm, - vmin=np.nanmin(Z), vmax=np.nanmax(Z)) - ax.set_xlabel("Angle") - ax.set_ylabel("FoV") - ax.set_zlabel("Resolution") - ax.set_zlim(0, 1e-5) - - # at 160 degrees, plot resolution to distance at given theta - fig2 = plt.figure() - res_30 = np.zeros(100) - res_60 = np.zeros(100) - res_80 = np.zeros(100) - d = np.linspace(0.03, 0.3, 100) - for i in range(100): - res_30[i] = calcRes(l, pi / 6, 0, 160 / 180.0 * pi, d[i]) - res_60[i] = calcRes(l, pi / 3, 0, 160 / 180.0 * pi, d[i]) - res_80[i] = calcRes(l, 80.0 / 180 * pi, 0, 160 / 180.0 * pi, d[i]) - plt.plot(d, res_30, label="30 Degrees") - plt.plot(d, res_60, label="60 Degrees") - plt.plot(d, res_80, label="80 Degrees") - gaussian_weights = signal.gaussian(29, std=10)[7:] * 2e-5 - plt.plot(np.linspace(0.03, 0.25, 22), gaussian_weights, label="Weights") - plt.ylim(0, 5e-5) - plt.xlabel("distance (m)") - plt.ylabel("resolution") - plt.legend() - - # resolutin to information - theta = pi/4 - res_45 = np.zeros(100) - info_45 = np.zeros(100) - for i in range(100): - res_45[i] = calcResLine(l, theta, 0, fovs[i]) - info_45[i] = calcShpericalSectorArea(fovs[i]) - fig3 = plt.figure() - plt.plot(fovs / pi * 180, res_45, label="Resolution") - plt.plot(fovs / pi * 180, info_45 * 1e-5, label="Visible Area") - plt.legend() - plt.ylim(0, 1e-5) - plt.xlabel("FoV (degrees)") - plt.ylabel("Scaled Value") - plt.show() diff --git a/blaser_ros/scripts/pub_cam_odom.py b/blaser_ros/scripts/pub_cam_odom.py deleted file mode 100644 index 121ec34..0000000 --- a/blaser_ros/scripts/pub_cam_odom.py +++ /dev/null @@ -1,53 +0,0 @@ -#!/usr/bin/env python -import rospy -import roslib -import tf -from nav_msgs.msg import Odometry -import sys -from sensor_msgs.msg import Image - -def im_cb(im): - listener.waitForTransform(frame1_name, world_frame_name, im.header.stamp, rospy.Duration(1.0)) - try: - (trans,rot) = listener.lookupTransform(frame1_name, world_frame_name, im.header.stamp) - except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e: - print(e) - return - print(im.header.stamp) - odom_msg = Odometry() - odom_msg.header.frame_id = "base" - odom_msg.header.stamp = im.header.stamp - odom_msg.pose.pose.position.x = trans[0] - odom_msg.pose.pose.position.y = trans[1] - odom_msg.pose.pose.position.z = trans[2] - odom_msg.pose.pose.orientation.x = rot[0] - odom_msg.pose.pose.orientation.y = rot[1] - odom_msg.pose.pose.orientation.z = rot[2] - odom_msg.pose.pose.orientation.w = rot[3] - - odom_pub.publish(odom_msg) - -frame1_name = '' -world_frame_name = '' -odom_topic = '' -camera_topic = '' -if len(sys.argv) != 5: - print("usage: python pub_cam_odom.py frame_name world_frame_name odom_topic camera_topic") - exit(0) - -frame1_name = sys.argv[1] -world_frame_name = sys.argv[2] -odom_topic = sys.argv[3] -camera_topic = sys.argv[4] - -rospy.init_node('tf2odom') - -listener = tf.TransformListener() - -odom_pub = rospy.Publisher(odom_topic, Odometry, queue_size = 20) - -listener.waitForTransform(frame1_name, world_frame_name, rospy.Time(), rospy.Duration(4.0)) - -rospy.Subscriber(camera_topic, Image, im_cb) - -rospy.spin() diff --git a/blaser_ros/scripts/static_tf_blaser_vio.py b/blaser_ros/scripts/static_tf_blaser_vio.py deleted file mode 100644 index dcfbf41..0000000 --- a/blaser_ros/scripts/static_tf_blaser_vio.py +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env python -import rospy -import tf -import time - -if __name__ == '__main__': - rospy.init_node("static_tf_publisher") - br = tf.TransformBroadcaster() - while not rospy.is_shutdown(): - br.sendTransform((0,0,0), - tf.transformations.quaternion_from_euler(0, 0, 0), - rospy.Time.now(), - 'blaser_640', - 'camera') - - time.sleep(0.001) diff --git a/blaser_ros/scripts/vis_laser_calib_result.ipynb b/blaser_ros/scripts/vis_laser_calib_result.ipynb deleted file mode 100644 index f555d8b..0000000 --- a/blaser_ros/scripts/vis_laser_calib_result.ipynb +++ /dev/null @@ -1,902 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from matplotlib import pyplot as plt\n", - "import math\n", - "%matplotlib notebook\n" - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": {}, - "outputs": [], - "source": [ - "# read plane parameters and laser points\n", - "result_file = open('../calib_result.txt')\n", - "raw_data = result_file.readlines()\n", - "plane_params = np.fromstring(raw_data[1].strip(), dtype=float, sep=',')\n", - "pts = np.zeros((len(raw_data) - 3, 3))\n", - "for i in range(len(raw_data) - 3):\n", - " pts[i] = np.fromstring(raw_data[i + 3].strip(), dtype=float, sep=',')\n" - ] - }, - { - "cell_type": "code", - "execution_count": 32, - "metadata": {}, - "outputs": [], - "source": [ - "# generate plane\n", - "min_x = np.min(pts[:, 0])\n", - "max_x = np.max(pts[:, 0])\n", - "min_y = np.min(pts[:, 1])\n", - "max_y = np.max(pts[:, 1])\n", - "min_z = np.min(pts[:, 2])\n", - "max_z = np.max(pts[:, 2])\n", - "pl_xx, pl_yy = np.meshgrid(np.linspace(min_x - 0.1, max_x + 0.1),\n", - " np.linspace(min_y - 0.1, max_y + 0.1))\n", - "pl_z = (-plane_params[0] * pl_xx - plane_params[1] * pl_yy - plane_params[3]) / plane_params[2]" - ] - }, - { - "cell_type": "code", - "execution_count": 36, - "metadata": {}, - "outputs": [ - { - "data": { - "application/javascript": [ - "/* Put everything inside the global mpl namespace */\n", - "window.mpl = {};\n", - "\n", - "\n", - "mpl.get_websocket_type = function() {\n", - " if (typeof(WebSocket) !== 'undefined') {\n", - " return WebSocket;\n", - " } else if (typeof(MozWebSocket) !== 'undefined') {\n", - " return MozWebSocket;\n", - " } else {\n", - " alert('Your browser does not have WebSocket support. ' +\n", - " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n", - " 'Firefox 4 and 5 are also supported but you ' +\n", - " 'have to enable WebSockets in about:config.');\n", - " };\n", - "}\n", - "\n", - "mpl.figure = function(figure_id, websocket, ondownload, parent_element) {\n", - " this.id = figure_id;\n", - "\n", - " this.ws = websocket;\n", - "\n", - " this.supports_binary = (this.ws.binaryType != undefined);\n", - "\n", - " if (!this.supports_binary) {\n", - " var warnings = document.getElementById(\"mpl-warnings\");\n", - " if (warnings) {\n", - " warnings.style.display = 'block';\n", - " warnings.textContent = (\n", - " \"This browser does not support binary websocket messages. \" +\n", - " \"Performance may be slow.\");\n", - " }\n", - " }\n", - "\n", - " this.imageObj = new Image();\n", - "\n", - " this.context = undefined;\n", - " this.message = undefined;\n", - " this.canvas = undefined;\n", - " this.rubberband_canvas = undefined;\n", - " this.rubberband_context = undefined;\n", - " this.format_dropdown = undefined;\n", - "\n", - " this.image_mode = 'full';\n", - "\n", - " this.root = $('
');\n", - " this._root_extra_style(this.root)\n", - " this.root.attr('style', 'display: inline-block');\n", - "\n", - " $(parent_element).append(this.root);\n", - "\n", - " this._init_header(this);\n", - " this._init_canvas(this);\n", - " this._init_toolbar(this);\n", - "\n", - " var fig = this;\n", - "\n", - " this.waiting = false;\n", - "\n", - " this.ws.onopen = function () {\n", - " fig.send_message(\"supports_binary\", {value: fig.supports_binary});\n", - " fig.send_message(\"send_image_mode\", {});\n", - " if (mpl.ratio != 1) {\n", - " fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.ratio});\n", - " }\n", - " fig.send_message(\"refresh\", {});\n", - " }\n", - "\n", - " this.imageObj.onload = function() {\n", - " if (fig.image_mode == 'full') {\n", - " // Full images could contain transparency (where diff images\n", - " // almost always do), so we need to clear the canvas so that\n", - " // there is no ghosting.\n", - " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n", - " }\n", - " fig.context.drawImage(fig.imageObj, 0, 0);\n", - " };\n", - "\n", - " this.imageObj.onunload = function() {\n", - " fig.ws.close();\n", - " }\n", - "\n", - " this.ws.onmessage = this._make_on_message_function(this);\n", - "\n", - " this.ondownload = ondownload;\n", - "}\n", - "\n", - "mpl.figure.prototype._init_header = function() {\n", - " var titlebar = $(\n", - " '
');\n", - " var titletext = $(\n", - " '
');\n", - " titlebar.append(titletext)\n", - " this.root.append(titlebar);\n", - " this.header = titletext[0];\n", - "}\n", - "\n", - "\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n", - "\n", - "}\n", - "\n", - "\n", - "mpl.figure.prototype._root_extra_style = function(canvas_div) {\n", - "\n", - "}\n", - "\n", - "mpl.figure.prototype._init_canvas = function() {\n", - " var fig = this;\n", - "\n", - " var canvas_div = $('
');\n", - "\n", - " canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n", - "\n", - " function canvas_keyboard_event(event) {\n", - " return fig.key_event(event, event['data']);\n", - " }\n", - "\n", - " canvas_div.keydown('key_press', canvas_keyboard_event);\n", - " canvas_div.keyup('key_release', canvas_keyboard_event);\n", - " this.canvas_div = canvas_div\n", - " this._canvas_extra_style(canvas_div)\n", - " this.root.append(canvas_div);\n", - "\n", - " var canvas = $('');\n", - " canvas.addClass('mpl-canvas');\n", - " canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n", - "\n", - " this.canvas = canvas[0];\n", - " this.context = canvas[0].getContext(\"2d\");\n", - "\n", - " var backingStore = this.context.backingStorePixelRatio ||\n", - "\tthis.context.webkitBackingStorePixelRatio ||\n", - "\tthis.context.mozBackingStorePixelRatio ||\n", - "\tthis.context.msBackingStorePixelRatio ||\n", - "\tthis.context.oBackingStorePixelRatio ||\n", - "\tthis.context.backingStorePixelRatio || 1;\n", - "\n", - " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n", - "\n", - " var rubberband = $('');\n", - " rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n", - "\n", - " var pass_mouse_events = true;\n", - "\n", - " canvas_div.resizable({\n", - " start: function(event, ui) {\n", - " pass_mouse_events = false;\n", - " },\n", - " resize: function(event, ui) {\n", - " fig.request_resize(ui.size.width, ui.size.height);\n", - " },\n", - " stop: function(event, ui) {\n", - " pass_mouse_events = true;\n", - " fig.request_resize(ui.size.width, ui.size.height);\n", - " },\n", - " });\n", - "\n", - " function mouse_event_fn(event) {\n", - " if (pass_mouse_events)\n", - " return fig.mouse_event(event, event['data']);\n", - " }\n", - "\n", - " rubberband.mousedown('button_press', mouse_event_fn);\n", - " rubberband.mouseup('button_release', mouse_event_fn);\n", - " // Throttle sequential mouse events to 1 every 20ms.\n", - " rubberband.mousemove('motion_notify', mouse_event_fn);\n", - "\n", - " rubberband.mouseenter('figure_enter', mouse_event_fn);\n", - " rubberband.mouseleave('figure_leave', mouse_event_fn);\n", - "\n", - " canvas_div.on(\"wheel\", function (event) {\n", - " event = event.originalEvent;\n", - " event['data'] = 'scroll'\n", - " if (event.deltaY < 0) {\n", - " event.step = 1;\n", - " } else {\n", - " event.step = -1;\n", - " }\n", - " mouse_event_fn(event);\n", - " });\n", - "\n", - " canvas_div.append(canvas);\n", - " canvas_div.append(rubberband);\n", - "\n", - " this.rubberband = rubberband;\n", - " this.rubberband_canvas = rubberband[0];\n", - " this.rubberband_context = rubberband[0].getContext(\"2d\");\n", - " this.rubberband_context.strokeStyle = \"#000000\";\n", - "\n", - " this._resize_canvas = function(width, height) {\n", - " // Keep the size of the canvas, canvas container, and rubber band\n", - " // canvas in synch.\n", - " canvas_div.css('width', width)\n", - " canvas_div.css('height', height)\n", - "\n", - " canvas.attr('width', width * mpl.ratio);\n", - " canvas.attr('height', height * mpl.ratio);\n", - " canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n", - "\n", - " rubberband.attr('width', width);\n", - " rubberband.attr('height', height);\n", - " }\n", - "\n", - " // Set the figure to an initial 600x600px, this will subsequently be updated\n", - " // upon first draw.\n", - " this._resize_canvas(600, 600);\n", - "\n", - " // Disable right mouse context menu.\n", - " $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\n", - " return false;\n", - " });\n", - "\n", - " function set_focus () {\n", - " canvas.focus();\n", - " canvas_div.focus();\n", - " }\n", - "\n", - " window.setTimeout(set_focus, 100);\n", - "}\n", - "\n", - "mpl.figure.prototype._init_toolbar = function() {\n", - " var fig = this;\n", - "\n", - " var nav_element = $('
');\n", - " nav_element.attr('style', 'width: 100%');\n", - " this.root.append(nav_element);\n", - "\n", - " // Define a callback function for later on.\n", - " function toolbar_event(event) {\n", - " return fig.toolbar_button_onclick(event['data']);\n", - " }\n", - " function toolbar_mouse_event(event) {\n", - " return fig.toolbar_button_onmouseover(event['data']);\n", - " }\n", - "\n", - " for(var toolbar_ind in mpl.toolbar_items) {\n", - " var name = mpl.toolbar_items[toolbar_ind][0];\n", - " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n", - " var image = mpl.toolbar_items[toolbar_ind][2];\n", - " var method_name = mpl.toolbar_items[toolbar_ind][3];\n", - "\n", - " if (!name) {\n", - " // put a spacer in here.\n", - " continue;\n", - " }\n", - " var button = $('